From b88612f9761601e985f8ec8db5d3b91214c39555 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 31 Oct 2021 01:03:08 +0000 Subject: [PATCH 001/273] [cron] Bump distribution date (2021-10-31) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index d1bff6ba10aa7..a638379ef4817 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 "2021-10-30" +//#define STRING_DISTRIBUTION_DATE "2021-10-31" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9e87e765d550c..a086f1797ec80 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 "2021-10-30" + #define STRING_DISTRIBUTION_DATE "2021-10-31" #endif /** From ba0b772d84bad99604b0131e2142366544370646 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 30 Oct 2021 22:43:02 -0500 Subject: [PATCH 002/273] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20linker=20error=20(?= =?UTF-8?q?transfer=5Fport=5Findex)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/sd/cardreader.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 1ab6dcc7c62eb..513d682de68ba 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -72,8 +72,8 @@ char CardReader::filename[FILENAME_LENGTH], CardReader::longFilename[LONG_FILENA IF_DISABLED(NO_SD_AUTOSTART, uint8_t CardReader::autofile_index); // = 0 -#if BOTH(HAS_MULTI_SERIAL, BINARY_FILE_TRANSFER) - serial_index_t CardReader::transfer_port_index; +#if ENABLED(BINARY_FILE_TRANSFER) + serial_index_t IF_DISABLED(HAS_MULTI_SERIAL, constexpr) CardReader::transfer_port_index; #endif // private: From efe2e79ac8e6d35e80a7d29bfd266685a82dc546 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 30 Oct 2021 23:43:19 -0500 Subject: [PATCH 003/273] =?UTF-8?q?=F0=9F=94=A8=20Help=20for=20GDB=20remot?= =?UTF-8?q?e=20debugging?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .gitignore | 6 +-- Marlin/src/pins/pins.h | 4 +- .../share/PlatformIO/debugging/launch.json | 48 +++++++++++++++++++ ini/native.ini | 18 +------ ini/stm32f1-maple.ini | 2 +- ini/stm32f4.ini | 7 +++ 6 files changed, 60 insertions(+), 25 deletions(-) create mode 100644 buildroot/share/PlatformIO/debugging/launch.json diff --git a/.gitignore b/.gitignore index bc603ba38b0d5..a83bfa4265a6a 100755 --- a/.gitignore +++ b/.gitignore @@ -27,7 +27,7 @@ bdf2u8g # OS # applet/ -*.DS_Store +.DS_Store # # Misc @@ -167,7 +167,3 @@ __pycache__ # IOLogger logs *_log.csv - -# Simulation / Native -eeprom.dat -imgui.ini diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 49d06590e9c04..40bbe6b41bee9 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -620,9 +620,9 @@ #elif MB(BTT_E3_RRF) #include "stm32f4/pins_BTT_E3_RRF.h" // STM32F4 env:BIGTREE_E3_RRF #elif MB(BTT_SKR_V2_0_REV_A) - #include "stm32f4/pins_BTT_SKR_V2_0_REV_A.h" // STM32F4 env:BIGTREE_SKR_2 env:BIGTREE_SKR_2_USB + #include "stm32f4/pins_BTT_SKR_V2_0_REV_A.h" // STM32F4 env:BIGTREE_SKR_2 env:BIGTREE_SKR_2_USB env:BIGTREE_SKR_2_USB_debug #elif MB(BTT_SKR_V2_0_REV_B) - #include "stm32f4/pins_BTT_SKR_V2_0_REV_B.h" // STM32F4 env:BIGTREE_SKR_2 env:BIGTREE_SKR_2_USB + #include "stm32f4/pins_BTT_SKR_V2_0_REV_B.h" // STM32F4 env:BIGTREE_SKR_2 env:BIGTREE_SKR_2_USB env:BIGTREE_SKR_2_USB_debug #elif MB(BTT_OCTOPUS_V1_0) #include "stm32f4/pins_BTT_OCTOPUS_V1_0.h" // STM32F4 env:BIGTREE_OCTOPUS_V1 env:BIGTREE_OCTOPUS_V1_USB #elif MB(BTT_OCTOPUS_V1_1) diff --git a/buildroot/share/PlatformIO/debugging/launch.json b/buildroot/share/PlatformIO/debugging/launch.json new file mode 100644 index 0000000000000..335c4c663e89c --- /dev/null +++ b/buildroot/share/PlatformIO/debugging/launch.json @@ -0,0 +1,48 @@ +/** + * Remote debugging on STM32 using the "Cortex Debug" extension. + * + * Copy one or more of the configurations items below into .vscode/launch.json + * to add those debug options to the PlatformIO IDE "Run & Debug" panel. + * + * Examples for BigTreeTech SKR 2 (USB) and Native Simulator. Modify for your own build. + * + * NOTE: The PlatformIO extension will remove items when regenerating launch.json. + */ +{ + "version": "0.2.0", + "configurations": [ + { + "name": "Debug STM32 (launch)", + "request": "launch", + "type": "cortex-debug", + "servertype": "openocd", + "cwd": "${workspaceRoot}", + "showDevDebugOutput": false, + "configFiles": [ "interface/stlink.cfg", "target/stm32f4x.cfg" ], + "device": "STM32F407", + "executable": ".pio/build/BIGTREE_SKR_2_USB_debug/firmware.elf", + }, + { + "name": "Debug STM32 (attach)", + "request": "attach", + "type": "cortex-debug", + "servertype": "openocd", + "cwd": "${workspaceRoot}", + "showDevDebugOutput": false, + "configFiles": [ "interface/stlink.cfg", "target/stm32f4x.cfg" ], + "device": "STM32F407", + "executable": ".pio/build/BIGTREE_SKR_2_USB_debug/firmware.elf", + }, + { + "name": "Debug Sim", + "request": "launch", + "type": "cppdbg", + "cwd": "${workspaceRoot}", + //"program": ".pio/build/simulator_linux_debug/MarlinSimulator", + //"program": ".pio/build/simulator_windows/MarlinSimulator", + "program": ".pio/build/simulator_macos_debug/MarlinSimulator", + "miDebuggerPath": "/opt/local/bin/ggdb", + "MIMode": "gdb" + } + ] +} diff --git a/ini/native.ini b/ini/native.ini index 981e93f996cf6..fe5fe3a5d05ad 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -29,10 +29,7 @@ src_filter = ${common.default_src_filter} + # # Tested with Linux (Mint 20) : gcc [9.3.0, 10.2.0]: libsdl2-dev[2.0.10], libsdl2-net-dev[2.0.1], libglm-dev[0.9.9.7, 0.9.9.8] # -# Debugging with gdb in vscode is as easy as adding the launch task as usual, but platformio -# will randomly remove your task when it recreates its tasks from a template. Add your gdb -# launch task to '~/.platformio/penv/lib/python{PYTHON_VERSION}/site-packages/platformio/ide/tpls/vscode/.vscode' -# to avoid this until platformio updates. +# For VSCode debugging see buildroot/share/PlatformIO/debugging/launch.json # [simulator_common] platform = native @@ -43,7 +40,6 @@ release_flags = -g0 -O3 -flto debug_build_flags = -fstack-protector-strong -g -g3 -ggdb lib_compat_mode = off src_filter = ${common.default_src_filter} + - lib_deps = ${common.lib_deps} MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/master.zip Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip @@ -51,7 +47,6 @@ lib_deps = ${common.lib_deps} extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/simulator.py - [simulator_linux] extends = simulator_common build_flags = ${simulator_common.build_flags} -ldl -lpthread -lSDL2 -lSDL2_net -lGL @@ -84,17 +79,6 @@ build_flags = ${simulator_linux.build_flags} ${simulator_linux.release_flags} # Use 'sudo port install mesa' to get a if no Xcode is installed. # If Xcode is installed be sure to run `xcode-select --install` first. # -# For VSCode debugging paste the block below near the top of launch.json. -# NOTE: The PlatformIO VSCode extension will remove it when regenerating launch.json. -# -# { "name": "Debug Sim", -# "type": "cppdbg", -# "request": "launch", -# "program": "${workspaceFolder}/.pio/build/simulator_macos/MarlinSimulator", -# "miDebuggerPath": "/opt/local/bin/ggdb", -# "MIMode": "gdb", -# "cwd": "${workspaceFolder}/.pio/build/simulator_macos" }, -# [simulator_macos] build_unflags = -lGL custom_verbose = 0 diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index f86bf98ebdc50..e0b4ad711a375 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -410,7 +410,7 @@ extends = common_stm32f1 board = genericSTM32F103VE build_flags = ${common_stm32f1.build_flags} -ffunction-sections -fdata-sections -nostdlib -MMD - -DMCU_STM32F103VE -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 -O0 + -DMCU_STM32F103VE -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 -DDEBUG_LEVEL=DEBUG_NONE -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DSS_TIMER=4 board_build.variant = MARLIN_F103Vx diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 3d7f4d2d02a75..850807585ff38 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -220,6 +220,7 @@ build_flags = ${stm_flash_drive.build_flags} -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 -DHSE_VALUE=8000000U -DHAL_SD_MODULE_ENABLED -DPIN_SERIAL3_RX=PD_9 -DPIN_SERIAL3_TX=PD_8 +upload_protocol = stlink # # BigTreeTech SKR V2.0 (STM32F407VGT6 ARM Cortex-M4) with USB Media Share Support @@ -230,6 +231,12 @@ extends = env:BIGTREE_SKR_2 build_flags = ${env:BIGTREE_SKR_2.build_flags} -DUSBD_USE_CDC_MSC build_unflags = ${env:BIGTREE_SKR_2.build_unflags} -DUSBD_USE_CDC +[env:BIGTREE_SKR_2_USB_debug] +platform = ${common_stm32.platform} +extends = env:BIGTREE_SKR_2_USB +build_flags = ${env:BIGTREE_SKR_2_USB.build_flags} -O0 +build_unflags = ${env:BIGTREE_SKR_2_USB.build_unflags} -Os -NDEBUG + # # BigTreeTech Octopus V1.0/1.1 / Octopus Pro V1.0 (STM32F446ZET6 ARM Cortex-M4) # From 9176dcea6ee1e449aee8f4972739268d4e97f034 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 8 Jul 2021 01:17:16 -0500 Subject: [PATCH 004/273] =?UTF-8?q?=F0=9F=93=9D=20Tweak=20EXP=20comments?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) 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 d3b59e03b862d..50330932cf879 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 @@ -294,14 +294,14 @@ #endif /** - * ----- ----- - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | PC4 (SD_DETECT) (LCD_D7) PE13 | 3 4 | PE12 (LCD_D6) - * (MOSI) PA7 | 5 6 PB2 (BTN_EN2) (LCD_D5) PE11 | 5 6 PE10 (LCD_D4) - * (SD_SS) PA4 | 7 8 | PE7 (BTN_EN1) (LCD_RS) PE9 | 7 8 | PB1 (LCD_EN) - * (SCK) PA5 | 9 10| PA6 (MISO) (BTN_ENC) PB0 | 9 10| PC5 (BEEPER) - * ----- ----- - * EXP2 EXP1 + * ------ ------ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | PC4 (SD_DETECT) (LCD_D7) PE13 | 3 4 | PE12 (LCD_D6) + * (MOSI) PA7 | 5 6 PB2 (BTN_EN2) (LCD_D5) PE11 | 5 6 PE10 (LCD_D4) + * (SD_SS) PA4 | 7 8 | PE7 (BTN_EN1) (LCD_RS) PE9 | 7 8 | PB1 (LCD_EN) + * (SCK) PA5 | 9 10 | PA6 (MISO) (BTN_ENC) PB0 | 9 10 | PC5 (BEEPER) + * ------ ------ + * EXP2 EXP1 */ #define EXP1_03_PIN PE13 #define EXP1_04_PIN PE12 From 5e9b5bb4482bdc4e600c2d0302faca29d6487b42 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 1 Nov 2021 01:03:28 +0000 Subject: [PATCH 005/273] [cron] Bump distribution date (2021-11-01) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index a638379ef4817..1eb431186e8fb 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 "2021-10-31" +//#define STRING_DISTRIBUTION_DATE "2021-11-01" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a086f1797ec80..aef8d8b60b530 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 "2021-10-31" + #define STRING_DISTRIBUTION_DATE "2021-11-01" #endif /** From 296a6137cd06ce06f062767ab1b59f99ee95a094 Mon Sep 17 00:00:00 2001 From: tombrazier <68918209+tombrazier@users.noreply.github.com> Date: Mon, 1 Nov 2021 23:03:50 +0000 Subject: [PATCH 006/273] =?UTF-8?q?=F0=9F=9A=B8=20More=20flexible=20Probe?= =?UTF-8?q?=20Temperature=20Compensation=20(#23033)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 100 +++--- Marlin/src/feature/probe_temp_comp.cpp | 86 ++--- Marlin/src/feature/probe_temp_comp.h | 118 ++---- Marlin/src/gcode/bedlevel/abl/G29.cpp | 10 +- Marlin/src/gcode/calibrate/G76_M192_M871.cpp | 358 ------------------- Marlin/src/gcode/calibrate/G76_M871.cpp | 337 +++++++++++++++++ Marlin/src/gcode/gcode.cpp | 9 +- Marlin/src/gcode/gcode.h | 57 ++- Marlin/src/gcode/temp/M192.cpp | 56 +++ Marlin/src/inc/Conditionals_adv.h | 14 + Marlin/src/inc/SanityCheck.h | 78 ++-- Marlin/src/module/settings.cpp | 54 ++- buildroot/tests/rambo | 8 +- ini/features.ini | 9 +- platformio.ini | 3 +- 15 files changed, 673 insertions(+), 624 deletions(-) delete mode 100644 Marlin/src/gcode/calibrate/G76_M192_M871.cpp create mode 100644 Marlin/src/gcode/calibrate/G76_M871.cpp create mode 100644 Marlin/src/gcode/temp/M192.cpp diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 4efab8193c7b2..aa6fffd44ec92 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1988,65 +1988,69 @@ /** * Thermal Probe Compensation - * Probe measurements are adjusted to compensate for temperature distortion. - * Use G76 to calibrate this feature. Use M871 to set values manually. - * For a more detailed explanation of the process see G76_M871.cpp. + * + * Adjust probe measurements to compensate for distortion associated with the temperature + * of the probe, bed, and/or hotend. + * Use G76 to automatically calibrate this feature for probe and bed temperatures. + * (Extruder temperature/offset values must be calibrated manually.) + * Use M871 to set temperature/offset values manually. + * For more details see https://marlinfw.org/docs/features/probe_temp_compensation.html */ -#if HAS_BED_PROBE && TEMP_SENSOR_PROBE && TEMP_SENSOR_BED - // Enable thermal first layer compensation using bed and probe temperatures - #define PROBE_TEMP_COMPENSATION +//#define PTC_PROBE // Compensate based on probe temperature +//#define PTC_BED // Compensate based on bed temperature +//#define PTC_HOTEND // Compensate based on hotend temperature + +#if ANY(PTC_PROBE, PTC_BED, PTC_HOTEND) + /** + * If the probe is outside the defined range, use linear extrapolation with the closest + * point and the point with index PTC_LINEAR_EXTRAPOLATION. e.g., If set to 4 it will use the + * linear extrapolation between data[0] and data[4] for values below PTC_PROBE_START. + */ + //#define PTC_LINEAR_EXTRAPOLATION 4 + + #if ENABLED(PTC_PROBE) + // Probe temperature calibration generates a table of values starting at PTC_PROBE_START + // (e.g., 30), in steps of PTC_PROBE_RES (e.g., 5) with PTC_PROBE_COUNT (e.g., 10) samples. + #define PTC_PROBE_START 30 // (°C) + #define PTC_PROBE_RES 5 // (°C) + #define PTC_PROBE_COUNT 10 + #define PTC_PROBE_ZOFFS { 0 } // (µm) Z adjustments per sample + #endif + + #if ENABLED(PTC_BED) + // Bed temperature calibration builds a similar table. + #define PTC_BED_START 60 // (°C) + #define PTC_BED_RES 5 // (°C) + #define PTC_BED_COUNT 10 + #define PTC_BED_ZOFFS { 0 } // (µm) Z adjustments per sample + #endif + + #if ENABLED(PTC_HOTEND) + // Note: There is no automatic calibration for the hotend. Use M871. + #define PTC_HOTEND_START 180 // (°C) + #define PTC_HOTEND_RES 5 // (°C) + #define PTC_HOTEND_COUNT 20 + #define PTC_HOTEND_ZOFFS { 0 } // (µm) Z adjustments per sample + #endif - // Add additional compensation depending on hotend temperature - // Note: this values cannot be calibrated and have to be set manually - #if ENABLED(PROBE_TEMP_COMPENSATION) + // G76 options + #if BOTH(PTC_PROBE, PTC_BED) // Park position to wait for probe cooldown #define PTC_PARK_POS { 0, 0, 100 } // Probe position to probe and wait for probe to reach target temperature + //#define PTC_PROBE_POS { 12.0f, 7.3f } // Example: MK52 magnetic heatbed #define PTC_PROBE_POS { 90, 100 } - // Enable additional compensation using hotend temperature - // Note: this values cannot be calibrated automatically but have to be set manually via M871. - //#define USE_TEMP_EXT_COMPENSATION - - // Probe temperature calibration generates a table of values starting at PTC_SAMPLE_START - // (e.g., 30), in steps of PTC_SAMPLE_RES (e.g., 5) with PTC_SAMPLE_COUNT (e.g., 10) samples. - - //#define PTC_SAMPLE_START 30 // (°C) - //#define PTC_SAMPLE_RES 5 // (°C) - //#define PTC_SAMPLE_COUNT 10 - - // Bed temperature calibration builds a similar table. - - //#define BTC_SAMPLE_START 60 // (°C) - //#define BTC_SAMPLE_RES 5 // (°C) - //#define BTC_SAMPLE_COUNT 10 - - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - //#define ETC_SAMPLE_START 180 // (°C) - //#define ETC_SAMPLE_RES 5 // (°C) - //#define ETC_SAMPLE_COUNT 20 - #endif - - // The temperature the probe should be at while taking measurements during bed temperature - // calibration. - //#define BTC_PROBE_TEMP 30 // (°C) + // The temperature the probe should be at while taking measurements during + // bed temperature calibration. + #define PTC_PROBE_TEMP 30 // (°C) // Height above Z=0.0 to raise the nozzle. Lowering this can help the probe to heat faster. - // Note: the Z=0.0 offset is determined by the probe offset which can be set using M851. - //#define PTC_PROBE_HEATING_OFFSET 0.5 - - // Height to raise the Z-probe between heating and taking the next measurement. Some probes - // may fail to untrigger if they have been triggered for a long time, which can be solved by - // increasing the height the probe is raised to. - //#define PTC_PROBE_RAISE 15 - - // If the probe is outside of the defined range, use linear extrapolation using the closest - // point and the PTC_LINEAR_EXTRAPOLATION'th next point. E.g. if set to 4 it will use data[0] - // and data[4] to perform linear extrapolation for values below PTC_SAMPLE_START. - //#define PTC_LINEAR_EXTRAPOLATION 4 + // Note: The Z=0.0 offset is determined by the probe Z offset (e.g., as set with M851 Z). + #define PTC_PROBE_HEATING_OFFSET 0.5 #endif -#endif +#endif // PTC_PROBE || PTC_BED || PTC_HOTEND // @section extras diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index 5f3bc985e63d2..9a975d6763fae 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -22,39 +22,53 @@ #include "../inc/MarlinConfigPre.h" -#if ENABLED(PROBE_TEMP_COMPENSATION) +#if HAS_PTC //#define DEBUG_PTC // Print extra debug output with 'M871' #include "probe_temp_comp.h" #include -ProbeTempComp temp_comp; +ProbeTempComp ptc; -int16_t ProbeTempComp::z_offsets_probe[cali_info_init[TSI_PROBE].measurements], // = {0} - ProbeTempComp::z_offsets_bed[cali_info_init[TSI_BED].measurements]; // = {0} +#if ENABLED(PTC_PROBE) + constexpr int16_t z_offsets_probe_default[PTC_PROBE_COUNT] = PTC_PROBE_ZOFFS; + int16_t ProbeTempComp::z_offsets_probe[PTC_PROBE_COUNT] = PTC_PROBE_ZOFFS; +#endif -#if ENABLED(USE_TEMP_EXT_COMPENSATION) - int16_t ProbeTempComp::z_offsets_ext[cali_info_init[TSI_EXT].measurements]; // = {0} +#if ENABLED(PTC_BED) + constexpr int16_t z_offsets_bed_default[PTC_BED_COUNT] = PTC_BED_ZOFFS; + int16_t ProbeTempComp::z_offsets_bed[PTC_BED_COUNT] = PTC_BED_ZOFFS; #endif -int16_t *ProbeTempComp::sensor_z_offsets[TSI_COUNT] = { - ProbeTempComp::z_offsets_probe, ProbeTempComp::z_offsets_bed - OPTARG(USE_TEMP_EXT_COMPENSATION, ProbeTempComp::z_offsets_ext) -}; +#if ENABLED(PTC_HOTEND) + constexpr int16_t z_offsets_hotend_default[PTC_HOTEND_COUNT] = PTC_HOTEND_ZOFFS; + int16_t ProbeTempComp::z_offsets_hotend[PTC_HOTEND_COUNT] = PTC_HOTEND_ZOFFS; +#endif -const temp_calib_t ProbeTempComp::cali_info[TSI_COUNT] = { - cali_info_init[TSI_PROBE], cali_info_init[TSI_BED] - OPTARG(USE_TEMP_EXT_COMPENSATION, cali_info_init[TSI_EXT]) +int16_t *ProbeTempComp::sensor_z_offsets[TSI_COUNT] = { + #if ENABLED(PTC_PROBE) + ProbeTempComp::z_offsets_probe, + #endif + #if ENABLED(PTC_BED) + ProbeTempComp::z_offsets_bed, + #endif + #if ENABLED(PTC_HOTEND) + ProbeTempComp::z_offsets_hotend, + #endif }; -constexpr xyz_pos_t ProbeTempComp::park_point; -constexpr xy_pos_t ProbeTempComp::measure_point; -constexpr celsius_t ProbeTempComp::probe_calib_bed_temp; +constexpr temp_calib_t ProbeTempComp::cali_info[TSI_COUNT]; uint8_t ProbeTempComp::calib_idx; // = 0 float ProbeTempComp::init_measurement; // = 0.0 +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]); +} + void ProbeTempComp::clear_offsets(const TempSensorID tsi) { LOOP_L_N(i, cali_info[tsi].measurements) sensor_z_offsets[tsi][i] = 0; @@ -71,10 +85,9 @@ void ProbeTempComp::print_offsets() { LOOP_L_N(s, TSI_COUNT) { celsius_t temp = cali_info[s].start_temp; for (int16_t i = -1; i < cali_info[s].measurements; ++i) { - SERIAL_ECHOF(s == TSI_BED ? F("Bed") : - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - s == TSI_EXT ? F("Extruder") : - #endif + SERIAL_ECHOF( + TERN_(PTC_BED, s == TSI_BED ? F("Bed") :) + TERN_(PTC_HOTEND, s == TSI_EXT ? F("Extruder") :) F("Probe") ); SERIAL_ECHOLNPGM( @@ -100,21 +113,13 @@ void ProbeTempComp::prepare_new_calibration(const_float_t init_meas_z) { } void ProbeTempComp::push_back_new_measurement(const TempSensorID tsi, const_float_t meas_z) { - switch (tsi) { - case TSI_PROBE: - case TSI_BED: - //case TSI_EXT: - if (calib_idx >= cali_info[tsi].measurements) return; - sensor_z_offsets[tsi][calib_idx++] = static_cast(meas_z * 1000.0f - init_measurement * 1000.0f); - default: break; - } + if (calib_idx >= cali_info[tsi].measurements) return; + sensor_z_offsets[tsi][calib_idx++] = static_cast((meas_z - init_measurement) * 1000.0f); } bool ProbeTempComp::finish_calibration(const TempSensorID tsi) { - if (tsi != TSI_PROBE && tsi != TSI_BED) return false; - - if (calib_idx < 3) { - SERIAL_ECHOLNPGM("!Insufficient measurements (min. 3)."); + if (!calib_idx) { + SERIAL_ECHOLNPGM("!No measurements."); clear_offsets(tsi); return false; } @@ -130,16 +135,15 @@ bool ProbeTempComp::finish_calibration(const TempSensorID tsi) { SERIAL_ECHOLNPGM("Got ", calib_idx, " measurements. "); if (linear_regression(tsi, k, d)) { SERIAL_ECHOPGM("Applying linear extrapolation"); - calib_idx--; for (; calib_idx < measurements; ++calib_idx) { - const celsius_float_t temp = start_temp + float(calib_idx) * res_temp; + const celsius_float_t temp = start_temp + float(calib_idx + 1) * res_temp; data[calib_idx] = static_cast(k * temp + d); } } else { // Simply use the last measured value for higher temperatures SERIAL_ECHOPGM("Failed to extrapolate"); - const int16_t last_val = data[calib_idx]; + const int16_t last_val = data[calib_idx-1]; for (; calib_idx < measurements; ++calib_idx) data[calib_idx] = last_val; } @@ -157,7 +161,7 @@ bool ProbeTempComp::finish_calibration(const TempSensorID tsi) { // Restrict the max. offset difference between two probings if (calib_idx > 0 && ABS(data[calib_idx - 1] - data[calib_idx]) > 800) { SERIAL_ECHOLNPGM("!Invalid Z-offset between two probings detected (0-0.8)."); - clear_offsets(TSI_PROBE); + clear_offsets(tsi); return false; } } @@ -168,8 +172,8 @@ bool ProbeTempComp::finish_calibration(const TempSensorID tsi) { void ProbeTempComp::compensate_measurement(const TempSensorID tsi, const celsius_t temp, float &meas_z) { const uint8_t measurements = cali_info[tsi].measurements; const celsius_t start_temp = cali_info[tsi].start_temp, - end_temp = cali_info[tsi].end_temp, - res_temp = cali_info[tsi].temp_resolution; + res_temp = cali_info[tsi].temp_resolution, + end_temp = start_temp + measurements * res_temp; const int16_t * const data = sensor_z_offsets[tsi]; // Given a data index, return { celsius, zoffset } in the form { x, y } @@ -208,9 +212,7 @@ void ProbeTempComp::compensate_measurement(const TempSensorID tsi, const celsius } bool ProbeTempComp::linear_regression(const TempSensorID tsi, float &k, float &d) { - if (tsi != TSI_PROBE && tsi != TSI_BED) return false; - - if (!WITHIN(calib_idx, 2, cali_info[tsi].measurements)) return false; + if (!WITHIN(calib_idx, 1, cali_info[tsi].measurements)) return false; const celsius_t start_temp = cali_info[tsi].start_temp, res_temp = cali_info[tsi].temp_resolution; @@ -243,4 +245,4 @@ bool ProbeTempComp::linear_regression(const TempSensorID tsi, float &k, float &d return true; } -#endif // PROBE_TEMP_COMPENSATION +#endif // HAS_PTC diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h index e5d459b8e8e46..4579f2187cd41 100644 --- a/Marlin/src/feature/probe_temp_comp.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -24,9 +24,13 @@ #include "../inc/MarlinConfig.h" enum TempSensorID : uint8_t { - TSI_PROBE, - TSI_BED, - #if ENABLED(USE_TEMP_EXT_COMPENSATION) + #if ENABLED(PTC_PROBE) + TSI_PROBE, + #endif + #if ENABLED(PTC_BED) + TSI_BED, + #endif + #if ENABLED(PTC_HOTEND) TSI_EXT, #endif TSI_COUNT @@ -35,8 +39,7 @@ enum TempSensorID : uint8_t { typedef struct { uint8_t measurements; // Max. number of measurements to be stored (35 - 80°C) celsius_t temp_resolution, // Resolution in °C between measurements - start_temp, // Base measurement; z-offset == 0 - end_temp; + start_temp; // Base measurement; z-offset == 0 } temp_calib_t; /** @@ -45,93 +48,40 @@ typedef struct { * measurement errors/shifts due to changed temperature. */ -// Probe temperature calibration constants -#ifndef PTC_SAMPLE_COUNT - #define PTC_SAMPLE_COUNT 10 -#endif -#ifndef PTC_SAMPLE_RES - #define PTC_SAMPLE_RES 5 -#endif -#ifndef PTC_SAMPLE_START - #define PTC_SAMPLE_START 30 -#endif -#define PTC_SAMPLE_END (PTC_SAMPLE_START + (PTC_SAMPLE_COUNT) * PTC_SAMPLE_RES) - -// Bed temperature calibration constants -#ifndef BTC_PROBE_TEMP - #define BTC_PROBE_TEMP 30 -#endif -#ifndef BTC_SAMPLE_COUNT - #define BTC_SAMPLE_COUNT 10 -#endif -#ifndef BTC_SAMPLE_RES - #define BTC_SAMPLE_RES 5 -#endif -#ifndef BTC_SAMPLE_START - #define BTC_SAMPLE_START 60 -#endif -#define BTC_SAMPLE_END (BTC_SAMPLE_START + (BTC_SAMPLE_COUNT) * BTC_SAMPLE_RES) - -// Extruder temperature calibration constants -#if ENABLED(USE_TEMP_EXT_COMPENSATION) - #ifndef ETC_SAMPLE_COUNT - #define ETC_SAMPLE_COUNT 20 - #endif - #ifndef ETC_SAMPLE_RES - #define ETC_SAMPLE_RES 5 - #endif - #ifndef ETC_SAMPLE_START - #define ETC_SAMPLE_START 180 - #endif - #define ETC_SAMPLE_END (ETC_SAMPLE_START + (ETC_SAMPLE_COUNT) * ETC_SAMPLE_RES) -#endif - -#ifndef PTC_PROBE_HEATING_OFFSET - #define PTC_PROBE_HEATING_OFFSET 0.5f -#endif - -#ifndef PTC_PROBE_RAISE - #define PTC_PROBE_RAISE 10 -#endif - -static constexpr temp_calib_t cali_info_init[TSI_COUNT] = { - { PTC_SAMPLE_COUNT, PTC_SAMPLE_RES, PTC_SAMPLE_START, PTC_SAMPLE_END }, // Probe - { BTC_SAMPLE_COUNT, BTC_SAMPLE_RES, BTC_SAMPLE_START, BTC_SAMPLE_END }, // Bed - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - { ETC_SAMPLE_COUNT, ETC_SAMPLE_RES, ETC_SAMPLE_START, ETC_SAMPLE_END }, // Extruder - #endif -}; - class ProbeTempComp { public: - static const temp_calib_t cali_info[TSI_COUNT]; - - // Where to park nozzle to wait for probe cooldown - static constexpr xyz_pos_t park_point = PTC_PARK_POS; - - // XY coordinates of nozzle for probing the bed - static constexpr xy_pos_t measure_point = PTC_PROBE_POS; // Coordinates to probe - //measure_point = { 12.0f, 7.3f }; // Coordinates for the MK52 magnetic heatbed - - static constexpr celsius_t probe_calib_bed_temp = BED_MAX_TARGET, // Bed temperature while calibrating probe - bed_calib_probe_temp = BTC_PROBE_TEMP; // Probe temperature while calibrating bed - - static int16_t *sensor_z_offsets[TSI_COUNT], - z_offsets_probe[cali_info_init[TSI_PROBE].measurements], // (µm) - z_offsets_bed[cali_info_init[TSI_BED].measurements]; // (µm) - - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - static int16_t z_offsets_ext[cali_info_init[TSI_EXT].measurements]; // (µm) + static constexpr temp_calib_t cali_info[TSI_COUNT] = { + #if ENABLED(PTC_PROBE) + { PTC_PROBE_COUNT, PTC_PROBE_RES, PTC_PROBE_START }, // Probe + #endif + #if ENABLED(PTC_BED) + { PTC_BED_COUNT, PTC_BED_RES, PTC_BED_START }, // Bed + #endif + #if ENABLED(PTC_HOTEND) + { PTC_HOTEND_COUNT, PTC_HOTEND_RES, PTC_HOTEND_START }, // Extruder + #endif + }; + + static int16_t *sensor_z_offsets[TSI_COUNT]; + #if ENABLED(PTC_PROBE) + static int16_t z_offsets_probe[PTC_PROBE_COUNT]; // (µm) + #endif + #if ENABLED(PTC_BED) + static int16_t z_offsets_bed[PTC_BED_COUNT]; // (µm) + #endif + #if ENABLED(PTC_HOTEND) + static int16_t z_offsets_hotend[PTC_HOTEND_COUNT]; // (µm) #endif static inline void reset_index() { calib_idx = 0; }; static inline uint8_t get_index() { return calib_idx; } + static void reset(); static void clear_offsets(const TempSensorID tsi); static inline void clear_all_offsets() { - clear_offsets(TSI_BED); - clear_offsets(TSI_PROBE); - TERN_(USE_TEMP_EXT_COMPENSATION, clear_offsets(TSI_EXT)); + TERN_(PTC_PROBE, clear_offsets(TSI_PROBE)); + TERN_(PTC_BED, clear_offsets(TSI_BED)); + TERN_(PTC_HOTEND, clear_offsets(TSI_EXT)); } static bool set_offset(const TempSensorID tsi, const uint8_t idx, const int16_t offset); static void print_offsets(); @@ -156,4 +106,4 @@ class ProbeTempComp { static bool linear_regression(const TempSensorID tsi, float &k, float &d); }; -extern ProbeTempComp temp_comp; +extern ProbeTempComp ptc; diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 5d94797f16a15..14da38c8fe2bb 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -36,7 +36,7 @@ #include "../../../module/probe.h" #include "../../queue.h" -#if ENABLED(PROBE_TEMP_COMPENSATION) +#if HAS_PTC #include "../../../feature/probe_temp_comp.h" #include "../../../module/temperature.h" #endif @@ -645,11 +645,9 @@ G29_TYPE GcodeSuite::G29() { break; // Breaks out of both loops } - #if ENABLED(PROBE_TEMP_COMPENSATION) - temp_comp.compensate_measurement(TSI_BED, thermalManager.degBed(), abl.measured_z); - temp_comp.compensate_measurement(TSI_PROBE, thermalManager.degProbe(), abl.measured_z); - TERN_(USE_TEMP_EXT_COMPENSATION, temp_comp.compensate_measurement(TSI_EXT, thermalManager.degHotend(0), abl.measured_z)); - #endif + TERN_(PTC_BED, ptc.compensate_measurement(TSI_BED, thermalManager.degBed(), abl.measured_z)); + TERN_(PTC_PROBE, ptc.compensate_measurement(TSI_PROBE, thermalManager.degProbe(), abl.measured_z)); + TERN_(PTC_HOTEND, ptc.compensate_measurement(TSI_EXT, thermalManager.degHotend(0), abl.measured_z)); #if ENABLED(AUTO_BED_LEVELING_LINEAR) diff --git a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp deleted file mode 100644 index 0fc41ed929090..0000000000000 --- a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp +++ /dev/null @@ -1,358 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -/** - * G76_M871.cpp - Temperature calibration/compensation for z-probing - */ - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(PROBE_TEMP_COMPENSATION) - -#include "../gcode.h" -#include "../../module/motion.h" -#include "../../module/planner.h" -#include "../../module/probe.h" -#include "../../feature/bedlevel/bedlevel.h" -#include "../../module/temperature.h" -#include "../../module/probe.h" -#include "../../feature/probe_temp_comp.h" -#include "../../lcd/marlinui.h" - -/** - * G76: calibrate probe and/or bed temperature offsets - * Notes: - * - When calibrating probe, bed temperature is held constant. - * Compensation values are deltas to first probe measurement at probe temp. = 30°C. - * - When calibrating bed, probe temperature is held constant. - * Compensation values are deltas to first probe measurement at bed temp. = 60°C. - * - The hotend will not be heated at any time. - * - On my Průša MK3S clone I put a piece of paper between the probe and the hotend - * so the hotend fan would not cool my probe constantly. Alternatively you could just - * make sure the fan is not running while running the calibration process. - * - * Probe calibration: - * - Moves probe to cooldown point. - * - Heats up bed to 100°C. - * - Moves probe to probing point (1mm above heatbed). - * - Waits until probe reaches target temperature (30°C). - * - Does a z-probing (=base value) and increases target temperature by 5°C. - * - Waits until probe reaches increased target temperature. - * - Does a z-probing (delta to base value will be a compensation value) and increases target temperature by 5°C. - * - Repeats last two steps until max. temperature reached or timeout (i.e. probe does not heat up any further). - * - Compensation values of higher temperatures will be extrapolated (using linear regression first). - * While this is not exact by any means it is still better than simply using the last compensation value. - * - * Bed calibration: - * - Moves probe to cooldown point. - * - Heats up bed to 60°C. - * - Moves probe to probing point (1mm above heatbed). - * - Waits until probe reaches target temperature (30°C). - * - Does a z-probing (=base value) and increases bed temperature by 5°C. - * - Moves probe to cooldown point. - * - Waits until probe is below 30°C and bed has reached target temperature. - * - Moves probe to probing point and waits until it reaches target temperature (30°C). - * - Does a z-probing (delta to base value will be a compensation value) and increases bed temperature by 5°C. - * - Repeats last four points until max. bed temperature reached (110°C) or timeout. - * - Compensation values of higher temperatures will be extrapolated (using linear regression first). - * While this is not exact by any means it is still better than simply using the last compensation value. - * - * G76 [B | P] - * - no flag - Both calibration procedures will be run. - * - `B` - Run bed temperature calibration. - * - `P` - Run probe temperature calibration. - */ - -static void say_waiting_for() { SERIAL_ECHOPGM("Waiting for "); } -static void say_waiting_for_probe_heating() { say_waiting_for(); SERIAL_ECHOLNPGM("probe heating."); } -static void say_successfully_calibrated() { SERIAL_ECHOPGM("Successfully calibrated"); } -static void say_failed_to_calibrate() { SERIAL_ECHOPGM("!Failed to calibrate"); } - -void GcodeSuite::G76() { - // Check if heated bed is available and z-homing is done with probe - #if TEMP_SENSOR_BED == 0 || !(HOMING_Z_WITH_PROBE) - return; - #endif - - auto report_temps = [](millis_t &ntr, millis_t timeout=0) { - idle_no_sleep(); - const millis_t ms = millis(); - if (ELAPSED(ms, ntr)) { - ntr = ms + 1000; - thermalManager.print_heater_states(active_extruder); - } - return (timeout && ELAPSED(ms, timeout)); - }; - - auto wait_for_temps = [&](const celsius_t tb, const celsius_t tp, millis_t &ntr, const millis_t timeout=0) { - say_waiting_for(); SERIAL_ECHOLNPGM("bed and probe temperature."); - while (thermalManager.wholeDegBed() != tb || thermalManager.wholeDegProbe() > tp) - if (report_temps(ntr, timeout)) return true; - return false; - }; - - auto g76_probe = [](const TempSensorID sid, celsius_t &targ, const xy_pos_t &nozpos) { - do_z_clearance(5.0); // Raise nozzle before probing - const float measured_z = probe.probe_at_point(nozpos, PROBE_PT_STOW, 0, false); // verbose=0, probe_relative=false - if (isnan(measured_z)) - SERIAL_ECHOLNPGM("!Received NAN. Aborting."); - else { - SERIAL_ECHOLNPAIR_F("Measured: ", measured_z); - if (targ == cali_info_init[sid].start_temp) - temp_comp.prepare_new_calibration(measured_z); - else - temp_comp.push_back_new_measurement(sid, measured_z); - targ += cali_info_init[sid].temp_resolution; - } - return measured_z; - }; - - #if ENABLED(BLTOUCH) - // Make sure any BLTouch error condition is cleared - bltouch_command(BLTOUCH_RESET, BLTOUCH_RESET_DELAY); - set_bltouch_deployed(false); - #endif - - bool do_bed_cal = parser.boolval('B'), do_probe_cal = parser.boolval('P'); - if (!do_bed_cal && !do_probe_cal) do_bed_cal = do_probe_cal = true; - - // Synchronize with planner - planner.synchronize(); - - const xyz_pos_t parkpos = temp_comp.park_point, - probe_pos_xyz = xyz_pos_t(temp_comp.measure_point) + xyz_pos_t({ 0.0f, 0.0f, PTC_PROBE_HEATING_OFFSET }), - noz_pos_xyz = probe_pos_xyz - probe.offset_xy; // Nozzle position based on probe position - - if (do_bed_cal || do_probe_cal) { - // Ensure park position is reachable - bool reachable = position_is_reachable(parkpos) || WITHIN(parkpos.z, Z_MIN_POS - fslop, Z_MAX_POS + fslop); - if (!reachable) - SERIAL_ECHOLNPGM("!Park"); - else { - // Ensure probe position is reachable - reachable = probe.can_reach(probe_pos_xyz); - if (!reachable) SERIAL_ECHOLNPGM("!Probe"); - } - - if (!reachable) { - SERIAL_ECHOLNPGM(" position unreachable - aborting."); - return; - } - - process_subcommands_now(FPSTR(G28_STR)); - } - - remember_feedrate_scaling_off(); - - /****************************************** - * Calibrate bed temperature offsets - ******************************************/ - - // Report temperatures every second and handle heating timeouts - millis_t next_temp_report = millis() + 1000; - - auto report_targets = [&](const celsius_t tb, const celsius_t tp) { - SERIAL_ECHOLNPGM("Target Bed:", tb, " Probe:", tp); - }; - - if (do_bed_cal) { - - celsius_t target_bed = cali_info_init[TSI_BED].start_temp, - target_probe = temp_comp.bed_calib_probe_temp; - - say_waiting_for(); SERIAL_ECHOLNPGM(" cooling."); - while (thermalManager.wholeDegBed() > target_bed || thermalManager.wholeDegProbe() > target_probe) - report_temps(next_temp_report); - - // Disable leveling so it won't mess with us - TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); - - for (;;) { - thermalManager.setTargetBed(target_bed); - - report_targets(target_bed, target_probe); - - // Park nozzle - do_blocking_move_to(parkpos); - - // Wait for heatbed to reach target temp and probe to cool below target temp - if (wait_for_temps(target_bed, target_probe, next_temp_report, millis() + MIN_TO_MS(15))) { - SERIAL_ECHOLNPGM("!Bed heating timeout."); - break; - } - - // Move the nozzle to the probing point and wait for the probe to reach target temp - do_blocking_move_to(noz_pos_xyz); - say_waiting_for_probe_heating(); - SERIAL_EOL(); - while (thermalManager.wholeDegProbe() < target_probe) - report_temps(next_temp_report); - - const float measured_z = g76_probe(TSI_BED, target_bed, noz_pos_xyz); - if (isnan(measured_z) || target_bed > (BED_MAX_TARGET)) break; - } - - SERIAL_ECHOLNPGM("Retrieved measurements: ", temp_comp.get_index()); - if (temp_comp.finish_calibration(TSI_BED)) { - say_successfully_calibrated(); - SERIAL_ECHOLNPGM(" bed."); - } - else { - say_failed_to_calibrate(); - SERIAL_ECHOLNPGM(" bed. Values reset."); - } - - // Cleanup - thermalManager.setTargetBed(0); - TERN_(HAS_LEVELING, set_bed_leveling_enabled(true)); - } // do_bed_cal - - /******************************************** - * Calibrate probe temperature offsets - ********************************************/ - - if (do_probe_cal) { - - // Park nozzle - do_blocking_move_to(parkpos); - - // Initialize temperatures - const celsius_t target_bed = temp_comp.probe_calib_bed_temp; - thermalManager.setTargetBed(target_bed); - - celsius_t target_probe = cali_info_init[TSI_PROBE].start_temp; - - report_targets(target_bed, target_probe); - - // Wait for heatbed to reach target temp and probe to cool below target temp - wait_for_temps(target_bed, target_probe, next_temp_report); - - // Disable leveling so it won't mess with us - TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); - - bool timeout = false; - for (;;) { - // Move probe to probing point and wait for it to reach target temperature - do_blocking_move_to(noz_pos_xyz); - - say_waiting_for_probe_heating(); - SERIAL_ECHOLNPGM(" Bed:", target_bed, " Probe:", target_probe); - const millis_t probe_timeout_ms = millis() + SEC_TO_MS(900UL); - while (thermalManager.degProbe() < target_probe) { - if (report_temps(next_temp_report, probe_timeout_ms)) { - SERIAL_ECHOLNPGM("!Probe heating timed out."); - timeout = true; - break; - } - } - if (timeout) break; - - const float measured_z = g76_probe(TSI_PROBE, target_probe, noz_pos_xyz); - if (isnan(measured_z) || target_probe > cali_info_init[TSI_PROBE].end_temp) break; - } - - SERIAL_ECHOLNPGM("Retrieved measurements: ", temp_comp.get_index()); - if (temp_comp.finish_calibration(TSI_PROBE)) - say_successfully_calibrated(); - else - say_failed_to_calibrate(); - SERIAL_ECHOLNPGM(" probe."); - - // Cleanup - thermalManager.setTargetBed(0); - TERN_(HAS_LEVELING, set_bed_leveling_enabled(true)); - - SERIAL_ECHOLNPGM("Final compensation values:"); - temp_comp.print_offsets(); - } // do_probe_cal - - restore_feedrate_and_scaling(); -} - -/** - * M871: Report / reset temperature compensation offsets. - * Note: This does not affect values in EEPROM until M500. - * - * M871 [ R | B | P | E ] - * - * No Parameters - Print current offset values. - * - * Select only one of these flags: - * R - Reset all offsets to zero (i.e., disable compensation). - * B - Manually set offset for bed - * P - Manually set offset for probe - * E - Manually set offset for extruder - * - * With B, P, or E: - * I[index] - Index in the array - * V[value] - Adjustment in µm - */ -void GcodeSuite::M871() { - - if (parser.seen('R')) { - // Reset z-probe offsets to factory defaults - temp_comp.clear_all_offsets(); - SERIAL_ECHOLNPGM("Offsets reset to default."); - } - else if (parser.seen("BPE")) { - if (!parser.seenval('V')) return; - const int16_t offset_val = parser.value_int(); - if (!parser.seenval('I')) return; - const int16_t idx = parser.value_int(); - const TempSensorID mod = (parser.seen('B') ? TSI_BED : - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - parser.seen('E') ? TSI_EXT : - #endif - TSI_PROBE - ); - if (idx > 0 && temp_comp.set_offset(mod, idx - 1, offset_val)) - SERIAL_ECHOLNPGM("Set value: ", offset_val); - else - SERIAL_ECHOLNPGM("!Invalid index. Failed to set value (note: value at index 0 is constant)."); - - } - else // Print current Z-probe adjustments. Note: Values in EEPROM might differ. - temp_comp.print_offsets(); -} - -/** - * M192: Wait for probe temperature sensor to reach a target - * - * Select only one of these flags: - * R - Wait for heating or cooling - * S - Wait only for heating - */ -void GcodeSuite::M192() { - if (DEBUGGING(DRYRUN)) return; - - const bool no_wait_for_cooling = parser.seenval('S'); - if (!no_wait_for_cooling && ! parser.seenval('R')) { - SERIAL_ERROR_MSG("No target temperature set."); - return; - } - - const celsius_t target_temp = parser.value_celsius(); - ui.set_status(thermalManager.isProbeBelowTemp(target_temp) ? GET_TEXT_F(MSG_PROBE_HEATING) : GET_TEXT_F(MSG_PROBE_COOLING)); - thermalManager.wait_for_probe(target_temp, no_wait_for_cooling); -} - -#endif // PROBE_TEMP_COMPENSATION diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp new file mode 100644 index 0000000000000..21bb2c7590066 --- /dev/null +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -0,0 +1,337 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * G76_M871.cpp - Temperature calibration/compensation for z-probing + */ + +#include "../../inc/MarlinConfig.h" + +#if HAS_PTC + +#include "../gcode.h" +#include "../../module/motion.h" +#include "../../module/planner.h" +#include "../../module/probe.h" +#include "../../feature/bedlevel/bedlevel.h" +#include "../../module/temperature.h" +#include "../../module/probe.h" +#include "../../feature/probe_temp_comp.h" +#include "../../lcd/marlinui.h" + +/** + * G76: calibrate probe and/or bed temperature offsets + * Notes: + * - When calibrating probe, bed temperature is held constant. + * Compensation values are deltas to first probe measurement at probe temp. = 30°C. + * - When calibrating bed, probe temperature is held constant. + * Compensation values are deltas to first probe measurement at bed temp. = 60°C. + * - The hotend will not be heated at any time. + * - On my Průša MK3S clone I put a piece of paper between the probe and the hotend + * so the hotend fan would not cool my probe constantly. Alternatively you could just + * make sure the fan is not running while running the calibration process. + * + * Probe calibration: + * - Moves probe to cooldown point. + * - Heats up bed to 100°C. + * - Moves probe to probing point (1mm above heatbed). + * - Waits until probe reaches target temperature (30°C). + * - Does a z-probing (=base value) and increases target temperature by 5°C. + * - Waits until probe reaches increased target temperature. + * - Does a z-probing (delta to base value will be a compensation value) and increases target temperature by 5°C. + * - Repeats last two steps until max. temperature reached or timeout (i.e. probe does not heat up any further). + * - Compensation values of higher temperatures will be extrapolated (using linear regression first). + * While this is not exact by any means it is still better than simply using the last compensation value. + * + * Bed calibration: + * - Moves probe to cooldown point. + * - Heats up bed to 60°C. + * - Moves probe to probing point (1mm above heatbed). + * - Waits until probe reaches target temperature (30°C). + * - Does a z-probing (=base value) and increases bed temperature by 5°C. + * - Moves probe to cooldown point. + * - Waits until probe is below 30°C and bed has reached target temperature. + * - Moves probe to probing point and waits until it reaches target temperature (30°C). + * - Does a z-probing (delta to base value will be a compensation value) and increases bed temperature by 5°C. + * - Repeats last four points until max. bed temperature reached (110°C) or timeout. + * - Compensation values of higher temperatures will be extrapolated (using linear regression first). + * While this is not exact by any means it is still better than simply using the last compensation value. + * + * G76 [B | P] + * - no flag - Both calibration procedures will be run. + * - `B` - Run bed temperature calibration. + * - `P` - Run probe temperature calibration. + */ + +static void say_waiting_for() { SERIAL_ECHOPGM("Waiting for "); } +static void say_waiting_for_probe_heating() { say_waiting_for(); SERIAL_ECHOLNPGM("probe heating."); } +static void say_successfully_calibrated() { SERIAL_ECHOPGM("Successfully calibrated"); } +static void say_failed_to_calibrate() { SERIAL_ECHOPGM("!Failed to calibrate"); } + +#if BOTH(PTC_PROBE, PTC_BED) + + void GcodeSuite::G76() { + auto report_temps = [](millis_t &ntr, millis_t timeout=0) { + idle_no_sleep(); + const millis_t ms = millis(); + if (ELAPSED(ms, ntr)) { + ntr = ms + 1000; + thermalManager.print_heater_states(active_extruder); + } + return (timeout && ELAPSED(ms, timeout)); + }; + + auto wait_for_temps = [&](const celsius_t tb, const celsius_t tp, millis_t &ntr, const millis_t timeout=0) { + say_waiting_for(); SERIAL_ECHOLNPGM("bed and probe temperature."); + while (thermalManager.wholeDegBed() != tb || thermalManager.wholeDegProbe() > tp) + if (report_temps(ntr, timeout)) return true; + return false; + }; + + auto g76_probe = [](const TempSensorID sid, celsius_t &targ, const xy_pos_t &nozpos) { + do_z_clearance(5.0); // Raise nozzle before probing + const float measured_z = probe.probe_at_point(nozpos, PROBE_PT_STOW, 0, false); // verbose=0, probe_relative=false + if (isnan(measured_z)) + SERIAL_ECHOLNPGM("!Received NAN. Aborting."); + else { + SERIAL_ECHOLNPAIR_F("Measured: ", measured_z); + if (targ == ProbeTempComp::cali_info[sid].start_temp) + ptc.prepare_new_calibration(measured_z); + else + ptc.push_back_new_measurement(sid, measured_z); + targ += ProbeTempComp::cali_info[sid].temp_resolution; + } + return measured_z; + }; + + #if ENABLED(BLTOUCH) + // Make sure any BLTouch error condition is cleared + bltouch_command(BLTOUCH_RESET, BLTOUCH_RESET_DELAY); + set_bltouch_deployed(false); + #endif + + bool do_bed_cal = parser.boolval('B'), do_probe_cal = parser.boolval('P'); + if (!do_bed_cal && !do_probe_cal) do_bed_cal = do_probe_cal = true; + + // Synchronize with planner + planner.synchronize(); + + #ifndef PTC_PROBE_HEATING_OFFSET + #define PTC_PROBE_HEATING_OFFSET 0 + #endif + const xyz_pos_t parkpos = PTC_PARK_POS, + probe_pos_xyz = xyz_pos_t(PTC_PROBE_POS) + xyz_pos_t({ 0.0f, 0.0f, PTC_PROBE_HEATING_OFFSET }), + noz_pos_xyz = probe_pos_xyz - probe.offset_xy; // Nozzle position based on probe position + + if (do_bed_cal || do_probe_cal) { + // Ensure park position is reachable + bool reachable = position_is_reachable(parkpos) || WITHIN(parkpos.z, Z_MIN_POS - fslop, Z_MAX_POS + fslop); + if (!reachable) + SERIAL_ECHOLNPGM("!Park"); + else { + // Ensure probe position is reachable + reachable = probe.can_reach(probe_pos_xyz); + if (!reachable) SERIAL_ECHOLNPGM("!Probe"); + } + + if (!reachable) { + SERIAL_ECHOLNPGM(" position unreachable - aborting."); + return; + } + + process_subcommands_now(FPSTR(G28_STR)); + } + + remember_feedrate_scaling_off(); + + /****************************************** + * Calibrate bed temperature offsets + ******************************************/ + + // Report temperatures every second and handle heating timeouts + millis_t next_temp_report = millis() + 1000; + + auto report_targets = [&](const celsius_t tb, const celsius_t tp) { + SERIAL_ECHOLNPGM("Target Bed:", tb, " Probe:", tp); + }; + + if (do_bed_cal) { + + celsius_t target_bed = PTC_BED_START, + target_probe = PTC_PROBE_TEMP; + + say_waiting_for(); SERIAL_ECHOLNPGM(" cooling."); + while (thermalManager.wholeDegBed() > target_bed || thermalManager.wholeDegProbe() > target_probe) + report_temps(next_temp_report); + + // Disable leveling so it won't mess with us + TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); + + for (uint8_t idx = 0; idx <= PTC_BED_COUNT; idx++) { + thermalManager.setTargetBed(target_bed); + + report_targets(target_bed, target_probe); + + // Park nozzle + do_blocking_move_to(parkpos); + + // Wait for heatbed to reach target temp and probe to cool below target temp + if (wait_for_temps(target_bed, target_probe, next_temp_report, millis() + MIN_TO_MS(15))) { + SERIAL_ECHOLNPGM("!Bed heating timeout."); + break; + } + + // Move the nozzle to the probing point and wait for the probe to reach target temp + do_blocking_move_to(noz_pos_xyz); + say_waiting_for_probe_heating(); + SERIAL_EOL(); + while (thermalManager.wholeDegProbe() < target_probe) + report_temps(next_temp_report); + + const float measured_z = g76_probe(TSI_BED, target_bed, noz_pos_xyz); + if (isnan(measured_z) || target_bed > (BED_MAX_TARGET)) break; + } + + SERIAL_ECHOLNPGM("Retrieved measurements: ", ptc.get_index()); + if (ptc.finish_calibration(TSI_BED)) { + say_successfully_calibrated(); + SERIAL_ECHOLNPGM(" bed."); + } + else { + say_failed_to_calibrate(); + SERIAL_ECHOLNPGM(" bed. Values reset."); + } + + // Cleanup + thermalManager.setTargetBed(0); + TERN_(HAS_LEVELING, set_bed_leveling_enabled(true)); + } // do_bed_cal + + /******************************************** + * Calibrate probe temperature offsets + ********************************************/ + + if (do_probe_cal) { + + // Park nozzle + do_blocking_move_to(parkpos); + + // Initialize temperatures + const celsius_t target_bed = BED_MAX_TARGET; + thermalManager.setTargetBed(target_bed); + + celsius_t target_probe = PTC_PROBE_START; + + report_targets(target_bed, target_probe); + + // Wait for heatbed to reach target temp and probe to cool below target temp + wait_for_temps(target_bed, target_probe, next_temp_report); + + // Disable leveling so it won't mess with us + TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); + + bool timeout = false; + for (uint8_t idx = 0; idx <= PTC_PROBE_COUNT; idx++) { + // Move probe to probing point and wait for it to reach target temperature + do_blocking_move_to(noz_pos_xyz); + + say_waiting_for_probe_heating(); + SERIAL_ECHOLNPGM(" Bed:", target_bed, " Probe:", target_probe); + const millis_t probe_timeout_ms = millis() + SEC_TO_MS(900UL); + while (thermalManager.degProbe() < target_probe) { + if (report_temps(next_temp_report, probe_timeout_ms)) { + SERIAL_ECHOLNPGM("!Probe heating timed out."); + timeout = true; + break; + } + } + if (timeout) break; + + const float measured_z = g76_probe(TSI_PROBE, target_probe, noz_pos_xyz); + if (isnan(measured_z)) break; + } + + SERIAL_ECHOLNPGM("Retrieved measurements: ", ptc.get_index()); + if (ptc.finish_calibration(TSI_PROBE)) + say_successfully_calibrated(); + else + say_failed_to_calibrate(); + SERIAL_ECHOLNPGM(" probe."); + + // Cleanup + thermalManager.setTargetBed(0); + TERN_(HAS_LEVELING, set_bed_leveling_enabled(true)); + + SERIAL_ECHOLNPGM("Final compensation values:"); + ptc.print_offsets(); + } // do_probe_cal + + restore_feedrate_and_scaling(); + } + +#endif // PTC_PROBE && PTC_BED + +/** + * M871: Report / reset temperature compensation offsets. + * Note: This does not affect values in EEPROM until M500. + * + * M871 [ R | B | P | E ] + * + * No Parameters - Print current offset values. + * + * Select only one of these flags: + * R - Reset all offsets to zero (i.e., disable compensation). + * B - Manually set offset for bed + * P - Manually set offset for probe + * E - Manually set offset for extruder + * + * With B, P, or E: + * I[index] - Index in the array + * V[value] - Adjustment in µm + */ +void GcodeSuite::M871() { + + if (parser.seen('R')) { + // Reset z-probe offsets to factory defaults + ptc.clear_all_offsets(); + SERIAL_ECHOLNPGM("Offsets reset to default."); + } + else if (parser.seen("BPE")) { + if (!parser.seenval('V')) return; + const int16_t offset_val = parser.value_int(); + if (!parser.seenval('I')) return; + const int16_t idx = parser.value_int(); + const TempSensorID mod = TERN_(PTC_BED, parser.seen_test('B') ? TSI_BED :) + TERN_(PTC_HOTEND, parser.seen_test('E') ? TSI_EXT :) + TERN_(PTC_PROBE, parser.seen_test('P') ? TSI_PROBE :) TSI_COUNT; + if (mod == TSI_COUNT) + SERIAL_ECHOLNPGM("!Invalid sensor."); + else if (idx > 0 && ptc.set_offset(mod, idx - 1, offset_val)) + SERIAL_ECHOLNPGM("Set value: ", offset_val); + else + SERIAL_ECHOLNPGM("!Invalid index. Failed to set value (note: value at index 0 is constant)."); + } + else // Print current Z-probe adjustments. Note: Values in EEPROM might differ. + ptc.print_offsets(); +} + +#endif // HAS_PTC diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index fb1669c1eae79..b2cb26122fcfa 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -424,7 +424,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 61: G61(); break; // G61: Apply/restore saved coordinates. #endif - #if ENABLED(PROBE_TEMP_COMPENSATION) + #if BOTH(PTC_PROBE, PTC_BED) case 76: G76(); break; // G76: Calibrate first layer compensation values #endif @@ -587,6 +587,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 191: M191(); break; // M191: Wait for chamber temperature to reach target #endif + #if HAS_TEMP_PROBE + case 192: M192(); break; // M192: Wait for probe temp + #endif + #if HAS_COOLER case 143: M143(); break; // M143: Set cooler temperature case 193: M193(); break; // M193: Wait for cooler temperature to reach target @@ -921,8 +925,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 852: M852(); break; // M852: Set Skew factors #endif - #if ENABLED(PROBE_TEMP_COMPENSATION) - case 192: M192(); break; // M192: Wait for probe temp + #if HAS_PTC case 871: M871(); break; // M871: Print/reset/clear first layer temperature offset values #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 8de15fc9c7f5a..09dd53d6f65c6 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -66,7 +66,7 @@ * G42 - Coordinated move to a mesh point (Requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BLINEAR, or AUTO_BED_LEVELING_UBL) * G60 - Save current position. (Requires SAVED_POSITIONS) * G61 - Apply/restore saved coordinates. (Requires SAVED_POSITIONS) - * G76 - Calibrate first layer temperature offsets. (Requires PROBE_TEMP_COMPENSATION) + * G76 - Calibrate first layer temperature offsets. (Requires PTC_PROBE and PTC_BED) * G80 - Cancel current motion mode (Requires GCODE_MOTION_MODES) * G90 - Use Absolute Coordinates * G91 - Use Relative Coordinates @@ -88,6 +88,8 @@ * M16 - Expected printer check. (Requires EXPECTED_PRINTER_CHECK) * M17 - Enable/Power all stepper motors * M18 - Disable all stepper motors; same as M84 + * + *** Print from Media (SDSUPPORT) *** * M20 - List SD card. (Requires SDSUPPORT) * M21 - Init SD card. (Requires SDSUPPORT) * M22 - Release SD card. (Requires SDSUPPORT) @@ -100,30 +102,36 @@ * OR, with 'C' get the current filename. * M28 - Start SD write: "M28 /path/file.gco". (Requires SDSUPPORT) * M29 - Stop SD write. (Requires SDSUPPORT) - * M30 - Delete file from SD: "M30 /path/file.gco" + * M30 - Delete file from SD: "M30 /path/file.gco" (Requires SDSUPPORT) * M31 - Report time since last M109 or SD card start to serial. * M32 - Select file and start SD print: "M32 [S] !/path/file.gco#". (Requires SDSUPPORT) * Use P to run other files as sub-programs: "M32 P !filename#" * The '#' is necessary when calling from within sd files, as it stops buffer prereading * M33 - Get the longname version of a path. (Requires LONG_FILENAME_HOST_SUPPORT) * M34 - Set SD Card sorting options. (Requires SDCARD_SORT_ALPHA) + * * M42 - Change pin status via gcode: M42 P S. LED pin assumed if P is omitted. (Requires DIRECT_PIN_CONTROL) - * M43 - Display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins + * M43 - Display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins (Requires PINS_DEBUGGING) * M48 - Measure Z Probe repeatability: M48 P X Y V E L S. (Requires Z_MIN_PROBE_REPEATABILITY_TEST) + * * M73 - Set the progress percentage. (Requires LCD_SET_PROGRESS_MANUALLY) * M75 - Start the print job timer. * M76 - Pause the print job timer. * M77 - Stop the print job timer. * M78 - Show statistical information about the print jobs. (Requires PRINTCOUNTER) + * * M80 - Turn on Power Supply. (Requires PSU_CONTROL) * M81 - Turn off Power Supply. (Requires PSU_CONTROL) + * * M82 - Set E codes absolute (default). * M83 - Set E codes relative while in Absolute (G90) mode. * M84 - Disable steppers until next move, or use S to specify an idle * duration after which steppers should turn off. S0 disables the timeout. * M85 - Set inactivity shutdown timer with parameter S. To disable set zero (default) * M92 - Set planner.settings.axis_steps_per_mm for one or more axes. + * * M100 - Watch Free Memory (for debugging) (Requires M100_FREE_MEMORY_WATCHER) + * * M104 - Set extruder target temp. * M105 - Report current temperatures. * M106 - Set print fan speed. @@ -132,23 +140,29 @@ * M109 - S Wait for extruder current temp to reach target temp. ** Wait only when heating! ** * R Wait for extruder current temp to reach target temp. ** Wait for heating or cooling. ** * If AUTOTEMP is enabled, S B F. Exit autotemp by any M109 without F + * * M110 - Set the current line number. (Used by host printing) * M111 - Set debug flags: "M111 S". See flag bits defined in enum.h. * M112 - Full Shutdown. + * * M113 - Get or set the timeout interval for Host Keepalive "busy" messages. (Requires HOST_KEEPALIVE_FEATURE) * M114 - Report current position. * M115 - Report capabilities. (Extended capabilities requires EXTENDED_CAPABILITIES_REPORT) * M117 - Display a message on the controller screen. (Requires an LCD) * M118 - Display a message in the host console. + * * M119 - Report endstops status. * M120 - Enable endstops detection. * M121 - Disable endstops detection. + * * M122 - Debug stepper (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660 or L6470) * M125 - Save current position and move to filament change position. (Requires PARK_HEAD_ON_PAUSE) + * * M126 - Solenoid Air Valve Open. (Requires BARICUDA) * M127 - Solenoid Air Valve Closed. (Requires BARICUDA) * M128 - EtoP Open. (Requires BARICUDA) * M129 - EtoP Closed. (Requires BARICUDA) + * * M140 - Set bed target temp. S * M141 - Set heated chamber target temp. S (Requires a chamber heater) * M143 - Set cooler target temp. S (Requires a laser cooling device) @@ -161,9 +175,9 @@ * M164 - Commit the mix and save to a virtual tool (current, or as specified by 'S'). (Requires MIXING_EXTRUDER) * M165 - Set the mix for the mixing extruder (and current virtual tool) with parameters ABCDHI. (Requires MIXING_EXTRUDER and DIRECT_MIXING_IN_G1) * M166 - Set the Gradient Mix for the mixing extruder. (Requires GRADIENT_MIX) - * M190 - S Wait for bed current temp to reach target temp. ** Wait only when heating! ** - * R Wait for bed current temp to reach target temp. ** Wait for heating or cooling. ** - * M193 - R Wait for cooler temp to reach target temp. ** Wait for cooling. ** + * M190 - Set bed target temperature and wait. R Set target temperature and wait. S Set, but only wait when heating. (Requires TEMP_SENSOR_BED) + * M192 - Wait for probe to reach target temperature. (Requires TEMP_SENSOR_PROBE) + * M193 - R Wait for cooler to reach target temp. ** Wait for cooling. ** * M200 - Set filament diameter, D, setting E axis units to cubic. (Use S0 to revert to linear units.) * M201 - Set max acceleration in units/s^2 for print moves: "M201 X Y Z E" * M202 - Set max acceleration in units/s^2 for travel moves: "M202 X Y Z E" ** UNUSED IN MARLIN! ** @@ -183,7 +197,7 @@ * M218 - Set/get a tool offset: "M218 T X Y". (Requires 2 or more extruders) * M220 - Set Feedrate Percentage: "M220 S" (i.e., "FR" on the LCD) * Use "M220 B" to back up the Feedrate Percentage and "M220 R" to restore it. (Requires an MMU_MODEL version 2 or 2S) - * M221 - Set Flow Percentage: "M221 S" + * M221 - Set Flow Percentage: "M221 S" (Requires an extruder) * M226 - Wait until a pin is in a given state: "M226 P S" (Requires DIRECT_PIN_CONTROL) * M240 - Trigger a camera to take a photograph. (Requires PHOTO_GCODE) * M250 - Set LCD contrast: "M250 C" (0-63). (Requires LCD support) @@ -230,9 +244,9 @@ * M502 - Revert to the default "factory settings". ** Does not write them to EEPROM! ** * M503 - Print the current settings (in memory): "M503 S". S0 specifies compact output. * M504 - Validate EEPROM contents. (Requires EEPROM_SETTINGS) - * M510 - Lock Printer - * M511 - Unlock Printer - * M512 - Set/Change/Remove Password + * M510 - Lock Printer (Requires PASSWORD_FEATURE) + * M511 - Unlock Printer (Requires PASSWORD_UNLOCK_GCODE) + * M512 - Set/Change/Remove Password (Requires PASSWORD_CHANGE_GCODE) * M524 - Abort the current SD print job started with M24. (Requires SDSUPPORT) * M540 - Enable/disable SD card abort on endstop hit: "M540 S". (Requires SD_ABORT_ON_ENDSTOP_HIT) * M552 - Get or set IP address. Enable/disable network interface. (Requires enabled Ethernet port) @@ -252,7 +266,9 @@ * M808 - Set or Goto a Repeat Marker (Requires GCODE_REPEAT_MARKERS) * M810-M819 - Define/execute a G-code macro (Requires GCODE_MACROS) * M851 - Set Z probe's XYZ offsets in current units. (Negative values: X=left, Y=front, Z=below) - * M852 - Set skew factors: "M852 [I] [J] [K]". (Requires SKEW_CORRECTION_GCODE, and SKEW_CORRECTION_FOR_Z for IJ) + * M852 - Set skew factors: "M852 [I] [J] [K]". (Requires SKEW_CORRECTION_GCODE, plus SKEW_CORRECTION_FOR_Z for IJ) + * + *** I2C_POSITION_ENCODERS *** * M860 - Report the position of position encoder modules. * M861 - Report the status of position encoder modules. * M862 - Perform an axis continuity test for position encoder modules. @@ -263,8 +279,8 @@ * M867 - Enable/disable or toggle error correction for position encoder modules. * M868 - Report or set position encoder module error correction threshold. * M869 - Report position encoder module error. - * M871 - Print/reset/clear first layer temperature offset values. (Requires PROBE_TEMP_COMPENSATION) - * M192 - Wait for probe temp (Requires PROBE_TEMP_COMPENSATION) + * + * M871 - Print/reset/clear first layer temperature offset values. (Requires PTC_PROBE, PTC_BED, or PTC_HOTEND) * M876 - Handle Prompt Response. (Requires HOST_PROMPT_SUPPORT and not EMERGENCY_PARSER) * M900 - Get or Set Linear Advance K-factor. (Requires LIN_ADVANCE) * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660 or L6470) @@ -282,13 +298,14 @@ * M951 - Set Magnetic Parking Extruder parameters. (Requires MAGNETIC_PARKING_EXTRUDER) * M7219 - Control Max7219 Matrix LEDs. (Requires MAX7219_GCODE) * + *** SCARA *** * M360 - SCARA calibration: Move to cal-position ThetaA (0 deg calibration) * M361 - SCARA calibration: Move to cal-position ThetaB (90 deg calibration - steps per degree) * M362 - SCARA calibration: Move to cal-position PsiA (0 deg calibration) * M363 - SCARA calibration: Move to cal-position PsiB (90 deg calibration - steps per degree) * M364 - SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position) * - * ************ Custom codes - This can change to suit future G-code regulations + *** Custom codes (can be changed to suit future G-code standards) *** * G425 - Calibrate using a conductive object. (Requires CALIBRATION_GCODE) * M928 - Start SD logging: "M928 filename.gco". Stop with M29. (Requires SDSUPPORT) * M993 - Backup SPI Flash to SD @@ -296,10 +313,11 @@ * M995 - Touch screen calibration for TFT display * M997 - Perform in-application firmware update * M999 - Restart after being stopped by error + * * D... - Custom Development G-code. Add hooks to 'gcode_D.cpp' for developers to test features. (Requires MARLIN_DEV_MODE) * D576 - Set buffer monitoring options. (Requires BUFFER_MONITORING) * - * "T" Codes + *** "T" Codes *** * * T0-T3 - Select an extruder (tool) by index: "T F" */ @@ -551,7 +569,7 @@ class GcodeSuite { static void G59(); #endif - #if ENABLED(PROBE_TEMP_COMPENSATION) + #if BOTH(PTC_PROBE, PTC_BED) static void G76(); #endif @@ -744,6 +762,10 @@ class GcodeSuite { static void M191(); #endif + #if HAS_TEMP_PROBE + static void M192(); + #endif + #if HAS_COOLER static void M143(); static void M193(); @@ -1087,8 +1109,7 @@ class GcodeSuite { FORCE_INLINE static void M869() { I2CPEM.M869(); } #endif - #if ENABLED(PROBE_TEMP_COMPENSATION) - static void M192(); + #if HAS_PTC static void M871(); #endif diff --git a/Marlin/src/gcode/temp/M192.cpp b/Marlin/src/gcode/temp/M192.cpp new file mode 100644 index 0000000000000..a96e2d34a4bf2 --- /dev/null +++ b/Marlin/src/gcode/temp/M192.cpp @@ -0,0 +1,56 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * M192.cpp - Wait for probe to reach temperature + */ + +#include "../../inc/MarlinConfig.h" + +#if HAS_TEMP_PROBE + +#include "../gcode.h" +#include "../../module/temperature.h" +#include "../../lcd/marlinui.h" + +/** + * M192: Wait for probe temperature sensor to reach a target + * + * Select only one of these flags: + * R - Wait for heating or cooling + * S - Wait only for heating + */ +void GcodeSuite::M192() { + if (DEBUGGING(DRYRUN)) return; + + const bool no_wait_for_cooling = parser.seenval('S'); + if (!no_wait_for_cooling && !parser.seenval('R')) { + SERIAL_ERROR_MSG("No target temperature set."); + return; + } + + const celsius_t target_temp = parser.value_celsius(); + ui.set_status(thermalManager.isProbeBelowTemp(target_temp) ? GET_TEXT_F(MSG_PROBE_HEATING) : GET_TEXT_F(MSG_PROBE_COOLING)); + thermalManager.wait_for_probe(target_temp, no_wait_for_cooling); +} + +#endif // HAS_TEMP_PROBE diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index efb9db420db8e..49067a5606763 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -550,6 +550,20 @@ #endif #endif +// Probe Temperature Compensation +#if !TEMP_SENSOR_PROBE + #undef PTC_PROBE +#endif +#if !TEMP_SENSOR_BED + #undef PTC_BED +#endif +#if !HAS_EXTRUDERS + #undef PTC_HOTEND +#endif +#if ANY(PTC_PROBE, PTC_BED, PTC_HOTEND) + #define HAS_PTC 1 +#endif + // Let SD_FINISHED_RELEASECOMMAND stand in for SD_FINISHED_STEPPERRELEASE #if ENABLED(SD_FINISHED_STEPPERRELEASE) #ifndef SD_FINISHED_RELEASECOMMAND diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 60238e6c80259..c8d30a27188ad 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -597,6 +597,10 @@ #error "SPINDLE_LASER_PWM (true) is now set with SPINDLE_LASER_USE_PWM (enabled)." #elif ANY(IS_RAMPS_EEB, IS_RAMPS_EEF, IS_RAMPS_EFB, IS_RAMPS_EFF, IS_RAMPS_SF) #error "The IS_RAMPS_* conditionals (for heater/fan/bed pins) are now called FET_ORDER_*." +#elif defined(PROBE_TEMP_COMPENSATION) + #error "PROBE_TEMP_COMPENSATION is now set using the PTC_PROBE, PTC_BED, PTC_HOTEND options." +#elif defined(BTC_PROBE_TEMP) + #error "BTC_PROBE_TEMP is now PTC_PROBE_TEMP." #endif #if MB(DUE3DOM_MINI) && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) @@ -611,60 +615,60 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Probe temp compensation requirements */ - -#if ENABLED(PROBE_TEMP_COMPENSATION) - #if defined(PTC_PARK_POS_X) || defined(PTC_PARK_POS_Y) || defined(PTC_PARK_POS_Z) - #error "PTC_PARK_POS_[XYZ] is now PTC_PARK_POS (array)." - #elif !defined(PTC_PARK_POS) - #error "PROBE_TEMP_COMPENSATION requires PTC_PARK_POS." - #elif defined(PTC_PROBE_POS_X) || defined(PTC_PROBE_POS_Y) - #error "PTC_PROBE_POS_[XY] is now PTC_PROBE_POS (array)." - #elif !defined(PTC_PROBE_POS) - #error "PROBE_TEMP_COMPENSATION requires PTC_PROBE_POS." +#if HAS_PTC + #if TEMP_SENSOR_PROBE && TEMP_SENSOR_BED + #if defined(PTC_PARK_POS_X) || defined(PTC_PARK_POS_Y) || defined(PTC_PARK_POS_Z) + #error "PTC_PARK_POS_[XYZ] is now PTC_PARK_POS (array)." + #elif !defined(PTC_PARK_POS) + #error "PTC_PARK_POS is required for Probe Temperature Compensation." + #elif defined(PTC_PROBE_POS_X) || defined(PTC_PROBE_POS_Y) + #error "PTC_PROBE_POS_[XY] is now PTC_PROBE_POS (array)." + #elif !defined(PTC_PROBE_POS) + #error "PTC_PROBE_POS is required for Probe Temperature Compensation." + #endif #endif - #ifdef PTC_SAMPLE_START - constexpr auto _ptc_sample_start = PTC_SAMPLE_START; + #ifdef PTC_PROBE_START + constexpr auto _ptc_sample_start = PTC_PROBE_START; constexpr decltype(_ptc_sample_start) _test_ptc_sample_start = 12.3f; - static_assert(_test_ptc_sample_start != 12.3f, "PTC_SAMPLE_START must be a whole number."); + static_assert(_test_ptc_sample_start != 12.3f, "PTC_PROBE_START must be a whole number."); #endif - #ifdef PTC_SAMPLE_RES - constexpr auto _ptc_sample_res = PTC_SAMPLE_RES; + #ifdef PTC_PROBE_RES + constexpr auto _ptc_sample_res = PTC_PROBE_RES; constexpr decltype(_ptc_sample_res) _test_ptc_sample_res = 12.3f; - static_assert(_test_ptc_sample_res != 12.3f, "PTC_SAMPLE_RES must be a whole number."); + static_assert(_test_ptc_sample_res != 12.3f, "PTC_PROBE_RES must be a whole number."); #endif - #ifdef BTC_SAMPLE_START - constexpr auto _btc_sample_start = BTC_SAMPLE_START; + #ifdef PTC_BED_START + constexpr auto _btc_sample_start = PTC_BED_START; constexpr decltype(_btc_sample_start) _test_btc_sample_start = 12.3f; - static_assert(_test_btc_sample_start != 12.3f, "BTC_SAMPLE_START must be a whole number."); + static_assert(_test_btc_sample_start != 12.3f, "PTC_BED_START must be a whole number."); #endif - #ifdef BTC_SAMPLE_RES - constexpr auto _btc_sample_res = BTC_SAMPLE_RES; + #ifdef PTC_BED_RES + constexpr auto _btc_sample_res = PTC_BED_RES; constexpr decltype(_btc_sample_res) _test_btc_sample_res = 12.3f; - static_assert(_test_btc_sample_res != 12.3f, "BTC_SAMPLE_RES must be a whole number."); + static_assert(_test_btc_sample_res != 12.3f, "PTC_BED_RES must be a whole number."); #endif - #ifdef BTC_PROBE_TEMP - constexpr auto _btc_probe_temp = BTC_PROBE_TEMP; + #ifdef PTC_PROBE_TEMP + constexpr auto _btc_probe_temp = PTC_PROBE_TEMP; constexpr decltype(_btc_probe_temp) _test_btc_probe_temp = 12.3f; - static_assert(_test_btc_probe_temp != 12.3f, "BTC_PROBE_TEMP must be a whole number."); + static_assert(_test_btc_probe_temp != 12.3f, "PTC_PROBE_TEMP must be a whole number."); #endif - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - #ifdef ETC_SAMPLE_START - constexpr auto _etc_sample_start = ETC_SAMPLE_START; + #if ENABLED(PTC_HOTEND) + #if EXTRUDERS != 1 + #error "PTC_HOTEND only works with a single extruder." + #endif + #ifdef PTC_HOTEND_START + constexpr auto _etc_sample_start = PTC_HOTEND_START; constexpr decltype(_etc_sample_start) _test_etc_sample_start = 12.3f; - static_assert(_test_etc_sample_start != 12.3f, "ETC_SAMPLE_START must be a whole number."); + static_assert(_test_etc_sample_start != 12.3f, "PTC_HOTEND_START must be a whole number."); #endif - #ifdef ETC_SAMPLE_RES - constexpr auto _etc_sample_res = ETC_SAMPLE_RES; + #ifdef PTC_HOTEND_RES + constexpr auto _etc_sample_res = PTC_HOTEND_RES; constexpr decltype(_etc_sample_res) _test_etc_sample_res = 12.3f; - static_assert(_test_etc_sample_res != 12.3f, "ETC_SAMPLE_RES must be a whole number."); + static_assert(_test_etc_sample_res != 12.3f, "PTC_HOTEND_RES must be a whole number."); #endif #endif - - #if ENABLED(USE_TEMP_EXT_COMPENSATION) && EXTRUDERS != 1 - #error "USE_TEMP_EXT_COMPENSATION only works with a single extruder." - #endif -#endif +#endif // HAS_PTC /** * Marlin release, version and default string diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index c82f5aad0df48..01a5c47fd54ee 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -128,7 +128,7 @@ #include "../feature/tmc_util.h" #endif -#if ENABLED(PROBE_TEMP_COMPENSATION) +#if HAS_PTC #include "../feature/probe_temp_comp.h" #endif @@ -264,13 +264,16 @@ typedef struct SettingsDataStruct { // // Temperature first layer compensation values // - #if ENABLED(PROBE_TEMP_COMPENSATION) - int16_t z_offsets_probe[COUNT(temp_comp.z_offsets_probe)], // M871 P I V - z_offsets_bed[COUNT(temp_comp.z_offsets_bed)] // M871 B I V - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - , z_offsets_ext[COUNT(temp_comp.z_offsets_ext)] // M871 E I V - #endif - ; + #if HAS_PTC + #if ENABLED(PTC_PROBE) + int16_t z_offsets_probe[COUNT(ptc.z_offsets_probe)]; // M871 P I V + #endif + #if ENABLED(PTC_BED) + int16_t z_offsets_bed[COUNT(ptc.z_offsets_bed)]; // M871 B I V + #endif + #if ENABLED(PTC_HOTEND) + int16_t z_offsets_hotend[COUNT(ptc.z_offsets_hotend)]; // M871 E I V + #endif #endif // @@ -844,11 +847,15 @@ void MarlinSettings::postprocess() { // // Thermal first layer compensation values // - #if ENABLED(PROBE_TEMP_COMPENSATION) - EEPROM_WRITE(temp_comp.z_offsets_probe); - EEPROM_WRITE(temp_comp.z_offsets_bed); - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - EEPROM_WRITE(temp_comp.z_offsets_ext); + #if HAS_PTC + #if ENABLED(PTC_PROBE) + EEPROM_WRITE(ptc.z_offsets_probe); + #endif + #if ENABLED(PTC_BED) + EEPROM_WRITE(ptc.z_offsets_bed); + #endif + #if ENABLED(PTC_HOTEND) + EEPROM_WRITE(ptc.z_offsets_hotend); #endif #else // No placeholder data for this feature @@ -1710,13 +1717,17 @@ void MarlinSettings::postprocess() { // // Thermal first layer compensation values // - #if ENABLED(PROBE_TEMP_COMPENSATION) - EEPROM_READ(temp_comp.z_offsets_probe); - EEPROM_READ(temp_comp.z_offsets_bed); - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - EEPROM_READ(temp_comp.z_offsets_ext); + #if HAS_PTC + #if ENABLED(PTC_PROBE) + EEPROM_READ(ptc.z_offsets_probe); #endif - temp_comp.reset_index(); + # if ENABLED(PTC_BED) + EEPROM_READ(ptc.z_offsets_bed); + #endif + #if ENABLED(PTC_HOTEND) + EEPROM_READ(ptc.z_offsets_hotend); + #endif + ptc.reset_index(); #else // No placeholder data for this feature #endif @@ -2728,6 +2739,11 @@ void MarlinSettings::reset() { // TERN_(EDITABLE_SERVO_ANGLES, COPY(servo_angles, base_servo_angles)); // When not editable only one copy of servo angles exists + // + // Probe Temperature Compensation + // + TERN_(HAS_PTC, ptc.reset()); + // // BLTOUCH // diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index a563bd4ed375e..b7136e445ed66 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -18,7 +18,7 @@ opt_set MOTHERBOARD BOARD_RAMBO \ FANMUX0_PIN 53 opt_disable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN USE_WATCHDOG opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TEST \ - FIX_MOUNTED_PROBE CODEPENDENT_XY_HOMING PIDTEMPBED PROBE_TEMP_COMPENSATION \ + FIX_MOUNTED_PROBE CODEPENDENT_XY_HOMING PIDTEMPBED PTC_PROBE PTC_BED \ PREHEAT_BEFORE_PROBING PROBING_HEATERS_OFF PROBING_FANS_OFF PROBING_STEPPERS_OFF WAIT_FOR_BED_HEATER \ EEPROM_SETTINGS SDSUPPORT SD_REPRINT_LAST_SELECTED_FILE BINARY_FILE_TRANSFER \ BLINKM PCA9533 PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ @@ -61,16 +61,16 @@ opt_disable MIN_SOFTWARE_ENDSTOP_Z MAX_SOFTWARE_ENDSTOPS exec_test $1 $2 "Rambo CNC Configuration" "$3" # -# Rambo heated bed only +# Rambo heated bed and probe temp sensor # restore_configs -opt_set MOTHERBOARD BOARD_RAMBO EXTRUDERS 0 TEMP_SENSOR_BED 1 \ +opt_set MOTHERBOARD BOARD_RAMBO EXTRUDERS 0 TEMP_SENSOR_BED 1 TEMP_SENSOR_PROBE 1 TEMP_PROBE_PIN 12 \ DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 4000 }' \ DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ AXIS_RELATIVE_MODES '{ false, false, false }' -opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER FIX_MOUNTED_PROBE Z_SAFE_HOMING exec_test $1 $2 "Rambo heated bed only" "$3" # diff --git a/ini/features.ini b/ini/features.ini index f54b645f85bb4..4c146512989f7 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -136,20 +136,20 @@ ADVANCED_PAUSE_FEATURE = src_filter=+ + HAS_POWER_MONITOR = src_filter=+ + POWER_LOSS_RECOVERY = src_filter=+ + -PROBE_TEMP_COMPENSATION = src_filter=+ + +HAS_PTC = src_filter=+ + HAS_FILAMENT_SENSOR = src_filter=+ + (EXT|MANUAL)_SOLENOID.* = src_filter=+ + MK2_MULTIPLEXER = src_filter=+ HAS_CUTTER = src_filter=+ + HAS_DRIVER_SAFE_POWER_PROTECT = src_filter=+ EXPERIMENTAL_I2CBUS = src_filter=+ + -MECHANICAL_GANTRY_CAL.+ = src_filter=+ -Z_MULTI_ENDSTOPS = src_filter=+ -Z_STEPPER_AUTO_ALIGN = src_filter=+ + G26_MESH_VALIDATION = src_filter=+ ASSISTED_TRAMMING = src_filter=+ + HAS_MESH = src_filter=+ HAS_LEVELING = src_filter=+ + +MECHANICAL_GANTRY_CAL.+ = src_filter=+ +Z_MULTI_ENDSTOPS|Z_STEPPER_AUTO_ALIGN = src_filter=+ +Z_STEPPER_AUTO_ALIGN = src_filter=+ DELTA_AUTO_CALIBRATION = src_filter=+ CALIBRATION_GCODE = src_filter=+ Z_MIN_PROBE_REPEATABILITY_TEST = src_filter=+ @@ -209,6 +209,7 @@ SDSUPPORT = src_filter=+ + GCODE_REPEAT_MARKERS = src_filter=+ + HAS_EXTRUDERS = src_filter=+ + + +HAS_TEMP_PROBE = src_filter=+ HAS_COOLER = src_filter=+ HAS_COOLER|LASER_COOLANT_FLOW_METER = src_filter=+ AUTO_REPORT_TEMPERATURES = src_filter=+ diff --git a/platformio.ini b/platformio.ini index 106e454d105f7..a364e8920f754 100644 --- a/platformio.ini +++ b/platformio.ini @@ -152,7 +152,7 @@ default_src_filter = + - - + - - - - - + - - - - @@ -229,6 +229,7 @@ default_src_filter = + - - + - - - + - - - - From 36e475b8beccd7bcc74335cbab69c5aa6ecbf61c Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 2 Nov 2021 12:34:53 +1300 Subject: [PATCH 007/273] =?UTF-8?q?=F0=9F=A9=B9=20Fill=20gaps=20in=20pinsD?= =?UTF-8?q?ebug=5Flist=20(#23051)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pinsDebug_list.h | 98 ++++++++++++++++++++++++++++++++ 1 file changed, 98 insertions(+) diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index f07b1cf025f75..05756d6004204 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -74,6 +74,16 @@ REPORT_NAME_ANALOG(__LINE__, MAIN_VOLTAGE_MEASURE_PIN) #endif #endif +#if PIN_EXISTS(POWER_MONITOR_CURRENT) + #if ANALOG_OK(POWER_MONITOR_CURRENT_PIN) + REPORT_NAME_ANALOG(__LINE__, POWER_MONITOR_CURRENT_PIN) + #endif +#endif +#if PIN_EXISTS(POWER_MONITOR_VOLTAGE) + #if ANALOG_OK(POWER_MONITOR_VOLTAGE_PIN) + REPORT_NAME_ANALOG(__LINE__, POWER_MONITOR_VOLTAGE_PIN) + #endif +#endif #if !defined(ARDUINO_ARCH_SAM) && !defined(ARDUINO_ARCH_SAMD) // TC1 & TC2 are macros in the SAM/SAMD tool chain #if _EXISTS(TC1) #if ANALOG_OK(TC1) @@ -131,6 +141,11 @@ REPORT_NAME_ANALOG(__LINE__, TEMP_BED_PIN) #endif #endif +#if PIN_EXISTS(TEMP_BOARD) + #if ANALOG_OK(TEMP_BOARD_PIN) + REPORT_NAME_ANALOG(__LINE__, TEMP_BOARD_PIN) + #endif +#endif #if PIN_EXISTS(TEMP_CHAMBER) #if ANALOG_OK(TEMP_CHAMBER_PIN) REPORT_NAME_ANALOG(__LINE__, TEMP_CHAMBER_PIN) @@ -141,6 +156,11 @@ REPORT_NAME_ANALOG(__LINE__, TEMP_COOLER_PIN) #endif #endif +#if PIN_EXISTS(TEMP_PROBE) + #if ANALOG_OK(TEMP_PROBE_PIN) + REPORT_NAME_ANALOG(__LINE__, TEMP_PROBE_PIN) + #endif +#endif #if PIN_EXISTS(ADC_KEYPAD) #if ANALOG_OK(ADC_KEYPAD_PIN) REPORT_NAME_ANALOG(__LINE__, ADC_KEYPAD_PIN) @@ -370,6 +390,9 @@ #if PIN_EXISTS(DIGIPOTSS) REPORT_NAME_DIGITAL(__LINE__, DIGIPOTSS_PIN) #endif +#if PIN_EXISTS(LCD_RESET) + REPORT_NAME_DIGITAL(__LINE__, LCD_RESET_PIN) +#endif #if _EXISTS(DOGLCD_A0) REPORT_NAME_DIGITAL(__LINE__, DOGLCD_A0) #endif @@ -433,6 +456,9 @@ #if PIN_EXISTS(E0_STEP) REPORT_NAME_DIGITAL(__LINE__, E0_STEP_PIN) #endif +#if PIN_EXISTS(E0_STDBY) + REPORT_NAME_DIGITAL(__LINE__, E0_STDBY_PIN) +#endif #if PIN_EXISTS(E1_AUTO_FAN) REPORT_NAME_DIGITAL(__LINE__, E1_AUTO_FAN_PIN) #endif @@ -457,6 +483,9 @@ #if PIN_EXISTS(E1_STEP) REPORT_NAME_DIGITAL(__LINE__, E1_STEP_PIN) #endif +#if PIN_EXISTS(E1_STDBY) + REPORT_NAME_DIGITAL(__LINE__, E1_STDBY_PIN) +#endif #if PIN_EXISTS(E2_AUTO_FAN) REPORT_NAME_DIGITAL(__LINE__, E2_AUTO_FAN_PIN) #endif @@ -481,6 +510,9 @@ #if PIN_EXISTS(E2_STEP) REPORT_NAME_DIGITAL(__LINE__, E2_STEP_PIN) #endif +#if PIN_EXISTS(E2_STDBY) + REPORT_NAME_DIGITAL(__LINE__, E2_STDBY_PIN) +#endif #if PIN_EXISTS(E3_AUTO_FAN) REPORT_NAME_DIGITAL(__LINE__, E3_AUTO_FAN_PIN) #endif @@ -505,6 +537,9 @@ #if PIN_EXISTS(E3_STEP) REPORT_NAME_DIGITAL(__LINE__, E3_STEP_PIN) #endif +#if PIN_EXISTS(E3_STDBY) + REPORT_NAME_DIGITAL(__LINE__, E3_STDBY_PIN) +#endif #if PIN_EXISTS(E4_AUTO_FAN) REPORT_NAME_DIGITAL(__LINE__, E4_AUTO_FAN_PIN) #endif @@ -529,6 +564,9 @@ #if PIN_EXISTS(E4_STEP) REPORT_NAME_DIGITAL(__LINE__, E4_STEP_PIN) #endif +#if PIN_EXISTS(E4_STDBY) + REPORT_NAME_DIGITAL(__LINE__, E4_STDBY_PIN) +#endif #if PIN_EXISTS(E5_AUTO_FAN) REPORT_NAME_DIGITAL(__LINE__, E5_AUTO_FAN_PIN) #endif @@ -553,6 +591,9 @@ #if PIN_EXISTS(E5_STEP) REPORT_NAME_DIGITAL(__LINE__, E5_STEP_PIN) #endif +#if PIN_EXISTS(E5_STDBY) + REPORT_NAME_DIGITAL(__LINE__, E5_STDBY_PIN) +#endif #if PIN_EXISTS(E6_AUTO_FAN) REPORT_NAME_DIGITAL(__LINE__, E6_AUTO_FAN_PIN) #endif @@ -577,6 +618,9 @@ #if PIN_EXISTS(E6_STEP) REPORT_NAME_DIGITAL(__LINE__, E6_STEP_PIN) #endif +#if PIN_EXISTS(E6_STDBY) + REPORT_NAME_DIGITAL(__LINE__, E6_STDBY_PIN) +#endif #if PIN_EXISTS(E7_AUTO_FAN) REPORT_NAME_DIGITAL(__LINE__, E7_AUTO_FAN_PIN) #endif @@ -601,6 +645,9 @@ #if PIN_EXISTS(E7_STEP) REPORT_NAME_DIGITAL(__LINE__, E7_STEP_PIN) #endif +#if PIN_EXISTS(E7_STDBY) + REPORT_NAME_DIGITAL(__LINE__, E7_STDBY_PIN) +#endif #if _EXISTS(ENET_CRS) REPORT_NAME_DIGITAL(__LINE__, ENET_CRS) #endif @@ -704,6 +751,9 @@ #if PIN_EXISTS(POWER_LOSS) REPORT_NAME_DIGITAL(__LINE__, POWER_LOSS_PIN) #endif +#if PIN_EXISTS(SAFE_POWER) + REPORT_NAME_DIGITAL(__LINE__, SAFE_POWER_PIN) +#endif #if PIN_EXISTS(FIL_RUNOUT) REPORT_NAME_DIGITAL(__LINE__, FIL_RUNOUT_PIN) #endif @@ -806,6 +856,15 @@ #if PIN_EXISTS(LED) REPORT_NAME_DIGITAL(__LINE__, LED_PIN) #endif +#if PIN_EXISTS(LED2) + REPORT_NAME_DIGITAL(__LINE__, LED2_PIN) +#endif +#if PIN_EXISTS(LED3) + REPORT_NAME_DIGITAL(__LINE__, LED3_PIN) +#endif +#if PIN_EXISTS(LED4) + REPORT_NAME_DIGITAL(__LINE__, LED4_PIN) +#endif #if PIN_EXISTS(LED_RED) REPORT_NAME_DIGITAL(__LINE__, LED_RED_PIN) #endif @@ -870,6 +929,12 @@ #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) REPORT_NAME_DIGITAL(__LINE__, MOTOR_CURRENT_PWM_E_PIN) #endif +#if PIN_EXISTS(MOTOR_CURRENT_PWM_E0) + REPORT_NAME_DIGITAL(__LINE__, MOTOR_CURRENT_PWM_E0_PIN) +#endif +#if PIN_EXISTS(MOTOR_CURRENT_PWM_E1) + REPORT_NAME_DIGITAL(__LINE__, MOTOR_CURRENT_PWM_E1_PIN) +#endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_X) REPORT_NAME_DIGITAL(__LINE__, MOTOR_CURRENT_PWM_X_PIN) #endif @@ -1146,6 +1211,9 @@ #if PIN_EXISTS(X_STEP) REPORT_NAME_DIGITAL(__LINE__, X_STEP_PIN) #endif +#if PIN_EXISTS(X_STDBY) + REPORT_NAME_DIGITAL(__LINE__, X_STDBY_PIN) +#endif #if PIN_EXISTS(X_STOP) REPORT_NAME_DIGITAL(__LINE__, X_STOP_PIN) #endif @@ -1209,6 +1277,9 @@ #if PIN_EXISTS(Y_STEP) REPORT_NAME_DIGITAL(__LINE__, Y_STEP_PIN) #endif +#if PIN_EXISTS(Y_STDBY) + REPORT_NAME_DIGITAL(__LINE__, Y_STDBY_PIN) +#endif #if PIN_EXISTS(Y_STOP) REPORT_NAME_DIGITAL(__LINE__, Y_STOP_PIN) #endif @@ -1272,6 +1343,9 @@ #if PIN_EXISTS(Z_STEP) REPORT_NAME_DIGITAL(__LINE__, Z_STEP_PIN) #endif +#if PIN_EXISTS(Z_STDBY) + REPORT_NAME_DIGITAL(__LINE__, Z_STDBY_PIN) +#endif #if PIN_EXISTS(Z_STOP) REPORT_NAME_DIGITAL(__LINE__, Z_STOP_PIN) #endif @@ -1290,6 +1364,9 @@ #if PIN_EXISTS(Z2_MIN) REPORT_NAME_DIGITAL(__LINE__, Z2_MIN_PIN) #endif +#if PIN_EXISTS(Z2_DIAG) + REPORT_NAME_DIGITAL(__LINE__, Z2_DIAG_PIN) +#endif #if PIN_EXISTS(Z2_MS1) REPORT_NAME_DIGITAL(__LINE__, Z2_MS1_PIN) #endif @@ -1302,6 +1379,9 @@ #if PIN_EXISTS(Z2_STEP) REPORT_NAME_DIGITAL(__LINE__, Z2_STEP_PIN) #endif +#if PIN_EXISTS(Z2_STOP) + REPORT_NAME_DIGITAL(__LINE__, Z2_STOP_PIN) +#endif #if PIN_EXISTS(Z3_CS) REPORT_NAME_DIGITAL(__LINE__, Z3_CS_PIN) #endif @@ -1584,6 +1664,24 @@ #if PIN_EXISTS(E7_SERIAL_RX) REPORT_NAME_DIGITAL(__LINE__, E7_SERIAL_RX_PIN) #endif +#if PIN_EXISTS(I_SERIAL_TX) + REPORT_NAME_DIGITAL(__LINE__, I_SERIAL_TX_PIN) +#endif +#if PIN_EXISTS(I_SERIAL_RX) + REPORT_NAME_DIGITAL(__LINE__, I_SERIAL_RX_PIN) +#endif +#if PIN_EXISTS(J_SERIAL_TX) + REPORT_NAME_DIGITAL(__LINE__, J_SERIAL_TX_PIN) +#endif +#if PIN_EXISTS(J_SERIAL_RX) + REPORT_NAME_DIGITAL(__LINE__, J_SERIAL_RX_PIN) +#endif +#if PIN_EXISTS(K_SERIAL_TX) + REPORT_NAME_DIGITAL(__LINE__, K_SERIAL_TX_PIN) +#endif +#if PIN_EXISTS(K_SERIAL_RX) + REPORT_NAME_DIGITAL(__LINE__, K_SERIAL_RX_PIN) +#endif #if PIN_EXISTS(L6470_CHAIN_SCK) REPORT_NAME_DIGITAL(__LINE__, L6470_CHAIN_SCK_PIN) #endif From 40477e031f16c2ecde535bc4ddae65c986060c9a Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 2 Nov 2021 12:36:22 +1300 Subject: [PATCH 008/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Y=5FSERIAL=5FRX=5F?= =?UTF-8?q?PIN=20for=20FYSETC=20S6=20(#23055)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index e2454b578dd00..37a48cab7fdc6 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -128,7 +128,7 @@ #define Y_SERIAL_TX_PIN PE14 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN PE13 + #define Y_SERIAL_RX_PIN PC4 #endif #ifndef Z_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PD11 From 6af344c19329b51307d38463c4912651ac1dcdaa Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 2 Nov 2021 01:02:55 +0000 Subject: [PATCH 009/273] [cron] Bump distribution date (2021-11-02) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 1eb431186e8fb..607561a87dd48 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 "2021-11-01" +//#define STRING_DISTRIBUTION_DATE "2021-11-02" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index aef8d8b60b530..c0dbd45fa2dde 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 "2021-11-01" + #define STRING_DISTRIBUTION_DATE "2021-11-02" #endif /** From 7942f71d26b58630a841f2de2d4f2abaa4120395 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 1 Nov 2021 20:23:24 -0700 Subject: [PATCH 010/273] =?UTF-8?q?=E2=9C=A8=20Artillery=20Ruby=20(STM32F4?= =?UTF-8?q?01RCT6)=20(#23029)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/HAL.cpp | 2 +- Marlin/src/core/boards.h | 1 + Marlin/src/pins/pins.h | 2 + Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h | 182 +++++++ .../boards/marlin_Artillery_Ruby.json | 60 +++ .../scripts/STM32F103RC_MEEB_3DP.py | 18 - .../PlatformIO/scripts/STM32F103RC_fysetc.py | 1 - .../MARLIN_ARTILLERY_RUBY/PeripheralPins.c | 247 +++++++++ .../MARLIN_ARTILLERY_RUBY/PinNamesVar.h | 33 ++ .../MARLIN_ARTILLERY_RUBY/hal_conf_custom.h | 496 ++++++++++++++++++ .../MARLIN_ARTILLERY_RUBY/ldscript.ld | 196 +++++++ .../MARLIN_ARTILLERY_RUBY/variant.cpp | 172 ++++++ .../variants/MARLIN_ARTILLERY_RUBY/variant.h | 148 ++++++ ini/stm32f4.ini | 14 + 14 files changed, 1552 insertions(+), 20 deletions(-) create mode 100644 Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h create mode 100644 buildroot/share/PlatformIO/boards/marlin_Artillery_Ruby.json create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/PeripheralPins.c create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/PinNamesVar.h create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/hal_conf_custom.h create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/ldscript.ld create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/variant.cpp create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/variant.h diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index a04a24c1123c0..0920a72ec1bcd 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -154,7 +154,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRe uint16_t HAL_adc_get_result() { return HAL_adc_result; } // Reset the system to initiate a firmware flash -void flashFirmware(const int16_t) { HAL_reboot(); } +WEAK void flashFirmware(const int16_t) { HAL_reboot(); } // Maple Compatibility volatile uint32_t systick_uptime_millis = 0; diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 2341e6577b60b..789512c4ef717 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -406,6 +406,7 @@ #define BOARD_INDEX_REV03 4234 // Index PnP Controller REV03 (STM32F407VET6/VGT6) #define BOARD_MKS_ROBIN_NANO_V1_3_F4 4235 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VET6) #define BOARD_MKS_EAGLE 4236 // MKS Eagle (STM32F407VET6) +#define BOARD_ARTILLERY_RUBY 4237 // Artillery Ruby (STM32F401RCT6) // // ARM Cortex M7 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 40bbe6b41bee9..369a78be7add0 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -667,6 +667,8 @@ #include "stm32f4/pins_MKS_ROBIN_NANO_V1_3_F4.h" // STM32F4 env:mks_robin_nano_v1_3_f4 #elif MB(MKS_EAGLE) #include "stm32f4/pins_MKS_EAGLE.h" // STM32F4 env:mks_eagle +#elif MB(ARTILLERY_RUBY) + #include "stm32f4/pins_ARTILLERY_RUBY.h" // STM32F4 env:Artillery_Ruby // // ARM Cortex M7 diff --git a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h new file mode 100644 index 0000000000000..4cf9768fbe805 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h @@ -0,0 +1,182 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "Artillery Ruby supports up to 1 hotends / E-steppers." +#endif + +#define BOARD_INFO_NAME "Artillery Ruby" + +#define FLASH_EEPROM_EMULATION +//#define I2C_EEPROM +//#define E2END 0xFFF // 4KB + +#define HAL_TIMER_RATE F_CPU + +// +// Limit Switches +// +#if (X_HOME_DIR == 1) + #define X_MIN_PIN -1 + #define X_MAX_PIN PA2 +#else + #define X_MIN_PIN PA2 + #define X_MAX_PIN -1 +#endif +#if (Y_HOME_DIR == 1) + #define Y_MIN_PIN -1 + #define Y_MAX_PIN PA1 +#else + #define Y_MIN_PIN PA1 + #define Y_MAX_PIN -1 +#endif +#if (Z_HOME_DIR == 1) + #define Z_MIN_PIN PC2 + #define Z_MAX_PIN PA0 +#else + #define Z_MIN_PIN PA0 + #define Z_MAX_PIN PC2 +#endif + +// +// Steppers +// +#define X_STEP_PIN PB14 +#define X_DIR_PIN PB13 +#define X_ENABLE_PIN PB15 + +#define Y_STEP_PIN PB10 +#define Y_DIR_PIN PB2 +#define Y_ENABLE_PIN PB12 + +#define Z_STEP_PIN PB0 +#define Z_DIR_PIN PC5 +#define Z_ENABLE_PIN PB1 + +#define E0_STEP_PIN PA7 +#define E0_DIR_PIN PA6 +#define E0_ENABLE_PIN PC4 + +#define E1_STEP_PIN PA4 +#define E1_DIR_PIN PA3 +#define E1_ENABLE_PIN PA5 + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC0 +#define TEMP_BED_PIN PC1 + +// +// Heaters / Fans +// +#ifndef HEATER_0_PIN + #define HEATER_0_PIN PC9 // Heater0 +#endif +#ifndef HEATER_BED_PIN + #define HEATER_BED_PIN PA8 // Hotbed +#endif +#ifndef FAN_PIN + #define FAN_PIN PC8 // Fan0 +#endif +#ifndef FAN1_PIN + #define FAN1_PIN PC7 // Fan1 +#endif +#ifndef FAN2_PIN + #define FAN2_PIN PC6 // Fan2 +#endif + +// +// Servos +// +#define SERVO0_PIN PC3 + +// +// SPI +// +#define SCK_PIN PC10 +#define MISO_PIN PC11 +#define MOSI_PIN PC12 + +// +// LCD / Controller +// +#if HAS_WIRED_LCD + #if EITHER(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 + #define DOGLCD_CS PC15 + #define DOGLCD_MOSI PB6 + #define DOGLCD_SCK PB5 + #define DOGLCD_A0 LCD_PINS_DC + #elif ENABLED(FYSETC_MINI_12864) + #define DOGLCD_CS PB6 + #define DOGLCD_A0 PC15 + + //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 + + #define LCD_RESET_PIN PB5 // Must be high or open for LCD to operate normally. + + #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN PB9 + #endif + #ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN PB8 + #endif + #ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN PB7 + #endif + #elif ENABLED(FYSETC_MINI_12864_2_1) + #define NEOPIXEL_PIN PB9 + #endif + + #define DEFAULT_LCD_CONTRAST 255 + #else + #define LCD_PINS_RS PC15 + #define LCD_PINS_ENABLE PB6 + #define LCD_PINS_D4 PB5 + #define LCD_PINS_D5 PB9 + #define LCD_PINS_D6 PB8 + #endif + + #define LCD_PINS_D7 PB7 + + // + // Beeper, SD Card, Encoder + // + #define BEEPER_PIN PC13 + + #if ENABLED(SDSUPPORT) + #define SDSS PA15 + #define SD_DETECT_PIN PD2 + #endif + + #define BTN_EN1 PB4 + #define BTN_EN2 PB3 + #define BTN_ENC PC14 +#endif diff --git a/buildroot/share/PlatformIO/boards/marlin_Artillery_Ruby.json b/buildroot/share/PlatformIO/boards/marlin_Artillery_Ruby.json new file mode 100644 index 0000000000000..e1c8333800cda --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_Artillery_Ruby.json @@ -0,0 +1,60 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F401xx", + "f_cpu": "84000000L", + "hwids": [ + [ + "0x0483", + "0xDF11" + ] + ], + "mcu": "stm32f401rct6", + "variant": "MARLIN_ARTILLERY_RUBY" + }, + "debug": { + "jlink_device": "STM32F401RC", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd", + "tools": { + "stlink": { + "server": { + "arguments": [ + "-f", + "scripts/interface/stlink.cfg", + "-c", + "transport select hla_swd", + "-f", + "scripts/target/stm32f4x.cfg", + "-c", + "reset_config none" + ], + "executable": "bin/openocd", + "package": "tool-openocd" + } + } + } + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "STM32F401RC (64k RAM. 256k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 65536, + "maximum_size": 262144, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/evaluation-tools/steval-3dp001v1.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py index 03e121c435d32..e059d445789c1 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py @@ -8,37 +8,19 @@ import os Import("env", "projenv") -# access to global build environment -print(env) -# access to project build environment (is used source files in "src" folder) -print(projenv) config = configparser.ConfigParser() config.read("platformio.ini") -#com_port = config.get("env:STM32F103RC_meeb", "upload_port") -#print('Use the {0:s} to reboot the board to dfu mode.'.format(com_port)) - # # Upload actions # - def before_upload(source, target, env): - print("before_upload") - # do some actions - # use com_port - # env.Execute("pwd") def after_upload(source, target, env): - print("after_upload") - # do some actions - # - # env.Execute("pwd") -print("Current build targets", map(str, BUILD_TARGETS)) - env.AddPreAction("upload", before_upload) env.AddPostAction("upload", after_upload) diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py index 668475dc010ae..07f6548b18d95 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py @@ -1,7 +1,6 @@ # # buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py # -import os from os.path import join from os.path import expandvars Import("env") diff --git a/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/PeripheralPins.c new file mode 100644 index 0000000000000..b2783d8c314e6 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/PeripheralPins.c @@ -0,0 +1,247 @@ +/* + ******************************************************************************* + * Copyright (c) 2019, 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 STM32F401R(B-C)Tx.xml + */ +#include "Arduino.h" +#include "PeripheralPins.h" + +/* ===== + * Note: Commented lines are alternative possibilities which are not used per default. + * If you change them, you will have to know what you do + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +WEAK const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 + {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 + {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 + {NC, NP, 0} +}; +#endif + +//*** No DAC *** + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SDA[] = { + {PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF9_I2C2)}, + {PB_4, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF9_I2C3)}, + {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + {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)}, + {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {NC, NP, 0} +}; +#endif + +//*** PWM *** + +#ifdef HAL_TIM_MODULE_ENABLED +WEAK const PinMap PinMap_PWM[] = { + {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 + {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 + {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 + {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 + {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + {PB_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_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {NC, NP, 0} +}; +#endif + +//*** SERIAL *** + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_TX[] = { + {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PA_11, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_RX[] = { + {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PA_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {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, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {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, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {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)}, + {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PA_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {NC, NP, 0} +}; +#endif + +//*** No CAN *** + +//*** No ETHERNET *** + +//*** No QUADSPI *** + +//*** USB *** + +#ifdef HAL_PCD_MODULE_ENABLED +WEAK const PinMap PinMap_USB_OTG_FS[] = { + {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF + {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS + {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID + {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM + {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP + {NC, NP, 0} +}; +#endif + +//*** No USB_OTG_HS *** + +//*** SD *** + +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { + {PB_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D4 + {PB_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D5 + {PC_6, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D6 + {PC_7, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D7 + {PC_8, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D0 + {PC_9, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D1 + {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D2 + {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D3 + {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CK + {PD_2, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CMD + {NC, NP, 0} +}; +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/PinNamesVar.h new file mode 100644 index 0000000000000..3082f8842ab3f --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/PinNamesVar.h @@ -0,0 +1,33 @@ +/* SYS_WKUP */ +#ifdef PWR_WAKEUP_PIN1 +SYS_WKUP1 = PA_0, +#endif +#ifdef PWR_WAKEUP_PIN2 +SYS_WKUP2 = NC, +#endif +#ifdef PWR_WAKEUP_PIN3 +SYS_WKUP3 = NC, +#endif +#ifdef PWR_WAKEUP_PIN4 +SYS_WKUP4 = NC, +#endif +#ifdef PWR_WAKEUP_PIN5 +SYS_WKUP5 = NC, +#endif +#ifdef PWR_WAKEUP_PIN6 +SYS_WKUP6 = NC, +#endif +#ifdef PWR_WAKEUP_PIN7 +SYS_WKUP7 = NC, +#endif +#ifdef PWR_WAKEUP_PIN8 +SYS_WKUP8 = NC, +#endif +/* USB */ +#ifdef USBCON +USB_OTG_FS_SOF = PA_8, +USB_OTG_FS_VBUS = PA_9, +USB_OTG_FS_ID = PA_10, +USB_OTG_FS_DM = PA_11, +USB_OTG_FS_DP = PA_12, +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/hal_conf_custom.h new file mode 100644 index 0000000000000..9fa98807d68e0 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/hal_conf_custom.h @@ -0,0 +1,496 @@ +/** + ****************************************************************************** + * @file stm32f4xx_hal_conf.h + * @brief HAL configuration file. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 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 + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_CONF_CUSTOM +#define __STM32F4xx_HAL_CONF_CUSTOM + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ + /** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +/* #define HAL_CAN_MODULE_ENABLED */ +/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_CEC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +//#define HAL_DAC_MODULE_ENABLED +/* #define HAL_DCMI_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED +/* #define HAL_DMA2D_MODULE_ENABLED */ +/* #define HAL_ETH_MODULE_ENABLED */ +#define HAL_FLASH_MODULE_ENABLED +/* #define HAL_NAND_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_PCCARD_MODULE_ENABLED */ +/* #define HAL_SRAM_MODULE_ENABLED */ +/* #define HAL_SDRAM_MODULE_ENABLED */ +/* #define HAL_HASH_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +/* #define HAL_SMBUS_MODULE_ENABLED */ +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_LTDC_MODULE_ENABLED */ +/* #define HAL_DSI_MODULE_ENABLED */ +#define HAL_PWR_MODULE_ENABLED +/* #define HAL_QSPI_MODULE_ENABLED */ +#define HAL_RCC_MODULE_ENABLED +/* #define HAL_RNG_MODULE_ENABLED */ +/* #define HAL_RTC_MODULE_ENABLED */ +/* #define HAL_SAI_MODULE_ENABLED */ +/* #define HAL_SD_MODULE_ENABLED */ +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +/* #define HAL_UART_MODULE_ENABLED */ +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ +#define HAL_CORTEX_MODULE_ENABLED +#ifndef HAL_PCD_MODULE_ENABLED + #define HAL_PCD_MODULE_ENABLED //Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE) +#endif +/* #define HAL_HCD_MODULE_ENABLED */ +/* #define HAL_FMPI2C_MODULE_ENABLED */ +/* #define HAL_SPDIFRX_MODULE_ENABLED */ +/* #define HAL_DFSDM_MODULE_ENABLED */ +/* #define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_MMC_MODULE_ENABLED */ + +/* ########################## HSE/HSI Values adaptation ##################### */ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#ifndef HSE_VALUE +#define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#ifndef HSE_STARTUP_TIMEOUT +#define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#ifndef HSI_VALUE +#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz */ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#ifndef LSI_VALUE +#define LSI_VALUE 32000U /*!< LSI Typical Value in Hz */ +#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz +The real value may vary depending on the variations +in voltage and temperature. */ +/** + * @brief External Low Speed oscillator (LSE) value. + */ +#ifndef LSE_VALUE +#define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */ +#endif /* LSE_VALUE */ + +#ifndef LSE_STARTUP_TIMEOUT +#define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#ifndef EXTERNAL_CLOCK_VALUE +#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#if !defined (VDD_VALUE) +#define VDD_VALUE 3300U /*!< Value of VDD in mv */ +#endif +#if !defined (TICK_INT_PRIORITY) +#define TICK_INT_PRIORITY 0x00U /*!< tick interrupt priority */ +#endif +#if !defined (USE_RTOS) +#define USE_RTOS 0U +#endif +#if !defined (PREFETCH_ENABLE) +#define PREFETCH_ENABLE 1U +#endif +#if !defined (INSTRUCTION_CACHE_ENABLE) +#define INSTRUCTION_CACHE_ENABLE 1U +#endif +#if !defined (DATA_CACHE_ENABLE) +#define DATA_CACHE_ENABLE 1U +#endif + +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ +#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ +#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ +#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ +#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ +#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ +#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ +#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */ +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ +#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ +#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ +#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ +#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1U */ + +/* ################## Ethernet peripheral configuration ##################### */ + +/* Section 1 : Ethernet peripheral configuration */ + +/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ +#define MAC_ADDR0 2U +#define MAC_ADDR1 0U +#define MAC_ADDR2 0U +#define MAC_ADDR3 0U +#define MAC_ADDR4 0U +#define MAC_ADDR5 0U + +/* Definition of the Ethernet driver buffers size and count */ +#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ +#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ +#define ETH_RXBUFNB ((uint32_t)4U) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */ +#define ETH_TXBUFNB ((uint32_t)4U) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */ + +/* Section 2: PHY configuration section */ + +/* DP83848_PHY_ADDRESS Address*/ +#define DP83848_PHY_ADDRESS 0x01U +/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ +#define PHY_RESET_DELAY 0x000000FFU +/* PHY Configuration delay */ +#define PHY_CONFIG_DELAY 0x00000FFFU + +#define PHY_READ_TO 0x0000FFFFU +#define PHY_WRITE_TO 0x0000FFFFU + +/* Section 3: Common PHY Registers */ + +#define PHY_BCR ((uint16_t)0x0000) /*!< Transceiver Basic Control Register */ +#define PHY_BSR ((uint16_t)0x0001) /*!< Transceiver Basic Status Register */ + +#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ +#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ +#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ +#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ +#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ +#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ +#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ +#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ +#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ +#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ + +#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ +#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ +#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ + +/* Section 4: Extended PHY Registers */ +#define PHY_SR ((uint16_t)0x10U) /*!< PHY status register Offset */ + +#define PHY_SPEED_STATUS ((uint16_t)0x0002U) /*!< PHY Speed mask */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0004U) /*!< PHY Duplex mask */ + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver + * Activated: CRC code is present inside driver + * Deactivated: CRC code cleaned from driver + */ +#ifndef USE_SPI_CRC +#define USE_SPI_CRC 0U +#endif + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED +#include "stm32f4xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED +#include "stm32f4xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED +#include "stm32f4xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED +#include "stm32f4xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED +#include "stm32f4xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED +#include "stm32f4xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED +#include "stm32f4xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED +#include "stm32f4xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED +#include "stm32f4xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED +#include "stm32f4xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED +#include "stm32f4xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED +#include "stm32f4xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED +#include "stm32f4xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED +#include "stm32f4xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED +#include "stm32f4xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED +#include "stm32f4xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED +#include "stm32f4xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED +#include "stm32f4xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_PCCARD_MODULE_ENABLED +#include "stm32f4xx_hal_pccard.h" +#endif /* HAL_PCCARD_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED +#include "stm32f4xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED +#include "stm32f4xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED +#include "stm32f4xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED +#include "stm32f4xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED +#include "stm32f4xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED +#include "stm32f4xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED +#include "stm32f4xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED +#include "stm32f4xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED +#include "stm32f4xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED +#include "stm32f4xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED +#include "stm32f4xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED +#include "stm32f4xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED +#include "stm32f4xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED +#include "stm32f4xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED +#include "stm32f4xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED +#include "stm32f4xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED +#include "stm32f4xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED +#include "stm32f4xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED +#include "stm32f4xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED +#include "stm32f4xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED +#include "stm32f4xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED +#include "stm32f4xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED +#include "stm32f4xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED +#include "stm32f4xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_FMPI2C_MODULE_ENABLED +#include "stm32f4xx_hal_fmpi2c.h" +#endif /* HAL_FMPI2C_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED +#include "stm32f4xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED +#include "stm32f4xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED +#include "stm32f4xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_MMC_MODULE_ENABLED +#include "stm32f4xx_hal_mmc.h" +#endif /* HAL_MMC_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ +#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ +void assert_failed(uint8_t *file, uint32_t line); +#else +#define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_CONF_CUSTOM_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/ldscript.ld new file mode 100644 index 0000000000000..57c01c8df8fc5 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/ldscript.ld @@ -0,0 +1,196 @@ +/* +***************************************************************************** +** +** File : ldscript.ld +** +** Abstract : Linker script for STM32F401RETx Device with +** 512KByte FLASH, 96KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +***************************************************************************** +** @attention +** +**

© COPYRIGHT(c) 2014 Ac6

+** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** 1. Redistributions of source code must retain the above copyright notice, +** this list of conditions and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright notice, +** this list of conditions and the following disclaimer in the documentation +** and/or other materials provided with the distribution. +** 3. Neither the name of Ac6 nor the names of its contributors +** may be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20010000; /* 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 +{ +BOOT (rx) : ORIGIN = 0x08000000, LENGTH = 16K +EMULATED_EEPROM (rx) : ORIGIN = 0x08004000, LENGTH = 16K +FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 256K - 16K * 2 +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >BOOT + + .boot : + { + . = ALIGN(4); + *(.text.Reset_Handler) + . = ALIGN(4); + } >BOOT + + /* 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 */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} + + diff --git a/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/variant.cpp new file mode 100644 index 0000000000000..8f24d68e2f9ac --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/variant.cpp @@ -0,0 +1,172 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "pins_arduino.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// Pin number +const PinName digitalPin[] = { + PA_0, //D0 + PA_1, //D1 + PA_2, //D2 + PA_3, //D3 + PA_4, //D4 + PA_5, //D5 + PA_6, //D6 + PA_7, //D7 + PA_8, //D8 + PA_9, //D9 + PA_10, //D10 + PA_11, //D11 + PA_12, //D12 + PA_13, //D13 + PA_14, //D14 + PA_15, //D15 + PB_0, //D16 + PB_1, //D17 + PB_2, //D18 + PB_3, //D19 + PB_4, //D20 + PB_5, //D21 + PB_6, //D22 + PB_7, //D23 + PB_8, //D24 + PB_9, //D25 + PB_10, //D26 + PB_12, //D27 + PB_13, //D28 + PB_14, //D29 + PB_15, //D30 + PC_0, //D31 + PC_1, //D32 + PC_2, //D33 + PC_3, //D34 + PC_4, //D35 + PC_5, //D36 + PC_6, //D37 + PC_7, //D38 + PC_8, //D39 + PC_9, //D40 + PC_10, //D41 + PC_11, //D42 + PC_12, //D43 + PC_13, //D44 + PC_14, //D45 + PC_15, //D46 + PD_2, //D47 + PH_0, //D48 + PH_1, //D49 + + //Duplicated ADC Pins + PA_0, //D50/A0 + PA_1, //D51/A1 + PA_2, //D52/A2 + PA_3, //D53/A3 + PA_4, //D54/A4 + PA_5, //D55/A5 + PA_6, //D56/A6 + PA_7, //D57/A7 + PB_0, //D58/A8 + PB_1, //D59/A9 + PC_0, //D60/A10 + PC_1, //D61/A11 + PC_2, //D62/A12 + PC_3, //D63/A13 + PC_4, //D64/A14 + PC_5 //D65/A15 +}; + +#ifdef __cplusplus +} +#endif + +// ---------------------------------------------------------------------------- + +#ifdef __cplusplus +extern "C" { +#endif +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 84000000 + * HCLK(Hz) = 84000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 2 + * APB2 Prescaler = 1 + * HSE Frequency(Hz) = 8000000 + * PLL_M = 8 + * PLL_N = 336 + * PLL_P = 4 + * PLL_Q = 7 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale2 mode + * Flash Latency(WS) = 2 + * @param None + * @retval None + */ +WEAK void SystemClock_Config(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2); + + /* Enable HSI Oscillator and activate PLL with HSI as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = 8; + RCC_OscInitStruct.PLL.PLLN = 336; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; + RCC_OscInitStruct.PLL.PLLQ = 7; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + /* Initialization Error */ + while (1); + } + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) { + /* Initialization Error */ + while (1); + } +} + +#ifdef __cplusplus +} +#endif + +void flashFirmware(const int16_t) { + *((unsigned long *)0x2000FFF0) = 0xDEADBEEF; // End of RAM + NVIC_SystemReset(); +} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/variant.h new file mode 100644 index 0000000000000..0c66ae89b88a6 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/variant.h @@ -0,0 +1,148 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _VARIANT_ARDUINO_STM32_ +#define _VARIANT_ARDUINO_STM32_ + +#ifdef __cplusplus +extern "C" { +#endif // __cplusplus + +/*---------------------------------------------------------------------------- + * Pins + *----------------------------------------------------------------------------*/ + + +#define PA0 0 //D0 +#define PA1 1 //D1 +#define PA2 2 //D2 +#define PA3 3 //D3 +#define PA4 4 //D4 +#define PA5 5 //D5 +#define PA6 6 //D6 +#define PA7 7 //D7 +#define PA8 8 //D8 +#define PA9 9 //D9 +#define PA10 10 //D10 +#define PA11 11 //D11 +#define PA12 12 //D12 +#define PA13 13 //D13 +#define PA14 14 //D14 +#define PA15 15 //D15 +#define PB0 16 //D16 +#define PB1 17 //D17 +#define PB2 18 //D18 +#define PB3 19 //D19 +#define PB4 20 //D20 +#define PB5 21 //D21 +#define PB6 22 //D22 +#define PB7 23 //D23 +#define PB8 24 //D24 +#define PB9 25 //D25 +#define PB10 26 //D26 +#define PB12 27 //D27 +#define PB13 28 //D28 +#define PB14 29 //D29 +#define PB15 30 //D30 +#define PC0 31 //D31 +#define PC1 32 //D32 +#define PC2 33 //D33 +#define PC3 34 //D34 +#define PC4 35 //D35 +#define PC5 36 //D36 +#define PC6 37 //D37 +#define PC7 38 //D38 +#define PC8 39 //D39 +#define PC9 40 //D40 +#define PC10 41 //D41 +#define PC11 42 //D42 +#define PC12 43 //D43 +#define PC13 44 //D44 +#define PC14 45 //D45 +#define PC15 46 //D46 +#define PD2 47 //D47 +#define PH0 48 //D48 +#define PH1 49 //D49 + +// This must be a literal +#define NUM_DIGITAL_PINS 66 +// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS +#define NUM_ANALOG_INPUTS 16 +#define NUM_ANALOG_FIRST 50 + +/* +// PWM resolution +#define PWM_RESOLUTION 8 +#define PWM_FREQUENCY 20000 // >= 20 Khz => inaudible noise for fans +#define PWM_MAX_DUTY_CYCLE 255 +*/ + +// SPI Definitions +#define PIN_SPI_MOSI PC12 +#define PIN_SPI_MISO PC11 +#define PIN_SPI_SCK PC10 +#define PIN_SPI_SS PA15 + +// Timer Definitions +// TIM1 - Hardware PWM (HB) +// TIM2 - TIMER_SERVO +// TIM3 - Hardware PWM (FAN0/1/2, HE0) +// TIM4 - Hardware PWM (LED_R/G/B) +// TIM5 - TIMER_TONE +// TIM9 - STEP_TIMER +// TIM10 - TEMP_TIMER +// TIM11 - +#define TIMER_SERVO TIM2 +#define TIMER_TONE TIM5 + +// UART Definitions +#define SERIAL_UART_INSTANCE 1 + +// Default pin used for 'Serial' instance (ex: ST-Link) +// Mandatory for Firmata +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +#ifdef __cplusplus +} // extern "C" +#endif +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus +// These serial port names are intended to allow libraries and architecture-neutral +// sketches to automatically default to the correct port name for a particular type +// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, +// the first hardware serial port whose RX/TX pins are not dedicated to another use. +// +// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor +// +// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial +// +// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library +// +// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. +// +// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX +// pins are NOT connected to anything by default. +#define SERIAL_PORT_MONITOR Serial +#define SERIAL_PORT_HARDWARE Serial +#endif + +#endif /* _VARIANT_ARDUINO_STM32_ */ diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 850807585ff38..0e9b507c8b221 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -564,3 +564,17 @@ build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC debug_tool = jlink upload_protocol = jlink + +# +# Artillery Ruby +# +[env:Artillery_Ruby] +platform = ${common_stm32.platform} +extends = common_stm32 +board = marlin_Artillery_Ruby +build_flags = ${common_stm32.build_flags} + -DSTM32F401xC -DTARGET_STM32F4 -DDISABLE_GENERIC_SERIALUSB -DARDUINO_ARCH_STM32 + -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS + -DUSB_PRODUCT=\"Artillery_3D_Printer\" +extra_scripts = ${common_stm32.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py From 498937967482faf7b299c2119c258c8ce7090ce9 Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Tue, 2 Nov 2021 10:29:23 +0700 Subject: [PATCH 011/273] =?UTF-8?q?=F0=9F=8E=A8=20Fix=20redefine=20warning?= =?UTF-8?q?s=20(#23061)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins_postprocess.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index a2fe2b9af3a46..d1047db0d7ce3 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -1260,22 +1260,22 @@ // Disable unused endstop / probe pins // #define _STOP_IN_USE(N) (X2_USE_ENDSTOP == N || Y2_USE_ENDSTOP == N || Z2_USE_ENDSTOP == N || Z3_USE_ENDSTOP == N || Z4_USE_ENDSTOP == N) -#if _STOP_IN_USE(_XMAX_) +#if !defined(USE_XMAX_PLUG) && _STOP_IN_USE(_XMAX_) #define USE_XMAX_PLUG #endif -#if _STOP_IN_USE(_YMAX_) +#if !defined(USE_YMAX_PLUG) && _STOP_IN_USE(_YMAX_) #define USE_YMAX_PLUG #endif -#if _STOP_IN_USE(_ZMAX_) +#if !defined(USE_ZMAX_PLUG) && _STOP_IN_USE(_ZMAX_) #define USE_ZMAX_PLUG #endif -#if _STOP_IN_USE(_XMIN_) +#if !defined(USE_XMIN_PLUG) && _STOP_IN_USE(_XMIN_) #define USE_XMIN_PLUG #endif -#if _STOP_IN_USE(_YMIN_) +#if !defined(USE_YMIN_PLUG) && _STOP_IN_USE(_YMIN_) #define USE_YMIN_PLUG #endif -#if _STOP_IN_USE(_ZMIN_) +#if !defined(USE_ZMIN_PLUG) && _STOP_IN_USE(_ZMIN_) #define USE_ZMIN_PLUG #endif #undef _STOP_IN_USE From a57355ee06e59fb3d89ab56f8749eb5549efbee3 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 1 Nov 2021 21:23:54 -0700 Subject: [PATCH 012/273] =?UTF-8?q?=E2=9C=A8=20Allow=20Low=20EJERK=20with?= =?UTF-8?q?=20LA,=20optional=20(#23054)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 1 + Marlin/src/inc/SanityCheck.h | 4 ++-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index aa6fffd44ec92..934ceceafd20e 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1913,6 +1913,7 @@ #define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed //#define LA_DEBUG // If enabled, this will generate debug information output over USB. //#define EXPERIMENTAL_SCURVE // Enable this option to permit S-Curve Acceleration + //#define ALLOW_LOW_EJERK // Allow a DEFAULT_EJERK value of <10. Recommended for direct drive hotends. #endif // @section leveling diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index c8d30a27188ad..b4eaf242b7073 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1246,8 +1246,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "LIN_ADVANCE and S_CURVE_ACCELERATION may not play well together! Enable EXPERIMENTAL_SCURVE to continue." #elif ENABLED(DIRECT_STEPPING) #error "DIRECT_STEPPING is incompatible with LIN_ADVANCE. Enable in external planner if possible." - #elif !HAS_JUNCTION_DEVIATION && defined(DEFAULT_EJERK) - static_assert(DEFAULT_EJERK >= 10, "It is strongly recommended to set DEFAULT_EJERK >= 10 when using LIN_ADVANCE."); + #elif NONE(HAS_JUNCTION_DEVIATION, ALLOW_LOW_EJERK) && defined(DEFAULT_EJERK) + static_assert(DEFAULT_EJERK >= 10, "It is strongly recommended to set DEFAULT_EJERK >= 10 when using LIN_ADVANCE. Enable ALLOW_LOW_EJERK to bypass this alert (e.g., for direct drive)."); #endif #endif From 767a15d468ab6859eec19600541ad21dff757d1a Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 1 Nov 2021 22:43:40 -0700 Subject: [PATCH 013/273] =?UTF-8?q?=F0=9F=94=A7=20Endstop=20/=20DIAG=20hom?= =?UTF-8?q?ing=20conflict=20warning=20(#23050)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/inc/Warnings.cpp | 9 +++++++++ Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 4 +++- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 2 ++ Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 2 ++ Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 2 ++ Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 2 ++ Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h | 2 ++ Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 5 +++-- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 1 + Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 8 +++++--- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 2 ++ Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 9 ++++----- Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 6 +++--- Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h | 5 +++-- Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 3 +-- Marlin/src/pins/stm32f4/pins_LERDGE_K.h | 3 +-- Marlin/src/pins/stm32f4/pins_LERDGE_S.h | 3 +-- Marlin/src/pins/stm32f4/pins_LERDGE_X.h | 3 +-- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 4 ++-- Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 6 ++---- Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h | 3 +-- Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 3 +-- Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h | 3 +-- 24 files changed, 55 insertions(+), 37 deletions(-) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 09dd53d6f65c6..d7bacaef32a80 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -1130,7 +1130,7 @@ class GcodeSuite { static void M913(); static void M913_report(const bool forReplay=true); #endif - #if ENABLED(USE_SENSORLESS) + #if USE_SENSORLESS static void M914(); static void M914_report(const bool forReplay=true); #endif diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index d258aefd82f7a..251094901051c 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -488,3 +488,12 @@ #if HOMING_Z_WITH_PROBE && IS_CARTESIAN && DISABLED(Z_SAFE_HOMING) #error "Z_SAFE_HOMING is recommended when homing with a probe. Enable Z_SAFE_HOMING or comment out this line to continue." #endif + +// +// Warn users of potential endstop/DIAG pin conflicts to prevent homing issues when not using sensorless homing +// +#if !USE_SENSORLESS && ENABLED(USES_DIAG_JUMPERS) + #warning "Motherboard DIAG jumpers must be removed when SENSORLESS_HOMING is disabled." +#elif !USE_SENSORLESS && ENABLED(USES_DIAG_PINS) + #warning "Driver DIAG pins must be physically removed unless SENSORLESS_HOMING is enabled. (See https://bit.ly/2ZPRlt0)" +#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 ec8f31b854d85..97d78c0d2434d 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -26,7 +26,9 @@ */ #define BOARD_INFO_NAME "BTT SKR V1.3" -#define LPC1768_IS_SKRV1_3 1 + +#define LPC1768_IS_SKRV1_3 +#define USES_DIAG_JUMPERS // // Trinamic Stallguard pins 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 a072242adc746..b9dc845c5b777 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -35,6 +35,8 @@ #define BOARD_CUSTOM_BUILD_FLAGS -DLPC_PINCFG_UART3_P4_28 #endif +#define USES_DIAG_PINS + // // EEPROM // diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index d6b1eeab46706..15afe7e238375 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -30,6 +30,8 @@ #define BOARD_INFO_NAME "MKS SGen-L" #define BOARD_WEBSITE_URL "github.com/makerbase-mks/MKS-SGEN_L" +#define USES_DIAG_JUMPERS + // // Servos // 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 9c514f8ca318a..bdc49fc236480 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -31,6 +31,8 @@ #define BOARD_INFO_NAME "BTT SKR E3 Turbo" #endif +#define USES_DIAG_JUMPERS + // Onboard I2C EEPROM #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x1000 // 4KB (AT24C32) 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 bb39009f094f4..8107f11937cda 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -30,6 +30,8 @@ #define BOARD_INFO_NAME "MKS SGEN_L V2" #define BOARD_WEBSITE_URL "github.com/makerbase-mks" +#define USES_DIAG_JUMPERS + // // EEPROM, MKS SGEN_L V2.0 hardware has 4K EEPROM on the board // 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 48d38e22136d2..c132691c2090f 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 @@ -26,6 +26,8 @@ // Release PB3/PB4 (E0 STP/DIR) from JTAG pins #define DISABLE_JTAG +#define USES_DIAG_JUMPERS + // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 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 a221ce94c5325..a34099120ebf4 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -27,10 +27,11 @@ #include "env_validate.h" -#define BOARD_NO_NATIVE_USB - #define BOARD_WEBSITE_URL "github.com/makerbase-mks" +#define BOARD_NO_NATIVE_USB +#define USES_DIAG_JUMPERS + //#define DISABLE_DEBUG #define DISABLE_JTAG 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 3df6727d03425..1cdee92b088d9 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -36,6 +36,7 @@ #define BOARD_INFO_NAME "MKS Robin nano V2.0" #define BOARD_NO_NATIVE_USB +#define USES_DIAG_PINS // Avoid conflict with TIMER_SERVO when using the STM32 HAL #define TEMP_TIMER 5 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 44485b0776c3d..b7ffcce4a86cc 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -29,6 +29,11 @@ #define BOARD_INFO_NAME "BTT BTT002 V1.0" +#define USES_DIAG_PINS + +// Ignore temp readings during development. +//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 + // Use one of these or SDCard-based Emulation will be used #if NO_EEPROM_SELECTED //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation @@ -41,9 +46,6 @@ #define FLASH_EEPROM_LEVELING #endif -// Ignore temp readings during development. -//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 - // // Limit Switches // diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index bd483ecf0ae8d..d1f38f5c8098f 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -29,6 +29,8 @@ #define BOARD_INFO_NAME "BTT E3 RRF" #endif +#define USES_DIAG_JUMPERS + // Add-on board for IDEX conversion //#define BTT_E3_RRF_IDEX_BOARD 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 95f74efe84988..dfa9d8a7b9ddb 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -31,15 +31,14 @@ #define BOARD_INFO_NAME "BTT GTR V1.0" +#define USES_DIAG_JUMPERS +#define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support +#define M5_EXTENDER // The M5 extender is attached + // Onboard I2C EEPROM #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x2000 // 8KB (24C64 ... 64Kb = 8KB) -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT - -#define M5_EXTENDER // The M5 extender is attached - // // Servos // 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 655e65da47a36..6dc90bf910ef9 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -23,15 +23,15 @@ #include "env_validate.h" +#define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support +#define USES_DIAG_JUMPERS + // Onboard I2C EEPROM #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x8000 // 32KB (24C32A) #define I2C_SCL_PIN PB8 #define I2C_SDA_PIN PB9 -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT - // Avoid conflict with TIMER_TONE #define STEP_TIMER 10 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 3314d0154da15..ac049baa2122b 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -23,6 +23,8 @@ #include "env_validate.h" +#define USES_DIAG_JUMPERS + // If you have the BigTreeTech driver expansion module, enable BTT_MOTOR_EXPANSION // https://github.com/bigtreetech/BTT-Expansion-module/tree/master/BTT%20EXP-MOT //#define BTT_MOTOR_EXPANSION @@ -47,8 +49,7 @@ #define FLASH_EEPROM_LEVELING #endif -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT +#define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support // // Servos 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 50330932cf879..9a280eac1643c 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 @@ -47,8 +47,7 @@ #define FLASH_EEPROM_LEVELING #endif -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT +#define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support // Avoid conflict with TIMER_TONE #define STEP_TIMER 10 diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index 6ad3849d11bde..099b3b79a4972 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -40,8 +40,7 @@ #define MARLIN_EEPROM_SIZE 0x10000 #endif -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT +#define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support // // Servos diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h index 68e5636955031..c686e19ccb294 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h @@ -34,8 +34,7 @@ #define STEP_TIMER 4 #define TEMP_TIMER 2 -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT +#define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support // // Servos diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h index 7f35c0f5dd7f0..93526db4425c8 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h @@ -39,8 +39,7 @@ #define I2C_SDA_PIN PB9 #define MARLIN_EEPROM_SIZE 0x10000 // FM24CL64 F-RAM 64K (8Kx8) -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT +#define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support // // Servos diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index 8fa211dc95027..a7f853185e1dc 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -32,8 +32,8 @@ #define BOARD_INFO_NAME "MKS Monster8 V1.x" -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT +#define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support +#define USES_DIAG_JUMPERS //#define DISABLE_DEBUG diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 4dc73e0312703..02140865f96ae 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -32,22 +32,20 @@ #define BOARD_INFO_NAME "MKS Robin Nano V3" +#define USES_DIAG_JUMPERS + #ifndef X_CS_PIN #define X_CS_PIN PD5 #endif - #ifndef Y_CS_PIN #define Y_CS_PIN PD7 #endif - #ifndef Z_CS_PIN #define Z_CS_PIN PD4 #endif - #ifndef E0_CS_PIN #define E0_CS_PIN PD9 #endif - #ifndef E1_CS_PIN #define E1_CS_PIN PD8 #endif 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 c3e3963b551fd..256439e654dc7 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 @@ -26,8 +26,7 @@ // MKS Robin Nano V3, MKS Eagle pinmap // -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT +#define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support // Avoid conflict with TIMER_TONE #define STEP_TIMER 10 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index 46dec71c11c1b..68b238525477f 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -39,8 +39,7 @@ #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x1000 // 4KB -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT +#define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h index 991c611a89f6c..9eb0acf1448d4 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h @@ -32,8 +32,7 @@ #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x1000 // 4KB (24C32 ... 32Kb = 4KB) -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT +#define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support // // Limit Switches From da830e6ced7f7c7e509e748104245064d1c1b265 Mon Sep 17 00:00:00 2001 From: Andrei M <22990561+andrei-moraru@users.noreply.github.com> Date: Tue, 2 Nov 2021 01:47:16 -0400 Subject: [PATCH 014/273] =?UTF-8?q?=E2=9A=97=EF=B8=8F=20Use=20pwm=5Fset=5F?= =?UTF-8?q?duty=20over=20analogWrite=20to=20set=20PWM=20(#23048)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/HAL/AVR/HAL.h | 2 +- Marlin/src/HAL/AVR/fast_pwm.cpp | 62 +++++++++++++-------------- Marlin/src/HAL/DUE/HAL.h | 5 +++ Marlin/src/HAL/ESP32/HAL.h | 4 ++ Marlin/src/HAL/LINUX/HAL.h | 3 ++ Marlin/src/HAL/LPC1768/fast_pwm.cpp | 16 +++---- Marlin/src/HAL/NATIVE_SIM/HAL.h | 3 ++ Marlin/src/HAL/SAMD51/HAL.h | 5 +++ Marlin/src/HAL/STM32/fast_pwm.cpp | 37 ++++++++-------- Marlin/src/HAL/STM32F1/HAL.cpp | 3 +- Marlin/src/HAL/STM32F1/fast_pwm.cpp | 60 +++++++++++++------------- Marlin/src/HAL/TEENSY31_32/HAL.h | 6 +++ Marlin/src/HAL/TEENSY35_36/HAL.h | 6 +++ Marlin/src/HAL/TEENSY40_41/HAL.cpp | 10 ++--- Marlin/src/HAL/TEENSY40_41/HAL.h | 8 +++- Marlin/src/feature/caselight.cpp | 2 +- Marlin/src/feature/controllerfan.cpp | 7 +-- Marlin/src/feature/leds/leds.cpp | 10 ++--- Marlin/src/feature/spindle_laser.cpp | 6 +-- Marlin/src/gcode/control/M42.cpp | 4 +- Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 2 +- Marlin/src/lcd/tft/ui_common.cpp | 2 +- Marlin/src/module/endstops.cpp | 2 +- Marlin/src/module/planner.cpp | 6 +-- Marlin/src/module/stepper.cpp | 2 +- Marlin/src/module/temperature.cpp | 10 ++--- 26 files changed, 158 insertions(+), 125 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index ecb566ed46bd0..ad1f47a4e685e 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -221,7 +221,7 @@ void set_pwm_frequency(const pin_t pin, int f_desired); /** * set_pwm_duty - * Sets the PWM duty cycle of the provided pin to the provided value + * Set the PWM duty cycle of the provided pin to the provided value * Optionally allows inverting the duty cycle [default = false] * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] */ diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index 238c1124adeb6..2556fa0441212 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -22,11 +22,10 @@ #ifdef __AVR__ #include "../../inc/MarlinConfigPre.h" +#include "HAL.h" #if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM -#include "HAL.h" - struct Timer { volatile uint8_t* TCCRnQ[3]; // max 3 TCCR registers per timer volatile uint16_t* OCRnQ[3]; // max 3 OCR registers per timer @@ -153,7 +152,7 @@ Timer get_pwm_timer(const pin_t pin) { void set_pwm_frequency(const pin_t pin, int f_desired) { Timer timer = get_pwm_timer(pin); - if (timer.n == 0) return; // Don't proceed if protected timer or not recognised + if (timer.n == 0) return; // Don't proceed if protected timer or not recognized uint16_t size; if (timer.n == 2) size = 255; else size = 65535; @@ -243,40 +242,39 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { _SET_ICRn(timer.ICRn, res); // Set ICRn value (TOP) = res } +#endif // NEEDS_HARDWARE_PWM + void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { - // If v is 0 or v_size (max), digitalWrite to LOW or HIGH. - // Note that digitalWrite also disables pwm output for us (sets COM bit to 0) - if (v == 0) - digitalWrite(pin, invert); - else if (v == v_size) - digitalWrite(pin, !invert); - else { - Timer timer = get_pwm_timer(pin); - if (timer.n == 0) return; // Don't proceed if protected timer or not recognised - // Set compare output mode to CLEAR -> SET or SET -> CLEAR (if inverted) - _SET_COMnQ(timer.TCCRnQ, (timer.q - #ifdef TCCR2 - + (timer.q == 2) // COM20 is on bit 4 of TCCR2, thus requires q + 1 in the macro - #endif - ), COM_CLEAR_SET + invert - ); + #if NEEDS_HARDWARE_PWM - uint16_t top; - if (timer.n == 2) { // if TIMER2 - top = ( - #if ENABLED(USE_OCR2A_AS_TOP) - *timer.OCRnQ[0] // top = OCR2A - #else - 255 // top = 0xFF (max) - #endif + // If v is 0 or v_size (max), digitalWrite to LOW or HIGH. + // Note that digitalWrite also disables pwm output for us (sets COM bit to 0) + if (v == 0) + digitalWrite(pin, invert); + else if (v == v_size) + digitalWrite(pin, !invert); + else { + Timer timer = get_pwm_timer(pin); + if (timer.n == 0) return; // Don't proceed if protected timer or not recognized + // Set compare output mode to CLEAR -> SET or SET -> CLEAR (if inverted) + _SET_COMnQ(timer.TCCRnQ, (timer.q + #ifdef TCCR2 + + (timer.q == 2) // COM20 is on bit 4 of TCCR2, thus requires q + 1 in the macro + #endif + ), COM_CLEAR_SET + invert ); + + uint16_t top = (timer.n == 2) ? TERN(USE_OCR2A_AS_TOP, *timer.OCRnQ[0], 255) : *timer.ICRn; + _SET_OCRnQ(timer.OCRnQ, timer.q, (v * top + v_size / 2) / v_size); // Scale 8/16-bit v to top value } - else - top = *timer.ICRn; // top = ICRn - _SET_OCRnQ(timer.OCRnQ, timer.q, v * float(top) / float(v_size)); // Scale 8/16-bit v to top value - } + #else + + analogWrite(pin, v); + UNUSED(v_size); + UNUSED(invert); + + #endif } -#endif // NEEDS_HARDWARE_PWM #endif // __AVR__ diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index fb90c40aa7ea6..96ab5d9808ac1 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -144,6 +144,11 @@ inline void HAL_adc_init() {}//todo void HAL_adc_start_conversion(const uint8_t ch); uint16_t HAL_adc_get_result(); +// +// PWM +// +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // // Pin Map // diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 8a8f6df6404c6..8473e3c4e4693 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -129,6 +129,10 @@ void HAL_adc_init(); void HAL_adc_start_conversion(const uint8_t adc_pin); +// PWM +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + +// Pin Map #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index b80fe210f8bbb..d7d3a92b73b95 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -101,6 +101,9 @@ void HAL_adc_enable_channel(const uint8_t ch); void HAL_adc_start_conversion(const uint8_t ch); uint16_t HAL_adc_get_result(); +// PWM +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // Reset source inline void HAL_clear_reset_source(void) {} inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp index dd440b5e77307..70fc0e333d115 100644 --- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp +++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp @@ -22,18 +22,18 @@ #ifdef TARGET_LPC1768 #include "../../inc/MarlinConfigPre.h" - -#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM - #include -void set_pwm_frequency(const pin_t pin, int f_desired) { - LPC176x::pwm_set_frequency(pin, f_desired); -} - void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size); } -#endif // NEEDS_HARDWARE_PWM +#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM + + void set_pwm_frequency(const pin_t pin, int f_desired) { + LPC176x::pwm_set_frequency(pin, f_desired); + } + +#endif + #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 235c24808cb4b..915339468b2cd 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -133,6 +133,9 @@ void HAL_adc_enable_channel(const uint8_t ch); void HAL_adc_start_conversion(const uint8_t ch); uint16_t HAL_adc_get_result(); +// PWM +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // Reset source inline void HAL_clear_reset_source(void) {} inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index 775a9240e1f49..c262752a8d66a 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -127,6 +127,11 @@ void HAL_adc_init(); void HAL_adc_start_conversion(const uint8_t adc_pin); +// +// PWM +// +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // // Pin Map // diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index 917e12615f1d6..d4d695b969b5f 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -24,26 +24,9 @@ #ifdef HAL_STM32 -#include "../../inc/MarlinConfigPre.h" - -#if NEEDS_HARDWARE_PWM - -#include "HAL.h" +#include "../../inc/MarlinConfig.h" #include "timers.h" -void set_pwm_frequency(const pin_t pin, int f_desired) { - if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer - - PinName pin_name = digitalPinToPinName(pin); - TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance - - LOOP_S_L_N(i, 0, NUM_HARDWARE_TIMERS) // Protect used timers - if (timer_instance[i] && timer_instance[i]->getHandle()->Instance == Instance) - return; - - pwm_start(pin_name, f_desired, 0, RESOLUTION_8B_COMPARE_FORMAT); -} - void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); @@ -58,5 +41,21 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 } } -#endif // NEEDS_HARDWARE_PWM +#if NEEDS_HARDWARE_PWM + + void set_pwm_frequency(const pin_t pin, int f_desired) { + if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer + + PinName pin_name = digitalPinToPinName(pin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance + + LOOP_S_L_N(i, 0, NUM_HARDWARE_TIMERS) // Protect used timers + if (timer_instance[i] && timer_instance[i]->getHandle()->Instance == Instance) + return; + + pwm_start(pin_name, f_desired, 0, RESOLUTION_8B_COMPARE_FORMAT); + } + +#endif + #endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index df1ba33d4adef..f29b30536146e 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -449,8 +449,7 @@ uint16_t analogRead(pin_t pin) { // Wrapper to maple unprotected analogWrite void analogWrite(pin_t pin, int pwm_val8) { - if (PWM_PIN(pin)) - analogWrite(uint8_t(pin), pwm_val8); + if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8); } void HAL_reboot() { nvic_sys_reset(); } diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp index 884d482af5f15..6a9d7e8a19479 100644 --- a/Marlin/src/HAL/STM32F1/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp @@ -23,40 +23,10 @@ #include "../../inc/MarlinConfigPre.h" -#if NEEDS_HARDWARE_PWM - #include #include "HAL.h" #include "timers.h" -void set_pwm_frequency(const pin_t pin, int f_desired) { - if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer - - timer_dev *timer = PIN_MAP[pin].timer_device; - uint8_t channel = PIN_MAP[pin].timer_channel; - - // Protect used timers - if (timer == get_timer_dev(TEMP_TIMER_NUM)) return; - if (timer == get_timer_dev(STEP_TIMER_NUM)) return; - #if PULSE_TIMER_NUM != STEP_TIMER_NUM - if (timer == get_timer_dev(PULSE_TIMER_NUM)) return; - #endif - - if (!(timer->regs.bas->SR & TIMER_CR1_CEN)) // Ensure the timer is enabled - timer_init(timer); - - timer_set_mode(timer, channel, TIMER_PWM); - uint16_t preload = 255; // Lock 255 PWM resolution for high frequencies - int32_t prescaler = (HAL_TIMER_RATE) / (preload + 1) / f_desired - 1; - if (prescaler > 65535) { // For low frequencies increase prescaler - prescaler = 65535; - preload = (HAL_TIMER_RATE) / (prescaler + 1) / f_desired - 1; - } - if (prescaler < 0) return; // Too high frequency - timer_set_reload(timer, preload); - timer_set_prescaler(timer, prescaler); -} - void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { timer_dev *timer = PIN_MAP[pin].timer_device; uint16_t max_val = timer->regs.bas->ARR * v / v_size; @@ -64,5 +34,35 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 pwmWrite(pin, max_val); } +#if NEEDS_HARDWARE_PWM + + void set_pwm_frequency(const pin_t pin, int f_desired) { + if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer + + timer_dev *timer = PIN_MAP[pin].timer_device; + uint8_t channel = PIN_MAP[pin].timer_channel; + + // Protect used timers + if (timer == get_timer_dev(TEMP_TIMER_NUM)) return; + if (timer == get_timer_dev(STEP_TIMER_NUM)) return; + #if PULSE_TIMER_NUM != STEP_TIMER_NUM + if (timer == get_timer_dev(PULSE_TIMER_NUM)) return; + #endif + + if (!(timer->regs.bas->SR & TIMER_CR1_CEN)) // Ensure the timer is enabled + timer_init(timer); + + timer_set_mode(timer, channel, TIMER_PWM); + uint16_t preload = 255; // Lock 255 PWM resolution for high frequencies + int32_t prescaler = (HAL_TIMER_RATE) / (preload + 1) / f_desired - 1; + if (prescaler > 65535) { // For low frequencies increase prescaler + prescaler = 65535; + preload = (HAL_TIMER_RATE) / (prescaler + 1) / f_desired - 1; + } + if (prescaler < 0) return; // Too high frequency + timer_set_reload(timer, preload); + timer_set_prescaler(timer, prescaler); + } + #endif // NEEDS_HARDWARE_PWM #endif // __STM32F1__ diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 7235f5ef0e875..61d8b34604c52 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -122,6 +122,12 @@ void HAL_adc_init(); void HAL_adc_start_conversion(const uint8_t adc_pin); uint16_t HAL_adc_get_result(); +// PWM + +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + +// Pin Map + #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 8892ffec45e77..892eb2d3c5b8f 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -129,6 +129,12 @@ void HAL_adc_init(); void HAL_adc_start_conversion(const uint8_t adc_pin); uint16_t HAL_adc_get_result(); +// PWM + +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + +// Pin Map + #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index ccc8c2659c65f..270bee0dc9d45 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -106,17 +106,17 @@ void HAL_adc_init() { void HAL_clear_reset_source() { uint32_t reset_source = SRC_SRSR; SRC_SRSR = reset_source; - } +} uint8_t HAL_get_reset_source() { switch (SRC_SRSR & 0xFF) { case 1: return RST_POWER_ON; break; case 2: return RST_SOFTWARE; break; case 4: return RST_EXTERNAL; break; - // case 8: return RST_BROWN_OUT; break; + //case 8: return RST_BROWN_OUT; break; case 16: return RST_WATCHDOG; break; - case 64: return RST_JTAG; break; - // case 128: return RST_OVERTEMP; break; + case 64: return RST_JTAG; break; + //case 128: return RST_OVERTEMP; break; } return 0; } @@ -168,7 +168,7 @@ uint16_t HAL_adc_get_result() { return 0; } -bool is_output(uint8_t pin) { +bool is_output(pin_t pin) { const struct digital_pin_bitband_and_config_table_struct *p; p = digital_pin_to_info_PGM + pin; return (*(p->reg + 1) & p->mask); diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index c9716eacde691..2b730768a8025 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -150,8 +150,14 @@ void HAL_adc_init(); void HAL_adc_start_conversion(const uint8_t adc_pin); uint16_t HAL_adc_get_result(); +// PWM + +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + +// Pin Map + #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -bool is_output(uint8_t pin); +bool is_output(pin_t pin); diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index 1baef6d46845b..7c4755d0b585b 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -70,7 +70,7 @@ void CaseLight::update(const bool sflag) { #if CASELIGHT_USES_BRIGHTNESS if (pin_is_pwm()) - analogWrite(pin_t(CASE_LIGHT_PIN), ( + set_pwm_duty(pin_t(CASE_LIGHT_PIN), ( #if CASE_LIGHT_MAX_PWM == 255 n10ct #else diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index 03ef31e414a0a..330f3914f6c0c 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -72,9 +72,10 @@ void ControllerFan::update() { ? settings.active_speed : settings.idle_speed ); - // Allow digital or PWM fan output (see M42 handling) - WRITE(CONTROLLER_FAN_PIN, speed); - analogWrite(pin_t(CONTROLLER_FAN_PIN), speed); + if (PWM_PIN(CONTROLLER_FAN_PIN)) + set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); + else + WRITE(CONTROLLER_FAN_PIN, speed); } } diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 328daa626d462..a371637f00501 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -121,11 +121,11 @@ void LEDLights::set_color(const LEDColor &incol // This variant uses 3-4 separate pins for the RGB(W) components. // If the pins can do PWM then their intensity will be set. - #define _UPDATE_RGBW(C,c) do { \ - if (PWM_PIN(RGB_LED_##C##_PIN)) \ - analogWrite(pin_t(RGB_LED_##C##_PIN), c); \ - else \ - WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \ + #define _UPDATE_RGBW(C,c) do { \ + if (PWM_PIN(RGB_LED_##C##_PIN)) \ + set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \ + else \ + WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \ }while(0) #define UPDATE_RGBW(C,c) _UPDATE_RGBW(C, TERN1(CASE_LIGHT_USE_RGB_LED, caselight.on) ? incol.c : 0) UPDATE_RGBW(R,r); UPDATE_RGBW(G,g); UPDATE_RGBW(B,b); diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index ea6fc4990e950..9297e9b95c8a8 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -66,7 +66,7 @@ void SpindleLaser::init() { #endif #if ENABLED(SPINDLE_LASER_USE_PWM) SET_PWM(SPINDLE_LASER_PWM_PIN); - analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed + set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed #endif #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY) set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); @@ -92,10 +92,8 @@ void SpindleLaser::init() { void SpindleLaser::_set_ocr(const uint8_t ocr) { #if NEEDS_HARDWARE_PWM && SPINDLE_LASER_FREQUENCY set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); - set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); - #else - analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); #endif + set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); } void SpindleLaser::set_ocr(const uint8_t ocr) { diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index eead971a012c3..77c0ccc49b0f8 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -126,10 +126,10 @@ void GcodeSuite::M42() { extDigitalWrite(pin, pin_status); #ifdef ARDUINO_ARCH_STM32 - // A simple I/O will be set to 0 by analogWrite() + // A simple I/O will be set to 0 by set_pwm_duty() if (pin_status <= 1 && !PWM_PIN(pin)) return; #endif - analogWrite(pin, pin_status); + set_pwm_duty(pin, pin_status); } #endif // DIRECT_PIN_CONTROL diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 5d4c30bbb4765..f339cad70614a 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -342,7 +342,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop void MarlinUI::_set_brightness() { #if PIN_EXISTS(TFT_BACKLIGHT) if (PWM_PIN(TFT_BACKLIGHT_PIN)) - analogWrite(pin_t(TFT_BACKLIGHT_PIN), brightness); + set_pwm_duty(pin_t(TFT_BACKLIGHT_PIN), brightness); #endif } #endif diff --git a/Marlin/src/lcd/tft/ui_common.cpp b/Marlin/src/lcd/tft/ui_common.cpp index 8c503d2c9eea3..85ae21e867fa0 100644 --- a/Marlin/src/lcd/tft/ui_common.cpp +++ b/Marlin/src/lcd/tft/ui_common.cpp @@ -213,7 +213,7 @@ void MarlinUI::clear_lcd() { void MarlinUI::_set_brightness() { #if PIN_EXISTS(TFT_BACKLIGHT) if (PWM_PIN(TFT_BACKLIGHT_PIN)) - analogWrite(pin_t(TFT_BACKLIGHT_PIN), brightness); + set_pwm_duty(pin_t(TFT_BACKLIGHT_PIN), brightness); #endif } #endif diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 332becfb73a4e..04f20ca3a4e27 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -1342,7 +1342,7 @@ void Endstops::update() { ES_REPORT_CHANGE(K_MAX); #endif SERIAL_ECHOLNPGM("\n"); - analogWrite(pin_t(LED_PIN), local_LED_status); + set_pwm_duty(pin_t(LED_PIN), local_LED_status); local_LED_status ^= 255; old_live_state_local = live_state_local; } diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 2552efc69a264..11460fa67a24b 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1270,7 +1270,7 @@ void Planner::recalculate() { #elif ENABLED(FAST_PWM_FAN) #define _FAN_SET(F) set_pwm_duty(FAN##F##_PIN, CALC_FAN_SPEED(F)); #else - #define _FAN_SET(F) analogWrite(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); + #define _FAN_SET(F) set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); #endif #define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0) @@ -1393,8 +1393,8 @@ void Planner::check_axes_activity() { TERN_(AUTOTEMP, autotemp_task()); #if ENABLED(BARICUDA) - TERN_(HAS_HEATER_1, analogWrite(pin_t(HEATER_1_PIN), tail_valve_pressure)); - TERN_(HAS_HEATER_2, analogWrite(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); + TERN_(HAS_HEATER_1, set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); + TERN_(HAS_HEATER_2, set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); #endif } diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index a54bf53c49061..2c8933266fa33 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -3253,7 +3253,7 @@ void Stepper::report_positions() { #elif HAS_MOTOR_CURRENT_PWM - #define _WRITE_CURRENT_PWM(P) analogWrite(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) + #define _WRITE_CURRENT_PWM(P) set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) switch (driver) { case 0: #if PIN_EXISTS(MOTOR_CURRENT_PWM_X) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 5e8f4c9d9595a..cef348c5f9856 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -887,11 +887,11 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { SBI(fanState, pgm_read_byte(&fanBit[COOLER_FAN_INDEX])); #endif - #define _UPDATE_AUTO_FAN(P,D,A) do{ \ - if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \ - analogWrite(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ - else \ - WRITE(P##_AUTO_FAN_PIN, D); \ + #define _UPDATE_AUTO_FAN(P,D,A) do{ \ + if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \ + set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ + else \ + WRITE(P##_AUTO_FAN_PIN, D); \ }while(0) uint8_t fanDone = 0; From 95357c33fb0d3ce6d84e59bd16e8354836997015 Mon Sep 17 00:00:00 2001 From: Sebastien BLAISOT Date: Tue, 2 Nov 2021 06:49:21 +0100 Subject: [PATCH 015/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20NEOPIXEL2=5FSEPARA?= =?UTF-8?q?TE=20default=20color=20(#23057)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/leds/leds.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index a371637f00501..17d790b8cc9a2 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -170,9 +170,9 @@ void LEDLights::set_color(const LEDColor &incol #if ENABLED(NEO2_COLOR_PRESETS) const LEDColor LEDLights2::defaultLEDColor = LEDColor( - LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE - OPTARG(HAS_WHITE_LED2, LED_USER_PRESET_WHITE) - OPTARG(NEOPIXEL_LED, LED_USER_PRESET_BRIGHTNESS) + NEO2_USER_PRESET_RED, NEO2_USER_PRESET_GREEN, NEO2_USER_PRESET_BLUE + OPTARG(HAS_WHITE_LED2, NEO2_USER_PRESET_WHITE) + OPTARG(NEOPIXEL_LED, NEO2_USER_PRESET_BRIGHTNESS) ); #endif From 0db9f9a828c43f978e37b5140f7b9bb6ca630667 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 1 Nov 2021 23:15:29 -0700 Subject: [PATCH 016/273] =?UTF-8?q?=F0=9F=93=8C=20Default=20NeoPixel=20pin?= =?UTF-8?q?=20for=20MKS=20Robin=20E3/E3D=20(#23060)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 5 +++++ 1 file changed, 5 insertions(+) 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 a34099120ebf4..025c65a38b24f 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -64,6 +64,11 @@ #define Z_MIN_PROBE_PIN PB1 #endif +// LED driving pin +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PA2 +#endif + // // Steppers // From f632b72e8c58ea4c54676ca17e9b9c9ee4584be0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 2 Nov 2021 01:28:00 -0500 Subject: [PATCH 017/273] =?UTF-8?q?=F0=9F=94=A8=20Support=20ABM=20in=20mf?= =?UTF-8?q?=20scripts?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/git/mfinfo | 1 + 1 file changed, 1 insertion(+) diff --git a/buildroot/share/git/mfinfo b/buildroot/share/git/mfinfo index e17138e45626e..0f5d79a002b36 100755 --- a/buildroot/share/git/mfinfo +++ b/buildroot/share/git/mfinfo @@ -52,6 +52,7 @@ case "$REPO" in Marlin ) TARG=bugfix-2.0.x ; [[ $INDEX == 1 ]] && TARG=bugfix-1.1.x ; [[ $INDEX == 3 ]] && TARG=dev-2.1.x ;; Configurations ) TARG=import-2.0.x ;; MarlinDocumentation ) TARG=master ;; + AutoBuildMarlin ) TARG=master ;; esac [[ $BRANCH =~ ^[123]$ ]] && USAGE=1 From 627b67e27aa4de50c172e0ffc4a13fe3fb2d35f8 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 3 Nov 2021 01:00:15 +0000 Subject: [PATCH 018/273] [cron] Bump distribution date (2021-11-03) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 607561a87dd48..68c7d052990c9 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 "2021-11-02" +//#define STRING_DISTRIBUTION_DATE "2021-11-03" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c0dbd45fa2dde..1e1977671b5be 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 "2021-11-02" + #define STRING_DISTRIBUTION_DATE "2021-11-03" #endif /** From cac42e24a581915176816c680a61396855660b19 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 3 Nov 2021 07:02:21 -0500 Subject: [PATCH 019/273] =?UTF-8?q?=F0=9F=94=A8=20Update=20git=20helper=20?= =?UTF-8?q?scripts?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/git/mffp | 14 +++++++++----- buildroot/share/git/mfinfo | 28 ++++++++++++++++------------ buildroot/share/git/mfnew | 6 +++--- buildroot/share/git/mfpr | 6 +++--- buildroot/share/git/mfqp | 4 ++-- buildroot/share/git/mfrb | 4 ++-- 6 files changed, 35 insertions(+), 27 deletions(-) diff --git a/buildroot/share/git/mffp b/buildroot/share/git/mffp index 2663a4a1374e7..0680b3dba5627 100755 --- a/buildroot/share/git/mffp +++ b/buildroot/share/git/mffp @@ -1,19 +1,23 @@ #!/usr/bin/env bash # -# mffp [1|2|3] [commit-id] +# mffp [1|2] [ref] # # Push the given commit (or HEAD) upstream immediately. -# By default: `git push upstream HEAD:bugfix-1.1.x` +# By default: `git push upstream HEAD:bugfix-2.0.x` # -[[ $# < 3 && $1 != "-h" && $1 != "--help" ]] || { echo "usage: `basename $0` [1|2|3] [commit-id]" 1>&2 ; exit 1; } +usage() { echo "usage: `basename $0` [1|2] [ref]" 1>&2 } -if [[ $1 == '1' || $1 == '2' || $1 == '3' ]]; then +[[ $# < 3 && $1 != "-h" && $1 != "--help" ]] || { usage ; exit 1; } + +if [[ $1 == '1' || $1 == '2' ]]; then MFINFO=$(mfinfo "$1") || exit 1 REF=${2:-HEAD} -else +elif [[ $# == 1 ]]; then MFINFO=$(mfinfo) || exit 1 REF=${1:-HEAD} +else + usage fi IFS=' ' read -a INFO <<< "$MFINFO" diff --git a/buildroot/share/git/mfinfo b/buildroot/share/git/mfinfo index 0f5d79a002b36..0c2113d922937 100755 --- a/buildroot/share/git/mfinfo +++ b/buildroot/share/git/mfinfo @@ -2,15 +2,19 @@ # # mfinfo # -# Provide the following info about the working directory: +# Print the following info about the working copy: # # - Remote (upstream) Org name (MarlinFirmware) # - Remote (origin) Org name (your Github username) # - Repo Name (Marlin, MarlinDocumentation) -# - PR Target branch (bugfix-1.1.x, bugfix-2.0.x, dev-2.1.x, etc.) +# - PR Target branch (e.g., bugfix-2.0.x) # - Branch Arg (the branch argument or current branch) # - Current Branch # +# Example output +# > mfinfo -q ongoing +# MarlinFirmware john.doe Marlin bugfix-2.0.x ongoing bugfix-2.0.x -q +# CURR=$(git branch 2>/dev/null | grep ^* | sed 's/\* //g') [[ -z $CURR ]] && { echo "No git repository here!" 1>&2 ; exit 1; } @@ -26,37 +30,37 @@ FORK=$(git remote get-url origin 2>/dev/null | sed -E 's/.*[\/:](.*)\/.*$/\1/') # Defaults if no arguments given BRANCH=$CURR -INDEX=1 +MORE="" +INDEX=2 +# Loop through arguments while [[ $# -gt 0 ]]; do + # Get an arg and maybe a val to go with it opt="$1" ; shift ; val="$1" + # Split up an arg containing = IFS='=' read -a PARTS <<<"$opt" [[ "${PARTS[1]}" != "" ]] && { EQUALS=1 ; opt="${PARTS[0]}" ; val="${PARTS[1]}" ; } - GOODVAL=1 if [[ "$val" =~ ^-{1,2}.* || ! "$opt" =~ ^-{1,2}.* ]]; then - GOODVAL=0 val="" fi case "$opt" in - -*|--*) MORE="$MORE$opt " ; [[ $EQUALS == 1 ]] && MORE="$MORE=$val" ;; - 1|2|3) INDEX=$opt ;; + -*|--*) MORE=" $MORE$opt" ; ((EQUALS)) && MORE="$MORE=$val" ;; + 1|2) INDEX=$opt ;; *) BRANCH="$opt" ;; esac done case "$REPO" in - Marlin ) TARG=bugfix-2.0.x ; [[ $INDEX == 1 ]] && TARG=bugfix-1.1.x ; [[ $INDEX == 3 ]] && TARG=dev-2.1.x ;; + Marlin ) TARG=bugfix-2.0.x ; ((INDEX == 1)) && TARG=bugfix-1.1.x ; [[ $BRANCH =~ ^[12]$ ]] && USAGE=1 ;; Configurations ) TARG=import-2.0.x ;; MarlinDocumentation ) TARG=master ;; AutoBuildMarlin ) TARG=master ;; esac -[[ $BRANCH =~ ^[123]$ ]] && USAGE=1 - -[[ $USAGE == 1 ]] && { echo "usage: `basename $0` [1|2|3] [branch]" 1>&2 ; exit 1 ; } +[[ $USAGE == 1 ]] && { echo "usage: `basename $0` [1|2] [branch]" 1>&2 ; exit 1 ; } -echo "$ORG $FORK $REPO $TARG $BRANCH $CURR $MORE" +echo "$ORG $FORK $REPO $TARG $BRANCH $CURR$MORE" diff --git a/buildroot/share/git/mfnew b/buildroot/share/git/mfnew index e491fea191034..6d067a7f08e66 100755 --- a/buildroot/share/git/mfnew +++ b/buildroot/share/git/mfnew @@ -6,7 +6,7 @@ # usage() { - echo "usage: `basename $0` [1|2|3] [name]" 1>&2 + echo "usage: `basename $0` [1|2] [name]" 1>&2 } [[ $# < 3 && $1 != "-h" && $1 != "--help" ]] || { usage; exit 1; } @@ -19,12 +19,12 @@ BRANCH=pr_for_$TARG-$(date +"%G-%m-%d_%H.%M.%S") # BRANCH can be given as the last argument case "$#" in 1 ) case "$1" in - 1|2|3) ;; + 1|2) ;; *) BRANCH=$1 ;; esac ;; 2 ) case "$1" in - 1|2|3) BRANCH=$2 ;; + 1|2) BRANCH=$2 ;; *) usage ; exit 1 ;; esac ;; diff --git a/buildroot/share/git/mfpr b/buildroot/share/git/mfpr index b853c6929e445..230bd2886cf4b 100755 --- a/buildroot/share/git/mfpr +++ b/buildroot/share/git/mfpr @@ -1,11 +1,11 @@ #!/usr/bin/env bash # -# mfpr [1|2|3] +# mfpr [1|2] # -# Make a PR against bugfix-1.1.x or bugfix-2.0.x +# Make a PR targeted to MarlinFirmware/[repo] # -[[ $# < 2 && $1 != "-h" && $1 != "--help" ]] || { echo "usage: `basename $0` [1|2|3] [branch]" 1>&2 ; exit 1; } +[[ $# < 2 && $1 != "-h" && $1 != "--help" ]] || { echo "usage: `basename $0` [1|2] [branch]" 1>&2 ; exit 1; } MFINFO=$(mfinfo "$@") || exit 1 IFS=' ' read -a INFO <<< "$MFINFO" diff --git a/buildroot/share/git/mfqp b/buildroot/share/git/mfqp index f0c4446a211e6..6e36e6113a1ac 100755 --- a/buildroot/share/git/mfqp +++ b/buildroot/share/git/mfqp @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# mfqp [1|2|3] +# mfqp [1|2] # # - git add . # - git commit --amend @@ -24,7 +24,7 @@ while [ $IND -lt ${#INFO[@]} ]; do let IND+=1 done -[[ $USAGE == 1 ]] && { echo "usage: `basename $0` [1|2|3]" 1>&2 ; exit 1 ; } +[[ $USAGE == 1 ]] && { echo "usage: `basename $0` [1|2]" 1>&2 ; exit 1 ; } [[ $FORCE != 1 && $CURR == $TARG && $REPO != "MarlinDocumentation" ]] && { echo "Don't alter the PR Target branch."; exit 1 ; } diff --git a/buildroot/share/git/mfrb b/buildroot/share/git/mfrb index 071b0b3d5989b..b55a34e0100d0 100755 --- a/buildroot/share/git/mfrb +++ b/buildroot/share/git/mfrb @@ -2,7 +2,7 @@ # # mfrb # -# Do "git rebase -i" against the "target" branch (bugfix-1.1.x, bugfix-2.0.x, dev-2.1.x, or master) +# Do "git rebase -i" against the repo's "target" branch # MFINFO=$(mfinfo "$@") || exit 1 @@ -21,7 +21,7 @@ while [ $IND -lt ${#INFO[@]} ]; do let IND+=1 done -[[ $USAGE == 1 ]] && { echo "usage: `basename $0` [1|2|3]" 1>&2 ; exit 1 ; } +[[ $USAGE == 1 ]] && { echo "usage: `basename $0` [1|2]" 1>&2 ; exit 1 ; } [[ $QUICK ]] || git fetch upstream git rebase upstream/$TARG && git rebase -i upstream/$TARG From 02b6fb8025ef82c2d1290cdc1a98bc0c54f502c9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 3 Nov 2021 07:06:31 -0500 Subject: [PATCH 020/273] =?UTF-8?q?=F0=9F=94=A8=20Script=20'mfprep'=20find?= =?UTF-8?q?s=20pending=20commits?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/git/mfprep | 64 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 64 insertions(+) create mode 100755 buildroot/share/git/mfprep diff --git a/buildroot/share/git/mfprep b/buildroot/share/git/mfprep new file mode 100755 index 0000000000000..7a8e05ee317c5 --- /dev/null +++ b/buildroot/share/git/mfprep @@ -0,0 +1,64 @@ +#!/usr/bin/env bash +# +# mfprep tag1 [tag2] +# +# Find commits in bugfix-2.0.x not yet in 2.0.x +# + +SED=$(which gsed sed | head -n1) +SELF=`basename "$0"` + +[[ $# < 1 || $# > 2 ]] && { echo "Usage $SELF tag1 [tag2]" ; exit 1 ; } + +TAG1=$1 +TAG2=${2:-"HEAD"} + +# Validate that the required tags exist + +MTAG=`git tag | grep -e "^bf-$TAG1\$"` +[[ -n $MTAG ]] || { echo "Can't find tag bf-$TAG1" ; exit 1 ; } +MTAG=`git tag | grep -e "^$TAG1\$"` +[[ -n $MTAG ]] || { echo "Can't find tag $TAG1" ; exit 1 ; } + +# Generate log of recent commits for bugfix-2.0.x and 2.0.x + +TMPDIR=`mktemp -d` +LOGB="$TMPDIR/log-bf.txt" +LOG2="$TMPDIR/log-20x.txt" +TMPF="$TMPDIR/tmp.txt" +SCRF="$TMPDIR/update-20x.sh" + +git checkout bugfix-2.0.x +git log --pretty="[%h] %s" bf-$TAG1..$TAG2 | grep -v '\[cron\]' | $SED '1!G;h;$!d' >"$LOGB" + +git checkout 2.0.x +git log --pretty="[%h] %s" $TAG1..$TAG2 | $SED '1!G;h;$!d' >"$LOG2" || { echo "Can't find tag bf-$TAG1" ; exit 1 ; } + +# Go through commit text from 2.0.x removing all matches from the bugfix log + +cat "$LOG2" | while read line; do + #echo "... $line" + if [[ $line =~ (\(#[0-9]{5}\))$ ]]; then + PATT=${BASH_REMATCH[1]} + #echo "... $PATT" + else + PATT=$( $SED -E 's/^\[[0-9a-f]{10}\]( . )?(.+)$/\2/' <<<"$line" ) + fi + [[ -n $PATT ]] && { grep -v "$PATT" "$LOGB" >"$TMPF" ; cp "$TMPF" "$LOGB" ; } +done + +# Convert remaining commits into git commands + +echo -e "#!/usr/bin/env bash\nset -e\ngit checkout 2.0.x\n" >"$TMPF" +cat "$LOGB" | while read line; do + if [[ $line =~ ^\[([0-9a-f]{10})\]\ *(.*)$ ]]; then + CID=${BASH_REMATCH[1]} + REST=${BASH_REMATCH[2]} + echo "git cherry-pick $CID ;# $REST" >>"$TMPF" + else + echo ";# $line" >>"$TMPF" + fi +done +mv "$TMPF" "$SCRF" + +open "$TMPDIR" From fef96bb556f19bf1e132368ec0675d1d2b12634d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 4 Nov 2021 01:00:55 +0000 Subject: [PATCH 021/273] [cron] Bump distribution date (2021-11-04) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 68c7d052990c9..e562730ae3f6e 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 "2021-11-03" +//#define STRING_DISTRIBUTION_DATE "2021-11-04" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 1e1977671b5be..f695d0a1b24a7 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 "2021-11-03" + #define STRING_DISTRIBUTION_DATE "2021-11-04" #endif /** From 399faa91b99dab0f8565396efd32f277965c93b2 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Thu, 4 Nov 2021 14:04:06 +1300 Subject: [PATCH 022/273] =?UTF-8?q?=F0=9F=93=8C=20'STOP'=20auto-assign,=20?= =?UTF-8?q?some=20Chitu=20V9=20pins=20(#22889)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/core/macros.h | 6 ++ Marlin/src/inc/Conditionals_post.h | 70 +++++++++++++++++++++-- Marlin/src/inc/Warnings.cpp | 48 ++++++++++++++++ Marlin/src/pins/pins_postprocess.h | 23 +++++++- Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h | 4 ++ 5 files changed, 143 insertions(+), 8 deletions(-) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index d8a15b910df75..62675d1319721 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -33,6 +33,12 @@ #define _AXIS(A) (A##_AXIS) +#define _XSTOP_ 0x01 +#define _YSTOP_ 0x02 +#define _ZSTOP_ 0x03 +#define _ISTOP_ 0x04 +#define _JSTOP_ 0x05 +#define _KSTOP_ 0x06 #define _XMIN_ 0x11 #define _YMIN_ 0x12 #define _ZMIN_ 0x13 diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index c8b6d504e294a..8008461547ce9 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -769,19 +769,25 @@ #define X2_MAX_ENDSTOP_INVERTING false #endif #endif - #ifndef X2_MAX_PIN + #if !defined(X2_MAX_PIN) && !defined(X2_STOP_PIN) #if X2_USE_ENDSTOP == _XMIN_ #define X2_MAX_PIN X_MIN_PIN #elif X2_USE_ENDSTOP == _XMAX_ #define X2_MAX_PIN X_MAX_PIN + #elif X2_USE_ENDSTOP == _XSTOP_ + #define X2_MAX_PIN X_STOP_PIN #elif X2_USE_ENDSTOP == _YMIN_ #define X2_MAX_PIN Y_MIN_PIN #elif X2_USE_ENDSTOP == _YMAX_ #define X2_MAX_PIN Y_MAX_PIN + #elif X2_USE_ENDSTOP == _YSTOP_ + #define X2_MAX_PIN Y_STOP_PIN #elif X2_USE_ENDSTOP == _ZMIN_ #define X2_MAX_PIN Z_MIN_PIN #elif X2_USE_ENDSTOP == _ZMAX_ #define X2_MAX_PIN Z_MAX_PIN + #elif X2_USE_ENDSTOP == _ZSTOP_ + #define X2_MAX_PIN Z_STOP_PIN #elif X2_USE_ENDSTOP == _XDIAG_ #define X2_MAX_PIN X_DIAG_PIN #elif X2_USE_ENDSTOP == _YDIAG_ @@ -827,19 +833,25 @@ #define X2_MIN_ENDSTOP_INVERTING false #endif #endif - #ifndef X2_MIN_PIN + #if !defined(X2_MIN_PIN) && !defined(X2_STOP_PIN) #if X2_USE_ENDSTOP == _XMIN_ #define X2_MIN_PIN X_MIN_PIN #elif X2_USE_ENDSTOP == _XMAX_ #define X2_MIN_PIN X_MAX_PIN + #elif X2_USE_ENDSTOP == _XSTOP_ + #define X2_MIN_PIN X_STOP_PIN #elif X2_USE_ENDSTOP == _YMIN_ #define X2_MIN_PIN Y_MIN_PIN #elif X2_USE_ENDSTOP == _YMAX_ #define X2_MIN_PIN Y_MAX_PIN + #elif X2_USE_ENDSTOP == _YSTOP_ + #define X2_MIN_PIN Y_STOP_PIN #elif X2_USE_ENDSTOP == _ZMIN_ #define X2_MIN_PIN Z_MIN_PIN #elif X2_USE_ENDSTOP == _ZMAX_ #define X2_MIN_PIN Z_MAX_PIN + #elif X2_USE_ENDSTOP == _ZSTOP_ + #define X2_MIN_PIN Z_STOP_PIN #elif X2_USE_ENDSTOP == _XDIAG_ #define X2_MIN_PIN X_DIAG_PIN #elif X2_USE_ENDSTOP == _YDIAG_ @@ -892,19 +904,25 @@ #define Y2_MAX_ENDSTOP_INVERTING false #endif #endif - #ifndef Y2_MAX_PIN + #if !defined(Y2_MAX_PIN) && !defined(Y2_STOP_PIN) #if Y2_USE_ENDSTOP == _XMIN_ #define Y2_MAX_PIN X_MIN_PIN #elif Y2_USE_ENDSTOP == _XMAX_ #define Y2_MAX_PIN X_MAX_PIN + #elif Y2_USE_ENDSTOP == _XSTOP_ + #define Y2_MAX_PIN X_STOP_PIN #elif Y2_USE_ENDSTOP == _YMIN_ #define Y2_MAX_PIN Y_MIN_PIN #elif Y2_USE_ENDSTOP == _YMAX_ #define Y2_MAX_PIN Y_MAX_PIN + #elif Y2_USE_ENDSTOP == _YSTOP_ + #define Y2_MAX_PIN Y_STOP_PIN #elif Y2_USE_ENDSTOP == _ZMIN_ #define Y2_MAX_PIN Z_MIN_PIN #elif Y2_USE_ENDSTOP == _ZMAX_ #define Y2_MAX_PIN Z_MAX_PIN + #elif Y2_USE_ENDSTOP == _ZSTOP_ + #define Y2_MAX_PIN Z_STOP_PIN #elif Y2_USE_ENDSTOP == _XDIAG_ #define Y2_MAX_PIN X_DIAG_PIN #elif Y2_USE_ENDSTOP == _YDIAG_ @@ -950,19 +968,25 @@ #define Y2_MIN_ENDSTOP_INVERTING false #endif #endif - #ifndef Y2_MIN_PIN + #if !defined(Y2_MIN_PIN) && !defined(Y2_STOP_PIN) #if Y2_USE_ENDSTOP == _XMIN_ #define Y2_MIN_PIN X_MIN_PIN #elif Y2_USE_ENDSTOP == _XMAX_ #define Y2_MIN_PIN X_MAX_PIN + #elif Y2_USE_ENDSTOP == _XSTOP_ + #define Y2_MIN_PIN X_STOP_PIN #elif Y2_USE_ENDSTOP == _YMIN_ #define Y2_MIN_PIN Y_MIN_PIN #elif Y2_USE_ENDSTOP == _YMAX_ #define Y2_MIN_PIN Y_MAX_PIN + #elif Y2_USE_ENDSTOP == _YSTOP_ + #define Y2_MIN_PIN Y_STOP_PIN #elif Y2_USE_ENDSTOP == _ZMIN_ #define Y2_MIN_PIN Z_MIN_PIN #elif Y2_USE_ENDSTOP == _ZMAX_ #define Y2_MIN_PIN Z_MAX_PIN + #elif Y2_USE_ENDSTOP == _ZSTOP_ + #define Y2_MIN_PIN Z_STOP_PIN #elif Y2_USE_ENDSTOP == _XDIAG_ #define Y2_MIN_PIN X_DIAG_PIN #elif Y2_USE_ENDSTOP == _YDIAG_ @@ -1016,19 +1040,25 @@ #define Z2_MAX_ENDSTOP_INVERTING false #endif #endif - #ifndef Z2_MAX_PIN + #if !defined(Z2_MAX_PIN) && !defined(Z2_STOP_PIN) #if Z2_USE_ENDSTOP == _XMIN_ #define Z2_MAX_PIN X_MIN_PIN #elif Z2_USE_ENDSTOP == _XMAX_ #define Z2_MAX_PIN X_MAX_PIN + #elif Z2_USE_ENDSTOP == _XSTOP_ + #define Z2_MAX_PIN X_STOP_PIN #elif Z2_USE_ENDSTOP == _YMIN_ #define Z2_MAX_PIN Y_MIN_PIN #elif Z2_USE_ENDSTOP == _YMAX_ #define Z2_MAX_PIN Y_MAX_PIN + #elif Z2_USE_ENDSTOP == _YSTOP_ + #define Z2_MAX_PIN Y_STOP_PIN #elif Z2_USE_ENDSTOP == _ZMIN_ #define Z2_MAX_PIN Z_MIN_PIN #elif Z2_USE_ENDSTOP == _ZMAX_ #define Z2_MAX_PIN Z_MAX_PIN + #elif Z2_USE_ENDSTOP == _ZSTOP_ + #define Z2_MAX_PIN Z_STOP_PIN #elif Z2_USE_ENDSTOP == _XDIAG_ #define Z2_MAX_PIN X_DIAG_PIN #elif Z2_USE_ENDSTOP == _YDIAG_ @@ -1079,14 +1109,20 @@ #define Z2_MIN_PIN X_MIN_PIN #elif Z2_USE_ENDSTOP == _XMAX_ #define Z2_MIN_PIN X_MAX_PIN + #elif Z2_USE_ENDSTOP == _XSTOP_ + #define Z2_MIN_PIN X_STOP_PIN #elif Z2_USE_ENDSTOP == _YMIN_ #define Z2_MIN_PIN Y_MIN_PIN #elif Z2_USE_ENDSTOP == _YMAX_ #define Z2_MIN_PIN Y_MAX_PIN + #elif Z2_USE_ENDSTOP == _YSTOP_ + #define Z2_MIN_PIN Y_STOP_PIN #elif Z2_USE_ENDSTOP == _ZMIN_ #define Z2_MIN_PIN Z_MIN_PIN #elif Z2_USE_ENDSTOP == _ZMAX_ #define Z2_MIN_PIN Z_MAX_PIN + #elif Z2_USE_ENDSTOP == _ZSTOP_ + #define Z2_MIN_PIN Z_STOP_PIN #elif Z2_USE_ENDSTOP == _XDIAG_ #define Z2_MIN_PIN X_DIAG_PIN #elif Z2_USE_ENDSTOP == _YDIAG_ @@ -1140,14 +1176,20 @@ #define Z3_MAX_PIN X_MIN_PIN #elif Z3_USE_ENDSTOP == _XMAX_ #define Z3_MAX_PIN X_MAX_PIN + #elif Z3_USE_ENDSTOP == _XSTOP_ + #define Z3_MAX_PIN X_STOP_PIN #elif Z3_USE_ENDSTOP == _YMIN_ #define Z3_MAX_PIN Y_MIN_PIN #elif Z3_USE_ENDSTOP == _YMAX_ #define Z3_MAX_PIN Y_MAX_PIN + #elif Z3_USE_ENDSTOP == _YSTOP_ + #define Z3_MAX_PIN Y_STOP_PIN #elif Z3_USE_ENDSTOP == _ZMIN_ #define Z3_MAX_PIN Z_MIN_PIN #elif Z3_USE_ENDSTOP == _ZMAX_ #define Z3_MAX_PIN Z_MAX_PIN + #elif Z3_USE_ENDSTOP == _ZSTOP_ + #define Z3_MAX_PIN Z_STOP_PIN #elif Z3_USE_ENDSTOP == _XDIAG_ #define Z3_MAX_PIN X_DIAG_PIN #elif Z3_USE_ENDSTOP == _YDIAG_ @@ -1198,14 +1240,20 @@ #define Z3_MIN_PIN X_MIN_PIN #elif Z3_USE_ENDSTOP == _XMAX_ #define Z3_MIN_PIN X_MAX_PIN + #elif Z3_USE_ENDSTOP == _XSTOP_ + #define Z3_MIN_PIN X_STOP_PIN #elif Z3_USE_ENDSTOP == _YMIN_ #define Z3_MIN_PIN Y_MIN_PIN #elif Z3_USE_ENDSTOP == _YMAX_ #define Z3_MIN_PIN Y_MAX_PIN + #elif Z3_USE_ENDSTOP == _YSTOP_ + #define Z3_MIN_PIN Y_STOP_PIN #elif Z3_USE_ENDSTOP == _ZMIN_ #define Z3_MIN_PIN Z_MIN_PIN #elif Z3_USE_ENDSTOP == _ZMAX_ #define Z3_MIN_PIN Z_MAX_PIN + #elif Z3_USE_ENDSTOP == _ZSTOP_ + #define Z3_MIN_PIN Z_STOP_PIN #elif Z3_USE_ENDSTOP == _XDIAG_ #define Z3_MIN_PIN X_DIAG_PIN #elif Z3_USE_ENDSTOP == _YDIAG_ @@ -1260,14 +1308,20 @@ #define Z4_MAX_PIN X_MIN_PIN #elif Z4_USE_ENDSTOP == _XMAX_ #define Z4_MAX_PIN X_MAX_PIN + #elif Z4_USE_ENDSTOP == _XSTOP_ + #define Z4_MAX_PIN X_STOP_PIN #elif Z4_USE_ENDSTOP == _YMIN_ #define Z4_MAX_PIN Y_MIN_PIN #elif Z4_USE_ENDSTOP == _YMAX_ #define Z4_MAX_PIN Y_MAX_PIN + #elif Z4_USE_ENDSTOP == _YSTOP_ + #define Z4_MAX_PIN Y_STOP_PIN #elif Z4_USE_ENDSTOP == _ZMIN_ #define Z4_MAX_PIN Z_MIN_PIN #elif Z4_USE_ENDSTOP == _ZMAX_ #define Z4_MAX_PIN Z_MAX_PIN + #elif Z4_USE_ENDSTOP == _ZSTOP_ + #define Z4_MAX_PIN Z_STOP_PIN #elif Z4_USE_ENDSTOP == _XDIAG_ #define Z4_MAX_PIN X_DIAG_PIN #elif Z4_USE_ENDSTOP == _YDIAG_ @@ -1318,14 +1372,20 @@ #define Z4_MIN_PIN X_MIN_PIN #elif Z4_USE_ENDSTOP == _XMAX_ #define Z4_MIN_PIN X_MAX_PIN + #elif Z4_USE_ENDSTOP == _XSTOP_ + #define Z4_MIN_PIN X_STOP_PIN #elif Z4_USE_ENDSTOP == _YMIN_ #define Z4_MIN_PIN Y_MIN_PIN #elif Z4_USE_ENDSTOP == _YMAX_ #define Z4_MIN_PIN Y_MAX_PIN + #elif Z4_USE_ENDSTOP == _YSTOP_ + #define Z4_MIN_PIN Y_STOP_PIN #elif Z4_USE_ENDSTOP == _ZMIN_ #define Z4_MIN_PIN Z_MIN_PIN #elif Z4_USE_ENDSTOP == _ZMAX_ #define Z4_MIN_PIN Z_MAX_PIN + #elif Z4_USE_ENDSTOP == _ZSTOP_ + #define Z4_MIN_PIN Z_STOP_PIN #elif Z4_USE_ENDSTOP == _XDIAG_ #define Z4_MIN_PIN X_DIAG_PIN #elif Z4_USE_ENDSTOP == _YDIAG_ diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index 251094901051c..1976c0958160f 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -79,14 +79,20 @@ #warning "Auto-assigned X2_DIAG_PIN to X_MIN_PIN." #elif X2_USE_ENDSTOP == _XMAX_ #warning "Auto-assigned X2_DIAG_PIN to X_MAX_PIN." + #elif X2_USE_ENDSTOP == _XSTOP_ + #warning "Auto-assigned X2_DIAG_PIN to X_STOP_PIN." #elif X2_USE_ENDSTOP == _YMIN_ #warning "Auto-assigned X2_DIAG_PIN to Y_MIN_PIN." #elif X2_USE_ENDSTOP == _YMAX_ #warning "Auto-assigned X2_DIAG_PIN to Y_MAX_PIN." + #elif X2_USE_ENDSTOP == _YSTOP_ + #warning "Auto-assigned X2_DIAG_PIN to Y_STOP_PIN." #elif X2_USE_ENDSTOP == _ZMIN_ #warning "Auto-assigned X2_DIAG_PIN to Z_MIN_PIN." #elif X2_USE_ENDSTOP == _ZMAX_ #warning "Auto-assigned X2_DIAG_PIN to Z_MAX_PIN." + #elif X2_USE_ENDSTOP == _ZSTOP_ + #warning "Auto-assigned X2_DIAG_PIN to Z_STOP_PIN." #elif X2_USE_ENDSTOP == _XDIAG_ #warning "Auto-assigned X2_DIAG_PIN to X_DIAG_PIN." #elif X2_USE_ENDSTOP == _YDIAG_ @@ -131,14 +137,20 @@ #warning "Auto-assigned Y2_DIAG_PIN to X_MIN_PIN." #elif Y2_USE_ENDSTOP == _XMAX_ #warning "Auto-assigned Y2_DIAG_PIN to X_MAX_PIN." + #elif Y2_USE_ENDSTOP == _XSTOP_ + #warning "Auto-assigned Y2_DIAG_PIN to X_STOP_PIN." #elif Y2_USE_ENDSTOP == _YMIN_ #warning "Auto-assigned Y2_DIAG_PIN to Y_MIN_PIN." #elif Y2_USE_ENDSTOP == _YMAX_ #warning "Auto-assigned Y2_DIAG_PIN to Y_MAX_PIN." + #elif Y2_USE_ENDSTOP == _YSTOP_ + #warning "Auto-assigned Y2_DIAG_PIN to Y_STOP_PIN." #elif Y2_USE_ENDSTOP == _ZMIN_ #warning "Auto-assigned Y2_DIAG_PIN to Z_MIN_PIN." #elif Y2_USE_ENDSTOP == _ZMAX_ #warning "Auto-assigned Y2_DIAG_PIN to Z_MAX_PIN." + #elif Y2_USE_ENDSTOP == _ZSTOP_ + #warning "Auto-assigned Y2_DIAG_PIN to Z_STOP_PIN." #elif Y2_USE_ENDSTOP == _XDIAG_ #warning "Auto-assigned Y2_DIAG_PIN to X_DIAG_PIN." #elif Y2_USE_ENDSTOP == _YDIAG_ @@ -183,14 +195,20 @@ #warning "Auto-assigned Z2_DIAG_PIN to X_MIN_PIN." #elif Z2_USE_ENDSTOP == _XMAX_ #warning "Auto-assigned Z2_DIAG_PIN to X_MAX_PIN." + #elif Z2_USE_ENDSTOP == _XSTOP_ + #warning "Auto-assigned Z2_DIAG_PIN to X_STOP_PIN." #elif Z2_USE_ENDSTOP == _YMIN_ #warning "Auto-assigned Z2_DIAG_PIN to Y_MIN_PIN." #elif Z2_USE_ENDSTOP == _YMAX_ #warning "Auto-assigned Z2_DIAG_PIN to Y_MAX_PIN." + #elif Z2_USE_ENDSTOP == _YSTOP_ + #warning "Auto-assigned Z2_DIAG_PIN to Y_STOP_PIN." #elif Z2_USE_ENDSTOP == _ZMIN_ #warning "Auto-assigned Z2_DIAG_PIN to Z_MIN_PIN." #elif Z2_USE_ENDSTOP == _ZMAX_ #warning "Auto-assigned Z2_DIAG_PIN to Z_MAX_PIN." + #elif Z2_USE_ENDSTOP == _ZSTOP_ + #warning "Auto-assigned Z2_DIAG_PIN to Z_STOP_PIN." #elif Z2_USE_ENDSTOP == _XDIAG_ #warning "Auto-assigned Z2_DIAG_PIN to X_DIAG_PIN." #elif Z2_USE_ENDSTOP == _YDIAG_ @@ -235,14 +253,20 @@ #warning "Auto-assigned Z3_DIAG_PIN to X_MIN_PIN." #elif Z3_USE_ENDSTOP == _XMAX_ #warning "Auto-assigned Z3_DIAG_PIN to X_MAX_PIN." + #elif Z3_USE_ENDSTOP == _XSTOP_ + #warning "Auto-assigned Z3_DIAG_PIN to X_STOP_PIN." #elif Z3_USE_ENDSTOP == _YMIN_ #warning "Auto-assigned Z3_DIAG_PIN to Y_MIN_PIN." #elif Z3_USE_ENDSTOP == _YMAX_ #warning "Auto-assigned Z3_DIAG_PIN to Y_MAX_PIN." + #elif Z3_USE_ENDSTOP == _YSTOP_ + #warning "Auto-assigned Z3_DIAG_PIN to Y_STOP_PIN." #elif Z3_USE_ENDSTOP == _ZMIN_ #warning "Auto-assigned Z3_DIAG_PIN to Z_MIN_PIN." #elif Z3_USE_ENDSTOP == _ZMAX_ #warning "Auto-assigned Z3_DIAG_PIN to Z_MAX_PIN." + #elif Z3_USE_ENDSTOP == _ZSTOP_ + #warning "Auto-assigned Z3_DIAG_PIN to Z_STOP_PIN." #elif Z3_USE_ENDSTOP == _XDIAG_ #warning "Auto-assigned Z3_DIAG_PIN to X_DIAG_PIN." #elif Z3_USE_ENDSTOP == _YDIAG_ @@ -287,14 +311,20 @@ #warning "Auto-assigned Z4_DIAG_PIN to X_MIN_PIN." #elif Z4_USE_ENDSTOP == _XMAX_ #warning "Auto-assigned Z4_DIAG_PIN to X_MAX_PIN." + #elif Z4_USE_ENDSTOP == _XSTOP_ + #warning "Auto-assigned Z4_DIAG_PIN to X_STOP_PIN." #elif Z4_USE_ENDSTOP == _YMIN_ #warning "Auto-assigned Z4_DIAG_PIN to Y_MIN_PIN." #elif Z4_USE_ENDSTOP == _YMAX_ #warning "Auto-assigned Z4_DIAG_PIN to Y_MAX_PIN." + #elif Z4_USE_ENDSTOP == _YSTOP_ + #warning "Auto-assigned Z4_DIAG_PIN to Y_STOP_PIN." #elif Z4_USE_ENDSTOP == _ZMIN_ #warning "Auto-assigned Z4_DIAG_PIN to Z_MIN_PIN." #elif Z4_USE_ENDSTOP == _ZMAX_ #warning "Auto-assigned Z4_DIAG_PIN to Z_MAX_PIN." + #elif Z4_USE_ENDSTOP == _ZSTOP_ + #warning "Auto-assigned Z4_DIAG_PIN to Z_STOP_PIN." #elif Z4_USE_ENDSTOP == _XDIAG_ #warning "Auto-assigned Z4_DIAG_PIN to X_DIAG_PIN." #elif Z4_USE_ENDSTOP == _YDIAG_ @@ -339,14 +369,20 @@ #warning "Auto-assigned I_DIAG_PIN to X_MIN_PIN." #elif I_USE_ENDSTOP == _XMAX_ #warning "Auto-assigned I_DIAG_PIN to X_MAX_PIN." + #elif I_USE_ENDSTOP == _XSTOP_ + #warning "Auto-assigned I_DIAG_PIN to X_STOP_PIN." #elif I_USE_ENDSTOP == _YMIN_ #warning "Auto-assigned I_DIAG_PIN to Y_MIN_PIN." #elif I_USE_ENDSTOP == _YMAX_ #warning "Auto-assigned I_DIAG_PIN to Y_MAX_PIN." + #elif I_USE_ENDSTOP == _YSTOP_ + #warning "Auto-assigned I_DIAG_PIN to Y_STOP_PIN." #elif I_USE_ENDSTOP == _ZMIN_ #warning "Auto-assigned I_DIAG_PIN to Z_MIN_PIN." #elif I_USE_ENDSTOP == _ZMAX_ #warning "Auto-assigned I_DIAG_PIN to Z_MAX_PIN." + #elif I_USE_ENDSTOP == _ZSTOP_ + #warning "Auto-assigned I_DIAG_PIN to Z_STOP_PIN." #elif I_USE_ENDSTOP == _XDIAG_ #warning "Auto-assigned I_DIAG_PIN to X_DIAG_PIN." #elif I_USE_ENDSTOP == _YDIAG_ @@ -391,14 +427,20 @@ #warning "Auto-assigned J_DIAG_PIN to X_MIN_PIN." #elif J_USE_ENDSTOP == _XMAX_ #warning "Auto-assigned J_DIAG_PIN to X_MAX_PIN." + #elif J_USE_ENDSTOP == _XSTOP_ + #warning "Auto-assigned J_DIAG_PIN to X_STOP_PIN." #elif J_USE_ENDSTOP == _YMIN_ #warning "Auto-assigned J_DIAG_PIN to Y_MIN_PIN." #elif J_USE_ENDSTOP == _YMAX_ #warning "Auto-assigned J_DIAG_PIN to Y_MAX_PIN." + #elif J_USE_ENDSTOP == _YSTOP_ + #warning "Auto-assigned J_DIAG_PIN to Y_STOP_PIN." #elif J_USE_ENDSTOP == _ZMIN_ #warning "Auto-assigned J_DIAG_PIN to Z_MIN_PIN." #elif J_USE_ENDSTOP == _ZMAX_ #warning "Auto-assigned J_DIAG_PIN to Z_MAX_PIN." + #elif J_USE_ENDSTOP == _ZSTOP_ + #warning "Auto-assigned J_DIAG_PIN to Z_STOP_PIN." #elif J_USE_ENDSTOP == _XDIAG_ #warning "Auto-assigned J_DIAG_PIN to X_DIAG_PIN." #elif J_USE_ENDSTOP == _YDIAG_ @@ -443,14 +485,20 @@ #warning "Auto-assigned K_DIAG_PIN to X_MIN_PIN." #elif K_USE_ENDSTOP == _XMAX_ #warning "Auto-assigned K_DIAG_PIN to X_MAX_PIN." + #elif K_USE_ENDSTOP == _XSTOP_ + #warning "Auto-assigned K_DIAG_PIN to X_STOP_PIN." #elif K_USE_ENDSTOP == _YMIN_ #warning "Auto-assigned K_DIAG_PIN to Y_MIN_PIN." #elif K_USE_ENDSTOP == _YMAX_ #warning "Auto-assigned K_DIAG_PIN to Y_MAX_PIN." + #elif K_USE_ENDSTOP == _YSTOP_ + #warning "Auto-assigned K_DIAG_PIN to Y_STOP_PIN." #elif K_USE_ENDSTOP == _ZMIN_ #warning "Auto-assigned K_DIAG_PIN to Z_MIN_PIN." #elif K_USE_ENDSTOP == _ZMAX_ #warning "Auto-assigned K_DIAG_PIN to Z_MAX_PIN." + #elif K_USE_ENDSTOP == _ZSTOP_ + #warning "Auto-assigned K_DIAG_PIN to Z_STOP_PIN." #elif K_USE_ENDSTOP == _XDIAG_ #warning "Auto-assigned K_DIAG_PIN to X_DIAG_PIN." #elif K_USE_ENDSTOP == _YDIAG_ diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index d1047db0d7ce3..1e6703fd4a3a4 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -419,6 +419,9 @@ #else #define X_STOP_PIN X_MAX_PIN #endif +#if !defined(X2_USE_ENDSTOP) && ENABLED(X_DUAL_ENDSTOPS) && PIN_EXISTS(X_STOP) + #define X2_USE_ENDSTOP _XSTOP_ +#endif #if HAS_Y_AXIS #ifdef Y_STOP_PIN @@ -438,6 +441,9 @@ #else #define Y_STOP_PIN Y_MAX_PIN #endif + #if !defined(Y2_USE_ENDSTOP) && ENABLED(Y_DUAL_ENDSTOPS) && PIN_EXISTS(Y_STOP) + #define Y2_USE_ENDSTOP _YSTOP_ + #endif #endif #if HAS_Z_AXIS @@ -458,6 +464,17 @@ #else #define Z_STOP_PIN Z_MAX_PIN #endif + #if ENABLED(Z_MULTI_ENDSTOPS) && PIN_EXISTS(Z_STOP) + #ifndef Z2_USE_ENDSTOP + #define Z2_USE_ENDSTOP _ZSTOP_ + #endif + #if NUM_Z_STEPPER_DRIVERS >= 3 && !defined(Z3_USE_ENDSTOP) + #define Z3_USE_ENDSTOP _ZSTOP_ + #endif + #if NUM_Z_STEPPER_DRIVERS >= 4 && !defined(Z4_USE_ENDSTOP) + #define Z4_USE_ENDSTOP _ZSTOP_ + #endif + #endif #endif #if LINEAR_AXES >= 4 @@ -801,7 +818,7 @@ #endif #endif // Auto-assign pins for stallGuard sensorless homing - #if !defined(Z2_DIAG_PIN) && !defined(Z2_USE_ENDSTOP) && defined(Z2_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 2 && _PEXI(Z2_E_INDEX, DIAG) + #if !defined(Z2_DIAG_PIN) && !defined(Z2_USE_ENDSTOP) && defined(Z2_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && _PEXI(Z2_E_INDEX, DIAG) #define Z2_DIAG_PIN _EPIN(Z2_E_INDEX, DIAG) #if DIAG_REMAPPED(Z2, X_MIN) #define Z2_USE_ENDSTOP _XMIN_ @@ -886,7 +903,7 @@ #endif #endif // Auto-assign pins for stallGuard sensorless homing - #if !defined(Z3_DIAG_PIN) && !defined(Z3_USE_ENDSTOP) && defined(Z3_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && _PEXI(Z3_E_INDEX, DIAG) + #if !defined(Z3_DIAG_PIN) && !defined(Z3_USE_ENDSTOP) && defined(Z3_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && _PEXI(Z3_E_INDEX, DIAG) #define Z3_DIAG_PIN _EPIN(Z3_E_INDEX, DIAG) #if DIAG_REMAPPED(Z3, X_MIN) #define Z3_USE_ENDSTOP _XMIN_ @@ -971,7 +988,7 @@ #endif #endif // Auto-assign pins for stallGuard sensorless homing - #if !defined(Z4_DIAG_PIN) && !defined(Z4_USE_ENDSTOP) && defined(Z4_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && _PEXI(Z4_E_INDEX, DIAG) + #if !defined(Z4_DIAG_PIN) && !defined(Z4_USE_ENDSTOP) && defined(Z4_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && _PEXI(Z4_E_INDEX, DIAG) #define Z4_DIAG_PIN _EPIN(Z4_E_INDEX, DIAG) #if DIAG_REMAPPED(Z4, X_MIN) #define Z4_USE_ENDSTOP _XMIN_ diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h index eb7f91deab96f..0d02e1d5d9015 100755 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h @@ -28,7 +28,11 @@ #define Z2_ENABLE_PIN PF3 #define Z2_STEP_PIN PF5 #define Z2_DIR_PIN PF1 +#define Z2_STOP_PIN PA13 +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PG9 +#endif #ifndef FIL_RUNOUT2_PIN #define FIL_RUNOUT2_PIN PF13 #endif From 4483b8aaf023576ea1c8ecfa84e7093ec26ad75a Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Thu, 4 Nov 2021 17:28:42 +0700 Subject: [PATCH 023/273] =?UTF-8?q?=F0=9F=94=A8=20Fix=20IntelliSense=20/?= =?UTF-8?q?=20PIO=20conflicts=20(#23058)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/HAL/DUE/upload_extra_script.py | 19 +- Marlin/src/HAL/LPC1768/upload_extra_script.py | 198 +++--- Marlin/src/HAL/STM32F1/build_flags.py | 30 +- .../scripts/SAMD51_grandcentral_m4.py | 24 +- .../scripts/STM32F103RC_MEEB_3DP.py | 61 +- .../PlatformIO/scripts/STM32F103RC_fysetc.py | 43 +- .../scripts/STM32F1_create_variant.py | 40 +- .../share/PlatformIO/scripts/add_nanolib.py | 1 + .../share/PlatformIO/scripts/chitu_crypt.py | 167 ++--- .../PlatformIO/scripts/common-cxxflags.py | 60 +- .../scripts/common-dependencies-post.py | 22 +- .../PlatformIO/scripts/common-dependencies.py | 603 +++++++++--------- .../share/PlatformIO/scripts/custom_board.py | 20 +- .../PlatformIO/scripts/download_mks_assets.py | 84 ++- .../scripts/fix_framework_weakness.py | 47 +- .../scripts/generic_create_variant.py | 96 +-- .../jgaurora_a5s_a1_with_bootloader.py | 67 +- buildroot/share/PlatformIO/scripts/lerdge.py | 70 +- buildroot/share/PlatformIO/scripts/marlin.py | 16 +- .../share/PlatformIO/scripts/mks_robin.py | 2 +- .../share/PlatformIO/scripts/mks_robin_e3.py | 2 +- .../share/PlatformIO/scripts/mks_robin_e3p.py | 2 +- .../PlatformIO/scripts/mks_robin_lite.py | 2 +- .../PlatformIO/scripts/mks_robin_lite3.py | 2 +- .../PlatformIO/scripts/mks_robin_mini.py | 2 +- .../PlatformIO/scripts/mks_robin_nano.py | 2 +- .../PlatformIO/scripts/mks_robin_nano35.py | 2 +- .../share/PlatformIO/scripts/mks_robin_pro.py | 2 +- .../PlatformIO/scripts/offset_and_rename.py | 104 +-- buildroot/share/PlatformIO/scripts/openblt.py | 28 +- buildroot/share/PlatformIO/scripts/pioutil.py | 8 +- .../PlatformIO/scripts/preflight-checks.py | 163 +++-- .../share/PlatformIO/scripts/random-bin.py | 10 +- buildroot/share/PlatformIO/scripts/robin.py | 16 +- .../share/PlatformIO/scripts/simulator.py | 68 +- .../PlatformIO/scripts/stm32_serialbuffer.py | 114 ++-- ini/stm32f1-maple.ini | 1 - 37 files changed, 1116 insertions(+), 1082 deletions(-) diff --git a/Marlin/src/HAL/DUE/upload_extra_script.py b/Marlin/src/HAL/DUE/upload_extra_script.py index d52a0a3642b45..4f7a494512b2e 100644 --- a/Marlin/src/HAL/DUE/upload_extra_script.py +++ b/Marlin/src/HAL/DUE/upload_extra_script.py @@ -4,15 +4,16 @@ # Windows: bossac.exe # Other: leave unchanged # +import pioutil +if pioutil.is_pio_build(): + import platform + current_OS = platform.system() -import platform -current_OS = platform.system() + if current_OS == 'Windows': -if current_OS == 'Windows': + Import("env") - Import("env") - - # Use bossac.exe on Windows - env.Replace( - UPLOADCMD="bossac --info --unlock --write --verify --reset --erase -U false --boot $SOURCE" - ) + # Use bossac.exe on Windows + env.Replace( + UPLOADCMD="bossac --info --unlock --write --verify --reset --erase -U false --boot $SOURCE" + ) diff --git a/Marlin/src/HAL/LPC1768/upload_extra_script.py b/Marlin/src/HAL/LPC1768/upload_extra_script.py index fb3aaef7cd38c..7975f151f7128 100755 --- a/Marlin/src/HAL/LPC1768/upload_extra_script.py +++ b/Marlin/src/HAL/LPC1768/upload_extra_script.py @@ -1,123 +1,127 @@ # -# sets output_port +# upload_extra_script.py +# set the output_port # if target_filename is found then that drive is used # else if target_drive is found then that drive is used # from __future__ import print_function -target_filename = "FIRMWARE.CUR" -target_drive = "REARM" +import pioutil +if pioutil.is_pio_build(): -import os,getpass,platform + target_filename = "FIRMWARE.CUR" + target_drive = "REARM" -current_OS = platform.system() -Import("env") + import os,getpass,platform -def print_error(e): - print('\nUnable to find destination disk (%s)\n' \ - 'Please select it in platformio.ini using the upload_port keyword ' \ - '(https://docs.platformio.org/en/latest/projectconf/section_env_upload.html) ' \ - 'or copy the firmware (.pio/build/%s/firmware.bin) manually to the appropriate disk\n' \ - %(e, env.get('PIOENV'))) + current_OS = platform.system() + Import("env") -def before_upload(source, target, env): - try: - # - # Find a disk for upload - # - upload_disk = 'Disk not found' - target_file_found = False - target_drive_found = False - if current_OS == 'Windows': + def print_error(e): + print('\nUnable to find destination disk (%s)\n' \ + 'Please select it in platformio.ini using the upload_port keyword ' \ + '(https://docs.platformio.org/en/latest/projectconf/section_env_upload.html) ' \ + 'or copy the firmware (.pio/build/%s/firmware.bin) manually to the appropriate disk\n' \ + %(e, env.get('PIOENV'))) + + def before_upload(source, target, env): + try: + # + # Find a disk for upload # - # platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:' - # Windows - doesn't care about the disk's name, only cares about the drive letter - import subprocess,string - from ctypes import windll + upload_disk = 'Disk not found' + target_file_found = False + target_drive_found = False + if current_OS == 'Windows': + # + # platformio.ini will accept this for a Windows upload port designation: 'upload_port = L:' + # Windows - doesn't care about the disk's name, only cares about the drive letter + import subprocess,string + from ctypes import windll - # getting list of drives - # https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python - drives = [] - bitmask = windll.kernel32.GetLogicalDrives() - for letter in string.ascii_uppercase: - if bitmask & 1: - drives.append(letter) - bitmask >>= 1 + # getting list of drives + # https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python + drives = [] + bitmask = windll.kernel32.GetLogicalDrives() + for letter in string.ascii_uppercase: + if bitmask & 1: + drives.append(letter) + bitmask >>= 1 - for drive in drives: - final_drive_name = drive + ':\\' - # print ('disc check: {}'.format(final_drive_name)) - try: - volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT)) - except Exception as e: - print ('error:{}'.format(e)) - continue - else: - if target_drive in volume_info and not target_file_found: # set upload if not found target file yet - target_drive_found = True - upload_disk = final_drive_name - if target_filename in volume_info: - if not target_file_found: + for drive in drives: + final_drive_name = drive + ':\\' + # print ('disc check: {}'.format(final_drive_name)) + try: + volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT)) + except Exception as e: + print ('error:{}'.format(e)) + continue + else: + if target_drive in volume_info and not target_file_found: # set upload if not found target file yet + target_drive_found = True upload_disk = final_drive_name - target_file_found = True + if target_filename in volume_info: + if not target_file_found: + upload_disk = final_drive_name + target_file_found = True - elif current_OS == 'Linux': - # - # platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive' - # - drives = os.listdir(os.path.join(os.sep, 'media', getpass.getuser())) - if target_drive in drives: # If target drive is found, use it. - target_drive_found = True - upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), target_drive) + os.sep - else: + elif current_OS == 'Linux': + # + # platformio.ini will accept this for a Linux upload port designation: 'upload_port = /media/media_name/drive' + # + drives = os.listdir(os.path.join(os.sep, 'media', getpass.getuser())) + if target_drive in drives: # If target drive is found, use it. + target_drive_found = True + upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), target_drive) + os.sep + else: + for drive in drives: + try: + files = os.listdir(os.path.join(os.sep, 'media', getpass.getuser(), drive)) + except: + continue + else: + if target_filename in files: + upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), drive) + os.sep + target_file_found = True + break + # + # set upload_port to drive if found + # + + if target_file_found or target_drive_found: + env.Replace( + UPLOAD_FLAGS="-P$UPLOAD_PORT" + ) + + elif current_OS == 'Darwin': # MAC + # + # platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive' + # + drives = os.listdir('/Volumes') # human readable names + if target_drive in drives and not target_file_found: # set upload if not found target file yet + target_drive_found = True + upload_disk = '/Volumes/' + target_drive + '/' for drive in drives: try: - files = os.listdir(os.path.join(os.sep, 'media', getpass.getuser(), drive)) + filenames = os.listdir('/Volumes/' + drive + '/') # will get an error if the drive is protected except: continue else: - if target_filename in files: - upload_disk = os.path.join(os.sep, 'media', getpass.getuser(), drive) + os.sep + if target_filename in filenames: + if not target_file_found: + upload_disk = '/Volumes/' + drive + '/' target_file_found = True - break - # - # set upload_port to drive if found - # - if target_file_found or target_drive_found: - env.Replace( - UPLOAD_FLAGS="-P$UPLOAD_PORT" - ) - - elif current_OS == 'Darwin': # MAC # - # platformio.ini will accept this for a OSX upload port designation: 'upload_port = /media/media_name/drive' + # Set upload_port to drive if found # - drives = os.listdir('/Volumes') # human readable names - if target_drive in drives and not target_file_found: # set upload if not found target file yet - target_drive_found = True - upload_disk = '/Volumes/' + target_drive + '/' - for drive in drives: - try: - filenames = os.listdir('/Volumes/' + drive + '/') # will get an error if the drive is protected - except: - continue - else: - if target_filename in filenames: - if not target_file_found: - upload_disk = '/Volumes/' + drive + '/' - target_file_found = True - - # - # Set upload_port to drive if found - # - if target_file_found or target_drive_found: - env.Replace(UPLOAD_PORT=upload_disk) - print('\nUpload disk: ', upload_disk, '\n') - else: - print_error('Autodetect Error') + if target_file_found or target_drive_found: + env.Replace(UPLOAD_PORT=upload_disk) + print('\nUpload disk: ', upload_disk, '\n') + else: + print_error('Autodetect Error') - except Exception as e: - print_error(str(e)) + except Exception as e: + print_error(str(e)) -env.AddPreAction("upload", before_upload) + env.AddPreAction("upload", before_upload) diff --git a/Marlin/src/HAL/STM32F1/build_flags.py b/Marlin/src/HAL/STM32F1/build_flags.py index d0848d1c64383..970ca8b767f9f 100755 --- a/Marlin/src/HAL/STM32F1/build_flags.py +++ b/Marlin/src/HAL/STM32F1/build_flags.py @@ -30,25 +30,27 @@ # extra script for linker options else: - from SCons.Script import DefaultEnvironment - env = DefaultEnvironment() - env.Append( + import pioutil + if pioutil.is_pio_build(): + from SCons.Script import DefaultEnvironment + env = DefaultEnvironment() + env.Append( ARFLAGS=["rcs"], ASFLAGS=["-x", "assembler-with-cpp"], CXXFLAGS=[ - "-fabi-version=0", - "-fno-use-cxa-atexit", - "-fno-threadsafe-statics" + "-fabi-version=0", + "-fno-use-cxa-atexit", + "-fno-threadsafe-statics" ], LINKFLAGS=[ - "-Os", - "-mcpu=cortex-m3", - "-ffreestanding", - "-mthumb", - "--specs=nano.specs", - "--specs=nosys.specs", - "-u_printf_float", + "-Os", + "-mcpu=cortex-m3", + "-ffreestanding", + "-mthumb", + "--specs=nano.specs", + "--specs=nosys.specs", + "-u_printf_float", ], - ) + ) diff --git a/buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py b/buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py index 9e37024d118fc..be2c87266acc6 100644 --- a/buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py +++ b/buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py @@ -2,18 +2,20 @@ # SAMD51_grandcentral_m4.py # Customizations for env:SAMD51_grandcentral_m4 # -from os.path import join, isfile -import shutil -from pprint import pprint +import pioutil +if pioutil.is_pio_build(): + from os.path import join, isfile + import shutil + from pprint import pprint -Import("env") + Import("env") -mf = env["MARLIN_FEATURES"] -rxBuf = mf["RX_BUFFER_SIZE"] if "RX_BUFFER_SIZE" in mf else "0" -txBuf = mf["TX_BUFFER_SIZE"] if "TX_BUFFER_SIZE" in mf else "0" + mf = env["MARLIN_FEATURES"] + rxBuf = mf["RX_BUFFER_SIZE"] if "RX_BUFFER_SIZE" in mf else "0" + txBuf = mf["TX_BUFFER_SIZE"] if "TX_BUFFER_SIZE" in mf else "0" -serialBuf = str(max(int(rxBuf), int(txBuf), 350)) + serialBuf = str(max(int(rxBuf), int(txBuf), 350)) -build_flags = env.get('BUILD_FLAGS') -build_flags.append("-DSERIAL_BUFFER_SIZE=" + serialBuf) -env.Replace(BUILD_FLAGS=build_flags) + build_flags = env.get('BUILD_FLAGS') + build_flags.append("-DSERIAL_BUFFER_SIZE=" + serialBuf) + env.Replace(BUILD_FLAGS=build_flags) diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py index e059d445789c1..eccee76068041 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py @@ -1,40 +1,43 @@ # -# buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py +# STM32F103RC_MEEB_3DP.py # -try: - import configparser -except ImportError: - import ConfigParser as configparser +import pioutil +if pioutil.is_pio_build(): -import os -Import("env", "projenv") + try: + import configparser + except ImportError: + import ConfigParser as configparser -config = configparser.ConfigParser() -config.read("platformio.ini") + import os + Import("env", "projenv") -# -# Upload actions -# -def before_upload(source, target, env): - env.Execute("pwd") + config = configparser.ConfigParser() + config.read("platformio.ini") + + # + # Upload actions + # + def before_upload(source, target, env): + env.Execute("pwd") -def after_upload(source, target, env): - env.Execute("pwd") + def after_upload(source, target, env): + env.Execute("pwd") -env.AddPreAction("upload", before_upload) -env.AddPostAction("upload", after_upload) + env.AddPreAction("upload", before_upload) + env.AddPostAction("upload", after_upload) -flash_size = 0 -vect_tab_addr = 0 + flash_size = 0 + vect_tab_addr = 0 -for define in env['CPPDEFINES']: - if define[0] == "VECT_TAB_ADDR": - vect_tab_addr = define[1] - if define[0] == "STM32_FLASH_SIZE": - flash_size = define[1] + for define in env['CPPDEFINES']: + if define[0] == "VECT_TAB_ADDR": + vect_tab_addr = define[1] + if define[0] == "STM32_FLASH_SIZE": + flash_size = define[1] -print('Use the {0:s} address as the marlin app entry point.'.format(vect_tab_addr)) -print('Use the {0:d}KB flash version of stm32f103rct6 chip.'.format(flash_size)) + print('Use the {0:s} address as the marlin app entry point.'.format(vect_tab_addr)) + print('Use the {0:d}KB flash version of stm32f103rct6 chip.'.format(flash_size)) -import marlin -marlin.custom_ld_script("STM32F103RC_MEEB_3DP.ld") + import marlin + marlin.custom_ld_script("STM32F103RC_MEEB_3DP.ld") diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py index 07f6548b18d95..c9794702c34a3 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py @@ -1,25 +1,28 @@ # -# buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +# STM32F103RC_fysetc.py # -from os.path import join -from os.path import expandvars -Import("env") +import pioutil +if pioutil.is_pio_build(): + import os + from os.path import join + from os.path import expandvars + Import("env") -# Custom HEX from ELF -env.AddPostAction( - join("$BUILD_DIR", "${PROGNAME}.elf"), - env.VerboseAction(" ".join([ - "$OBJCOPY", "-O ihex", "$TARGET", - "\"" + join("$BUILD_DIR", "${PROGNAME}.hex") + "\"", # Note: $BUILD_DIR is a full path - ]), "Building $TARGET")) + # Custom HEX from ELF + env.AddPostAction( + join("$BUILD_DIR", "${PROGNAME}.elf"), + env.VerboseAction(" ".join([ + "$OBJCOPY", "-O ihex", "$TARGET", + "\"" + join("$BUILD_DIR", "${PROGNAME}.hex") + "\"", # Note: $BUILD_DIR is a full path + ]), "Building $TARGET")) -# In-line command with arguments -UPLOAD_TOOL="stm32flash" -platform = env.PioPlatform() -if platform.get_package_dir("tool-stm32duino") != None: - UPLOAD_TOOL=expandvars("\"" + join(platform.get_package_dir("tool-stm32duino"),"stm32flash","stm32flash") + "\"") + # In-line command with arguments + UPLOAD_TOOL="stm32flash" + platform = env.PioPlatform() + if platform.get_package_dir("tool-stm32duino") != None: + UPLOAD_TOOL=expandvars("\"" + join(platform.get_package_dir("tool-stm32duino"),"stm32flash","stm32flash") + "\"") -env.Replace( - UPLOADER=UPLOAD_TOOL, - UPLOADCMD=expandvars(UPLOAD_TOOL + " -v -i rts,-dtr,dtr -R -b 115200 -g 0x8000000 -w \"" + join("$BUILD_DIR","${PROGNAME}.hex")+"\"" + " $UPLOAD_PORT") -) + env.Replace( + UPLOADER=UPLOAD_TOOL, + UPLOADCMD=expandvars(UPLOAD_TOOL + " -v -i rts,-dtr,dtr -R -b 115200 -g 0x8000000 -w \"" + join("$BUILD_DIR","${PROGNAME}.hex")+"\"" + " $UPLOAD_PORT") + ) diff --git a/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py b/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py index 0a38e1ceee9d7..592fa50e5e680 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py @@ -1,30 +1,32 @@ # # STM32F1_create_variant.py # -import os,shutil,marlin -from SCons.Script import DefaultEnvironment -from platformio import util +import pioutil +if pioutil.is_pio_build(): + import os,shutil,marlin + from SCons.Script import DefaultEnvironment + from platformio import util -env = DefaultEnvironment() -platform = env.PioPlatform() -board = env.BoardConfig() + env = DefaultEnvironment() + platform = env.PioPlatform() + board = env.BoardConfig() -FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32-maple") -assert os.path.isdir(FRAMEWORK_DIR) + FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32-maple") + assert os.path.isdir(FRAMEWORK_DIR) -source_root = os.path.join("buildroot", "share", "PlatformIO", "variants") -assert os.path.isdir(source_root) + source_root = os.path.join("buildroot", "share", "PlatformIO", "variants") + assert os.path.isdir(source_root) -variant = board.get("build.variant") -variant_dir = os.path.join(FRAMEWORK_DIR, "STM32F1", "variants", variant) + variant = board.get("build.variant") + variant_dir = os.path.join(FRAMEWORK_DIR, "STM32F1", "variants", variant) -source_dir = os.path.join(source_root, variant) -assert os.path.isdir(source_dir) + source_dir = os.path.join(source_root, variant) + assert os.path.isdir(source_dir) -if os.path.isdir(variant_dir): - shutil.rmtree(variant_dir) + if os.path.isdir(variant_dir): + shutil.rmtree(variant_dir) -if not os.path.isdir(variant_dir): - os.mkdir(variant_dir) + if not os.path.isdir(variant_dir): + os.mkdir(variant_dir) -marlin.copytree(source_dir, variant_dir) + marlin.copytree(source_dir, variant_dir) diff --git a/buildroot/share/PlatformIO/scripts/add_nanolib.py b/buildroot/share/PlatformIO/scripts/add_nanolib.py index 3b74b0d2714de..f5166d7d84c7c 100644 --- a/buildroot/share/PlatformIO/scripts/add_nanolib.py +++ b/buildroot/share/PlatformIO/scripts/add_nanolib.py @@ -2,4 +2,5 @@ # add_nanolib.py # Import("env") + env.Append(LINKFLAGS=["--specs=nano.specs"]) diff --git a/buildroot/share/PlatformIO/scripts/chitu_crypt.py b/buildroot/share/PlatformIO/scripts/chitu_crypt.py index 23d81c1721f91..b28156bfb9f1d 100644 --- a/buildroot/share/PlatformIO/scripts/chitu_crypt.py +++ b/buildroot/share/PlatformIO/scripts/chitu_crypt.py @@ -1,116 +1,117 @@ # -# buildroot/share/PlatformIO/scripts/chitu_crypt.py +# chitu_crypt.py # Customizations for Chitu boards # -import os,random,struct,uuid,marlin +import pioutil +if pioutil.is_pio_build(): + import os,random,struct,uuid,marlin + # Relocate firmware from 0x08000000 to 0x08008800 + marlin.relocate_firmware("0x08008800") -# Relocate firmware from 0x08000000 to 0x08008800 -marlin.relocate_firmware("0x08008800") + def calculate_crc(contents, seed): + accumulating_xor_value = seed; -def calculate_crc(contents, seed): - accumulating_xor_value = seed; + for i in range(0, len(contents), 4): + value = struct.unpack('> ip - # shift the xor_seed left by the bits in IP. - xor_seed = xor_seed >> ip + # load a byte into IP + ip = r0[loop_counter] - # load a byte into IP - ip = r0[loop_counter] + # XOR the seed with r7 + xor_seed = xor_seed ^ r7 - # XOR the seed with r7 - xor_seed = xor_seed ^ r7 + # and then with IP + xor_seed = xor_seed ^ ip - # and then with IP - xor_seed = xor_seed ^ ip + #Now store the byte back + r1[loop_counter] = xor_seed & 0xFF - #Now store the byte back - r1[loop_counter] = xor_seed & 0xFF + #increment the loop_counter + loop_counter = loop_counter + 1 - #increment the loop_counter - loop_counter = loop_counter + 1 + def encrypt_file(input, output_file, file_length): + input_file = bytearray(input.read()) + block_size = 0x800 + key_length = 0x18 -def encrypt_file(input, output_file, file_length): - input_file = bytearray(input.read()) - block_size = 0x800 - key_length = 0x18 + uid_value = uuid.uuid4() + file_key = int(uid_value.hex[0:8], 16) - uid_value = uuid.uuid4() - file_key = int(uid_value.hex[0:8], 16) + xor_crc = 0xEF3D4323; - xor_crc = 0xEF3D4323; + # the input file is exepcted to be in chunks of 0x800 + # so round the size + while len(input_file) % block_size != 0: + input_file.extend(b'0x0') - # the input file is exepcted to be in chunks of 0x800 - # so round the size - while len(input_file) % block_size != 0: - input_file.extend(b'0x0') + # write the file header + output_file.write(struct.pack(">I", 0x443D2D3F)) + # encrypt the contents using a known file header key - # write the file header - output_file.write(struct.pack(">I", 0x443D2D3F)) - # encrypt the contents using a known file header key + # write the file_key + output_file.write(struct.pack("= level: - print("[deps] %s" % str) - -FEATURE_CONFIG = {} +import pioutil +if pioutil.is_pio_build(): -def add_to_feat_cnf(feature, flines): + import subprocess,os,re + Import("env") - try: - feat = FEATURE_CONFIG[feature] - except: - FEATURE_CONFIG[feature] = {} - - # Get a reference to the FEATURE_CONFIG under construction - feat = FEATURE_CONFIG[feature] - - # Split up passed lines on commas or newlines and iterate - # Add common options to the features config under construction - # For lib_deps replace a previous instance of the same library - atoms = re.sub(r',\\s*', '\n', flines).strip().split('\n') - for line in atoms: - parts = line.split('=') - name = parts.pop(0) - if name in ['build_flags', 'extra_scripts', 'src_filter', 'lib_ignore']: - feat[name] = '='.join(parts) - blab("[%s] %s=%s" % (feature, name, feat[name]), 3) - else: - for dep in re.split(r",\s*", line): - lib_name = re.sub(r'@([~^]|[<>]=?)?[\d.]+', '', dep.strip()).split('=').pop(0) - lib_re = re.compile('(?!^' + lib_name + '\\b)') - feat['lib_deps'] = list(filter(lib_re.match, feat['lib_deps'])) + [dep] - blab("[%s] lib_deps = %s" % (feature, dep), 3) - -def load_config(): - blab("========== Gather [features] entries...") - items = ProjectConfig().items('features') - for key in items: - feature = key[0].upper() - if not feature in FEATURE_CONFIG: - FEATURE_CONFIG[feature] = { 'lib_deps': [] } - add_to_feat_cnf(feature, key[1]) - - # Add options matching custom_marlin.MY_OPTION to the pile - blab("========== Gather custom_marlin entries...") - all_opts = env.GetProjectOptions() - for n in all_opts: - key = n[0] - mat = re.match(r'custom_marlin\.(.+)', key) - if mat: - try: - val = env.GetProjectOption(key) - except: - val = None - if val: - opt = mat.group(1).upper() - blab("%s.custom_marlin.%s = '%s'" % ( env['PIOENV'], opt, val )) - add_to_feat_cnf(opt, val) - -def get_all_known_libs(): - known_libs = [] - for feature in FEATURE_CONFIG: - feat = FEATURE_CONFIG[feature] - if not 'lib_deps' in feat: - continue - for dep in feat['lib_deps']: - known_libs.append(PackageSpec(dep).name) - return known_libs - -def get_all_env_libs(): - env_libs = [] - lib_deps = env.GetProjectOption('lib_deps') - for dep in lib_deps: - env_libs.append(PackageSpec(dep).name) - return env_libs - -def set_env_field(field, value): - proj = env.GetProjectConfig() - proj.set("env:" + env['PIOENV'], field, value) - -# All unused libs should be ignored so that if a library -# exists in .pio/lib_deps it will not break compilation. -def force_ignore_unused_libs(): - env_libs = get_all_env_libs() - known_libs = get_all_known_libs() - diff = (list(set(known_libs) - set(env_libs))) - lib_ignore = env.GetProjectOption('lib_ignore') + diff - blab("Ignore libraries: %s" % lib_ignore) - set_env_field('lib_ignore', lib_ignore) - -def apply_features_config(): - load_config() - blab("========== Apply enabled features...") - for feature in FEATURE_CONFIG: - if not env.MarlinFeatureIsEnabled(feature): - continue + from platformio.package.meta import PackageSpec + from platformio.project.config import ProjectConfig + verbose = 0 + FEATURE_CONFIG = {} + + def validate_pio(): + PIO_VERSION_MIN = (5, 0, 3) + try: + from platformio import VERSION as PIO_VERSION + weights = (1000, 100, 1) + version_min = sum([x[0] * float(re.sub(r'[^0-9]', '.', str(x[1]))) for x in zip(weights, PIO_VERSION_MIN)]) + version_cur = sum([x[0] * float(re.sub(r'[^0-9]', '.', str(x[1]))) for x in zip(weights, PIO_VERSION)]) + if version_cur < version_min: + print() + print("**************************************************") + print("****** An update to PlatformIO is ******") + print("****** required to build Marlin Firmware. ******") + print("****** ******") + print("****** Minimum version: ", PIO_VERSION_MIN, " ******") + print("****** Current Version: ", PIO_VERSION, " ******") + print("****** ******") + print("****** Update PlatformIO and try again. ******") + print("**************************************************") + print() + exit(1) + except SystemExit: + exit(1) + except: + print("Can't detect PlatformIO Version") + + def blab(str,level=1): + if verbose >= level: + print("[deps] %s" % str) + + def add_to_feat_cnf(feature, flines): + + try: + feat = FEATURE_CONFIG[feature] + except: + FEATURE_CONFIG[feature] = {} + + # Get a reference to the FEATURE_CONFIG under construction feat = FEATURE_CONFIG[feature] - if 'lib_deps' in feat and len(feat['lib_deps']): - blab("========== Adding lib_deps for %s... " % feature, 2) - - # feat to add - deps_to_add = {} + # Split up passed lines on commas or newlines and iterate + # Add common options to the features config under construction + # For lib_deps replace a previous instance of the same library + atoms = re.sub(r',\\s*', '\n', flines).strip().split('\n') + for line in atoms: + parts = line.split('=') + name = parts.pop(0) + if name in ['build_flags', 'extra_scripts', 'src_filter', 'lib_ignore']: + feat[name] = '='.join(parts) + blab("[%s] %s=%s" % (feature, name, feat[name]), 3) + else: + for dep in re.split(r",\s*", line): + lib_name = re.sub(r'@([~^]|[<>]=?)?[\d.]+', '', dep.strip()).split('=').pop(0) + lib_re = re.compile('(?!^' + lib_name + '\\b)') + feat['lib_deps'] = list(filter(lib_re.match, feat['lib_deps'])) + [dep] + blab("[%s] lib_deps = %s" % (feature, dep), 3) + + def load_config(): + blab("========== Gather [features] entries...") + items = ProjectConfig().items('features') + for key in items: + feature = key[0].upper() + if not feature in FEATURE_CONFIG: + FEATURE_CONFIG[feature] = { 'lib_deps': [] } + add_to_feat_cnf(feature, key[1]) + + # Add options matching custom_marlin.MY_OPTION to the pile + blab("========== Gather custom_marlin entries...") + all_opts = env.GetProjectOptions() + for n in all_opts: + key = n[0] + mat = re.match(r'custom_marlin\.(.+)', key) + if mat: + try: + val = env.GetProjectOption(key) + except: + val = None + if val: + opt = mat.group(1).upper() + blab("%s.custom_marlin.%s = '%s'" % ( env['PIOENV'], opt, val )) + add_to_feat_cnf(opt, val) + + def get_all_known_libs(): + known_libs = [] + for feature in FEATURE_CONFIG: + feat = FEATURE_CONFIG[feature] + if not 'lib_deps' in feat: + continue for dep in feat['lib_deps']: - deps_to_add[PackageSpec(dep).name] = dep - blab("==================== %s... " % dep, 2) - - # Does the env already have the dependency? - deps = env.GetProjectOption('lib_deps') - for dep in deps: - name = PackageSpec(dep).name - if name in deps_to_add: - del deps_to_add[name] - - # Are there any libraries that should be ignored? - lib_ignore = env.GetProjectOption('lib_ignore') - for dep in deps: - name = PackageSpec(dep).name - if name in deps_to_add: - del deps_to_add[name] - - # Is there anything left? - if len(deps_to_add) > 0: - # Only add the missing dependencies - set_env_field('lib_deps', deps + list(deps_to_add.values())) - - if 'build_flags' in feat: - f = feat['build_flags'] - blab("========== Adding build_flags for %s: %s" % (feature, f), 2) - new_flags = env.GetProjectOption('build_flags') + [ f ] - env.Replace(BUILD_FLAGS=new_flags) - - if 'extra_scripts' in feat: - blab("Running extra_scripts for %s... " % feature, 2) - env.SConscript(feat['extra_scripts'], exports="env") - - if 'src_filter' in feat: - blab("========== Adding src_filter for %s... " % feature, 2) - src_filter = ' '.join(env.GetProjectOption('src_filter')) - # first we need to remove the references to the same folder - my_srcs = re.findall(r'[+-](<.*?>)', feat['src_filter']) - cur_srcs = re.findall(r'[+-](<.*?>)', src_filter) - for d in my_srcs: - if d in cur_srcs: - src_filter = re.sub(r'[+-]' + d, '', src_filter) - - src_filter = feat['src_filter'] + ' ' + src_filter - set_env_field('src_filter', [src_filter]) - env.Replace(SRC_FILTER=src_filter) - - if 'lib_ignore' in feat: - blab("========== Adding lib_ignore for %s... " % feature, 2) - lib_ignore = env.GetProjectOption('lib_ignore') + [feat['lib_ignore']] - set_env_field('lib_ignore', lib_ignore) - -# -# Find a compiler, considering the OS -# -ENV_BUILD_PATH = os.path.join(env.Dictionary('PROJECT_BUILD_DIR'), env['PIOENV']) -GCC_PATH_CACHE = os.path.join(ENV_BUILD_PATH, ".gcc_path") -def search_compiler(): - try: - filepath = env.GetProjectOption('custom_gcc') - blab("Getting compiler from env") - return filepath - except: - pass - - if os.path.exists(GCC_PATH_CACHE): - with open(GCC_PATH_CACHE, 'r') as f: - return f.read() - - # Find the current platform compiler by searching the $PATH - # which will be in a platformio toolchain bin folder - path_regex = re.escape(env['PROJECT_PACKAGES_DIR']) - - # See if the environment provides a default compiler - try: - gcc = env.GetProjectOption('custom_deps_gcc') - except: - gcc = "g++" - - if env['PLATFORM'] == 'win32': - path_separator = ';' - path_regex += r'.*\\bin' - gcc += ".exe" - else: - path_separator = ':' - path_regex += r'/.+/bin' - - # Search for the compiler - for pathdir in env['ENV']['PATH'].split(path_separator): - if not re.search(path_regex, pathdir, re.IGNORECASE): - continue - for filepath in os.listdir(pathdir): - if not filepath.endswith(gcc): + known_libs.append(PackageSpec(dep).name) + return known_libs + + def get_all_env_libs(): + env_libs = [] + lib_deps = env.GetProjectOption('lib_deps') + for dep in lib_deps: + env_libs.append(PackageSpec(dep).name) + return env_libs + + def set_env_field(field, value): + proj = env.GetProjectConfig() + proj.set("env:" + env['PIOENV'], field, value) + + # All unused libs should be ignored so that if a library + # exists in .pio/lib_deps it will not break compilation. + def force_ignore_unused_libs(): + env_libs = get_all_env_libs() + known_libs = get_all_known_libs() + diff = (list(set(known_libs) - set(env_libs))) + lib_ignore = env.GetProjectOption('lib_ignore') + diff + blab("Ignore libraries: %s" % lib_ignore) + set_env_field('lib_ignore', lib_ignore) + + def apply_features_config(): + load_config() + blab("========== Apply enabled features...") + for feature in FEATURE_CONFIG: + if not env.MarlinFeatureIsEnabled(feature): continue - # Use entire path to not rely on env PATH - filepath = os.path.sep.join([pathdir, filepath]) - # Cache the g++ path to no search always - if os.path.exists(ENV_BUILD_PATH): - with open(GCC_PATH_CACHE, 'w+') as f: - f.write(filepath) + feat = FEATURE_CONFIG[feature] + + if 'lib_deps' in feat and len(feat['lib_deps']): + blab("========== Adding lib_deps for %s... " % feature, 2) + + # feat to add + deps_to_add = {} + for dep in feat['lib_deps']: + deps_to_add[PackageSpec(dep).name] = dep + blab("==================== %s... " % dep, 2) + + # Does the env already have the dependency? + deps = env.GetProjectOption('lib_deps') + for dep in deps: + name = PackageSpec(dep).name + if name in deps_to_add: + del deps_to_add[name] + + # Are there any libraries that should be ignored? + lib_ignore = env.GetProjectOption('lib_ignore') + for dep in deps: + name = PackageSpec(dep).name + if name in deps_to_add: + del deps_to_add[name] + + # Is there anything left? + if len(deps_to_add) > 0: + # Only add the missing dependencies + set_env_field('lib_deps', deps + list(deps_to_add.values())) + + if 'build_flags' in feat: + f = feat['build_flags'] + blab("========== Adding build_flags for %s: %s" % (feature, f), 2) + new_flags = env.GetProjectOption('build_flags') + [ f ] + env.Replace(BUILD_FLAGS=new_flags) + + if 'extra_scripts' in feat: + blab("Running extra_scripts for %s... " % feature, 2) + env.SConscript(feat['extra_scripts'], exports="env") + + if 'src_filter' in feat: + blab("========== Adding src_filter for %s... " % feature, 2) + src_filter = ' '.join(env.GetProjectOption('src_filter')) + # first we need to remove the references to the same folder + my_srcs = re.findall(r'[+-](<.*?>)', feat['src_filter']) + cur_srcs = re.findall(r'[+-](<.*?>)', src_filter) + for d in my_srcs: + if d in cur_srcs: + src_filter = re.sub(r'[+-]' + d, '', src_filter) + + src_filter = feat['src_filter'] + ' ' + src_filter + set_env_field('src_filter', [src_filter]) + env.Replace(SRC_FILTER=src_filter) + + if 'lib_ignore' in feat: + blab("========== Adding lib_ignore for %s... " % feature, 2) + lib_ignore = env.GetProjectOption('lib_ignore') + [feat['lib_ignore']] + set_env_field('lib_ignore', lib_ignore) + + # + # Find a compiler, considering the OS + # + ENV_BUILD_PATH = os.path.join(env.Dictionary('PROJECT_BUILD_DIR'), env['PIOENV']) + GCC_PATH_CACHE = os.path.join(ENV_BUILD_PATH, ".gcc_path") + def search_compiler(): + try: + filepath = env.GetProjectOption('custom_gcc') + blab("Getting compiler from env") return filepath + except: + pass + + if os.path.exists(GCC_PATH_CACHE): + with open(GCC_PATH_CACHE, 'r') as f: + return f.read() + + # Find the current platform compiler by searching the $PATH + # which will be in a platformio toolchain bin folder + path_regex = re.escape(env['PROJECT_PACKAGES_DIR']) + + # See if the environment provides a default compiler + try: + gcc = env.GetProjectOption('custom_deps_gcc') + except: + gcc = "g++" + + if env['PLATFORM'] == 'win32': + path_separator = ';' + path_regex += r'.*\\bin' + gcc += ".exe" + else: + path_separator = ':' + path_regex += r'/.+/bin' - filepath = env.get('CXX') - if filepath == 'CC': - filepath = gcc - blab("Couldn't find a compiler! Fallback to %s" % filepath) - return filepath + # Search for the compiler + for pathdir in env['ENV']['PATH'].split(path_separator): + if not re.search(path_regex, pathdir, re.IGNORECASE): + continue + for filepath in os.listdir(pathdir): + if not filepath.endswith(gcc): + continue + # Use entire path to not rely on env PATH + filepath = os.path.sep.join([pathdir, filepath]) + # Cache the g++ path to no search always + if os.path.exists(ENV_BUILD_PATH): + with open(GCC_PATH_CACHE, 'w+') as f: + f.write(filepath) + + return filepath + + filepath = env.get('CXX') + if filepath == 'CC': + filepath = gcc + blab("Couldn't find a compiler! Fallback to %s" % filepath) + return filepath -# -# Use the compiler to get a list of all enabled features -# -def load_marlin_features(): - if 'MARLIN_FEATURES' in env: - return - - # Process defines - build_flags = env.get('BUILD_FLAGS') - build_flags = env.ParseFlagsExtended(build_flags) - - cxx = search_compiler() - cmd = ['"' + cxx + '"'] - - # Build flags from board.json - #if 'BOARD' in env: - # cmd += [env.BoardConfig().get("build.extra_flags")] - for s in build_flags['CPPDEFINES']: - if isinstance(s, tuple): - cmd += ['-D' + s[0] + '=' + str(s[1])] - else: - cmd += ['-D' + s] - - cmd += ['-D__MARLIN_DEPS__ -w -dM -E -x c++ buildroot/share/PlatformIO/scripts/common-dependencies.h'] - cmd = ' '.join(cmd) - blab(cmd, 4) - define_list = subprocess.check_output(cmd, shell=True).splitlines() - marlin_features = {} - for define in define_list: - feature = define[8:].strip().decode().split(' ') - feature, definition = feature[0], ' '.join(feature[1:]) - marlin_features[feature] = definition - env['MARLIN_FEATURES'] = marlin_features + # + # Use the compiler to get a list of all enabled features + # + def load_marlin_features(): + if 'MARLIN_FEATURES' in env: + return + + # Process defines + build_flags = env.get('BUILD_FLAGS') + build_flags = env.ParseFlagsExtended(build_flags) + + cxx = search_compiler() + cmd = ['"' + cxx + '"'] + + # Build flags from board.json + #if 'BOARD' in env: + # cmd += [env.BoardConfig().get("build.extra_flags")] + for s in build_flags['CPPDEFINES']: + if isinstance(s, tuple): + cmd += ['-D' + s[0] + '=' + str(s[1])] + else: + cmd += ['-D' + s] + + cmd += ['-D__MARLIN_DEPS__ -w -dM -E -x c++ buildroot/share/PlatformIO/scripts/common-dependencies.h'] + cmd = ' '.join(cmd) + blab(cmd, 4) + define_list = subprocess.check_output(cmd, shell=True).splitlines() + marlin_features = {} + for define in define_list: + feature = define[8:].strip().decode().split(' ') + feature, definition = feature[0], ' '.join(feature[1:]) + marlin_features[feature] = definition + env['MARLIN_FEATURES'] = marlin_features + + # + # Return True if a matching feature is enabled + # + def MarlinFeatureIsEnabled(env, feature): + load_marlin_features() + r = re.compile('^' + feature + '$') + found = list(filter(r.match, env['MARLIN_FEATURES'])) + + # Defines could still be 'false' or '0', so check + some_on = False + if len(found): + for f in found: + val = env['MARLIN_FEATURES'][f] + if val in [ '', '1', 'true' ]: + some_on = True + elif val in env['MARLIN_FEATURES']: + some_on = env.MarlinFeatureIsEnabled(val) + + return some_on + + validate_pio() -# -# Return True if a matching feature is enabled -# -def MarlinFeatureIsEnabled(env, feature): - load_marlin_features() - r = re.compile('^' + feature + '$') - found = list(filter(r.match, env['MARLIN_FEATURES'])) - - # Defines could still be 'false' or '0', so check - some_on = False - if len(found): - for f in found: - val = env['MARLIN_FEATURES'][f] - if val in [ '', '1', 'true' ]: - some_on = True - elif val in env['MARLIN_FEATURES']: - some_on = env.MarlinFeatureIsEnabled(val) - - return some_on + try: + verbose = int(env.GetProjectOption('custom_verbose')) + except: + pass -# -# Add a method for other PIO scripts to query enabled features -# -env.AddMethod(MarlinFeatureIsEnabled) + # Add a method for other PIO scripts to query enabled features + env.AddMethod(MarlinFeatureIsEnabled) -# -# Add dependencies for enabled Marlin features -# -apply_features_config() -force_ignore_unused_libs() + # Add dependencies for enabled Marlin features + apply_features_config() + force_ignore_unused_libs() diff --git a/buildroot/share/PlatformIO/scripts/custom_board.py b/buildroot/share/PlatformIO/scripts/custom_board.py index e462738190dd5..da3bdca0bbe70 100644 --- a/buildroot/share/PlatformIO/scripts/custom_board.py +++ b/buildroot/share/PlatformIO/scripts/custom_board.py @@ -1,16 +1,18 @@ # -# buildroot/share/PlatformIO/scripts/custom_board.py +# custom_board.py # # - For build.address replace VECT_TAB_ADDR to relocate the firmware # - For build.ldscript use one of the linker scripts in buildroot/share/PlatformIO/ldscripts # -import marlin -board = marlin.env.BoardConfig() +import pioutil +if pioutil.is_pio_build(): + import marlin + board = marlin.env.BoardConfig() -address = board.get("build.address", "") -if address: - marlin.relocate_firmware(address) + address = board.get("build.address", "") + if address: + marlin.relocate_firmware(address) -ldscript = board.get("build.ldscript", "") -if ldscript: - marlin.custom_ld_script(ldscript) + ldscript = board.get("build.ldscript", "") + if ldscript: + marlin.custom_ld_script(ldscript) diff --git a/buildroot/share/PlatformIO/scripts/download_mks_assets.py b/buildroot/share/PlatformIO/scripts/download_mks_assets.py index 251a74a4ccb5a..199040022282f 100644 --- a/buildroot/share/PlatformIO/scripts/download_mks_assets.py +++ b/buildroot/share/PlatformIO/scripts/download_mks_assets.py @@ -1,51 +1,49 @@ # -# buildroot/share/PlatformIO/scripts/download_mks_assets.py +# download_mks_assets.py # Added by HAS_TFT_LVGL_UI to download assets from Makerbase repo # -Import("env") -import os,requests,zipfile,tempfile,shutil,pioutil +import pioutil +if pioutil.is_pio_build(): + Import("env") + import os,requests,zipfile,tempfile,shutil -# Detect that 'vscode init' is running -if pioutil.is_vscode_init(): - env.Exit(0) + url = "https://github.com/makerbase-mks/Mks-Robin-Nano-Marlin2.0-Firmware/archive/0263cdaccf.zip" + deps_path = env.Dictionary("PROJECT_LIBDEPS_DIR") + zip_path = os.path.join(deps_path, "mks-assets.zip") + assets_path = os.path.join(env.Dictionary("PROJECT_BUILD_DIR"), env.Dictionary("PIOENV"), "assets") -url = "https://github.com/makerbase-mks/Mks-Robin-Nano-Marlin2.0-Firmware/archive/0263cdaccf.zip" -deps_path = env.Dictionary("PROJECT_LIBDEPS_DIR") -zip_path = os.path.join(deps_path, "mks-assets.zip") -assets_path = os.path.join(env.Dictionary("PROJECT_BUILD_DIR"), env.Dictionary("PIOENV"), "assets") + def download_mks_assets(): + print("Downloading MKS Assets") + r = requests.get(url, stream=True) + # the user may have a very clean workspace, + # so create the PROJECT_LIBDEPS_DIR directory if not exits + if os.path.exists(deps_path) == False: + os.mkdir(deps_path) + with open(zip_path, 'wb') as fd: + for chunk in r.iter_content(chunk_size=128): + fd.write(chunk) -def download_mks_assets(): - print("Downloading MKS Assets") - r = requests.get(url, stream=True) - # the user may have a very clean workspace, - # so create the PROJECT_LIBDEPS_DIR directory if not exits - if os.path.exists(deps_path) == False: - os.mkdir(deps_path) - with open(zip_path, 'wb') as fd: - for chunk in r.iter_content(chunk_size=128): - fd.write(chunk) + def copy_mks_assets(): + print("Copying MKS Assets") + output_path = tempfile.mkdtemp() + zip_obj = zipfile.ZipFile(zip_path, 'r') + zip_obj.extractall(output_path) + zip_obj.close() + if os.path.exists(assets_path) == True and os.path.isdir(assets_path) == False: + os.unlink(assets_path) + if os.path.exists(assets_path) == False: + os.mkdir(assets_path) + base_path = '' + for filename in os.listdir(output_path): + base_path = filename + for filename in os.listdir(os.path.join(output_path, base_path, 'Firmware', 'mks_font')): + shutil.copy(os.path.join(output_path, base_path, 'Firmware', 'mks_font', filename), assets_path) + for filename in os.listdir(os.path.join(output_path, base_path, 'Firmware', 'mks_pic')): + shutil.copy(os.path.join(output_path, base_path, 'Firmware', 'mks_pic', filename), assets_path) + shutil.rmtree(output_path, ignore_errors=True) -def copy_mks_assets(): - print("Copying MKS Assets") - output_path = tempfile.mkdtemp() - zip_obj = zipfile.ZipFile(zip_path, 'r') - zip_obj.extractall(output_path) - zip_obj.close() - if os.path.exists(assets_path) == True and os.path.isdir(assets_path) == False: - os.unlink(assets_path) - if os.path.exists(assets_path) == False: - os.mkdir(assets_path) - base_path = '' - for filename in os.listdir(output_path): - base_path = filename - for filename in os.listdir(os.path.join(output_path, base_path, 'Firmware', 'mks_font')): - shutil.copy(os.path.join(output_path, base_path, 'Firmware', 'mks_font', filename), assets_path) - for filename in os.listdir(os.path.join(output_path, base_path, 'Firmware', 'mks_pic')): - shutil.copy(os.path.join(output_path, base_path, 'Firmware', 'mks_pic', filename), assets_path) - shutil.rmtree(output_path, ignore_errors=True) - -if os.path.exists(zip_path) == False: - download_mks_assets() + if os.path.exists(zip_path) == False: + download_mks_assets() -if os.path.exists(assets_path) == False: - copy_mks_assets() + if os.path.exists(assets_path) == False: + copy_mks_assets() diff --git a/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py b/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py index fa91b7bb7041e..663e7c76d96ad 100644 --- a/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py +++ b/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py @@ -1,32 +1,35 @@ # # fix_framework_weakness.py # -from os.path import join, isfile -import shutil -from pprint import pprint +import pioutil +if pioutil.is_pio_build(): -Import("env") + import shutil + from os.path import join, isfile + from pprint import pprint -if env.MarlinFeatureIsEnabled("POSTMORTEM_DEBUGGING"): - FRAMEWORK_DIR = env.PioPlatform().get_package_dir("framework-arduinoststm32-maple") - patchflag_path = join(FRAMEWORK_DIR, ".exc-patching-done") + Import("env") - # patch file only if we didn't do it before - if not isfile(patchflag_path): - print("Patching libmaple exception handlers") - original_file = join(FRAMEWORK_DIR, "STM32F1", "cores", "maple", "libmaple", "exc.S") - backup_file = join(FRAMEWORK_DIR, "STM32F1", "cores", "maple", "libmaple", "exc.S.bak") - src_file = join("buildroot", "share", "PlatformIO", "scripts", "exc.S") + if env.MarlinFeatureIsEnabled("POSTMORTEM_DEBUGGING"): + FRAMEWORK_DIR = env.PioPlatform().get_package_dir("framework-arduinoststm32-maple") + patchflag_path = join(FRAMEWORK_DIR, ".exc-patching-done") - assert isfile(original_file) and isfile(src_file) - shutil.copyfile(original_file, backup_file) - shutil.copyfile(src_file, original_file); + # patch file only if we didn't do it before + if not isfile(patchflag_path): + print("Patching libmaple exception handlers") + original_file = join(FRAMEWORK_DIR, "STM32F1", "cores", "maple", "libmaple", "exc.S") + backup_file = join(FRAMEWORK_DIR, "STM32F1", "cores", "maple", "libmaple", "exc.S.bak") + src_file = join("buildroot", "share", "PlatformIO", "scripts", "exc.S") - def _touch(path): - with open(path, "w") as fp: - fp.write("") + assert isfile(original_file) and isfile(src_file) + shutil.copyfile(original_file, backup_file) + shutil.copyfile(src_file, original_file); - env.Execute(lambda *args, **kwargs: _touch(patchflag_path)) - print("Done patching exception handler") + def _touch(path): + with open(path, "w") as fp: + fp.write("") - print("Libmaple modified and ready for post mortem debugging") + env.Execute(lambda *args, **kwargs: _touch(patchflag_path)) + print("Done patching exception handler") + + print("Libmaple modified and ready for post mortem debugging") diff --git a/buildroot/share/PlatformIO/scripts/generic_create_variant.py b/buildroot/share/PlatformIO/scripts/generic_create_variant.py index 7f76ef94262c2..52473c752ac6f 100644 --- a/buildroot/share/PlatformIO/scripts/generic_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -5,50 +5,52 @@ # the appropriate framework variants folder, so that its contents # will be picked up by PlatformIO just like any other variant. # -import os,shutil,marlin -from SCons.Script import DefaultEnvironment -from platformio import util - -env = DefaultEnvironment() - -# -# Get the platform name from the 'platform_packages' option, -# or look it up by the platform.class.name. -# -platform = env.PioPlatform() - -from platformio.package.meta import PackageSpec -platform_packages = env.GetProjectOption('platform_packages') -if len(platform_packages) == 0: - framewords = { - "Ststm32Platform": "framework-arduinoststm32", - "AtmelavrPlatform": "framework-arduino-avr" - } - platform_name = framewords[platform.__class__.__name__] -else: - platform_name = PackageSpec(platform_packages[0]).name - -if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "usb-host-msc-cdc-msc-2", "usb-host-msc-cdc-msc-3", "tool-stm32duino" ]: - platform_name = "framework-arduinoststm32" - -FRAMEWORK_DIR = platform.get_package_dir(platform_name) -assert os.path.isdir(FRAMEWORK_DIR) - -board = env.BoardConfig() - -#mcu_type = board.get("build.mcu")[:-2] -variant = board.get("build.variant") -#series = mcu_type[:7].upper() + "xx" - -# Prepare a new empty folder at the destination -variant_dir = os.path.join(FRAMEWORK_DIR, "variants", variant) -if os.path.isdir(variant_dir): - shutil.rmtree(variant_dir) -if not os.path.isdir(variant_dir): - os.mkdir(variant_dir) - -# Source dir is a local variant sub-folder -source_dir = os.path.join("buildroot/share/PlatformIO/variants", variant) -assert os.path.isdir(source_dir) - -marlin.copytree(source_dir, variant_dir) +import pioutil +if pioutil.is_pio_build(): + import os,shutil,marlin + from SCons.Script import DefaultEnvironment + from platformio import util + + env = DefaultEnvironment() + + # + # Get the platform name from the 'platform_packages' option, + # or look it up by the platform.class.name. + # + platform = env.PioPlatform() + + from platformio.package.meta import PackageSpec + platform_packages = env.GetProjectOption('platform_packages') + if len(platform_packages) == 0: + framewords = { + "Ststm32Platform": "framework-arduinoststm32", + "AtmelavrPlatform": "framework-arduino-avr" + } + platform_name = framewords[platform.__class__.__name__] + else: + platform_name = PackageSpec(platform_packages[0]).name + + if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "usb-host-msc-cdc-msc-2", "usb-host-msc-cdc-msc-3", "tool-stm32duino" ]: + platform_name = "framework-arduinoststm32" + + FRAMEWORK_DIR = platform.get_package_dir(platform_name) + assert os.path.isdir(FRAMEWORK_DIR) + + board = env.BoardConfig() + + #mcu_type = board.get("build.mcu")[:-2] + variant = board.get("build.variant") + #series = mcu_type[:7].upper() + "xx" + + # Prepare a new empty folder at the destination + variant_dir = os.path.join(FRAMEWORK_DIR, "variants", variant) + if os.path.isdir(variant_dir): + shutil.rmtree(variant_dir) + if not os.path.isdir(variant_dir): + os.mkdir(variant_dir) + + # Source dir is a local variant sub-folder + source_dir = os.path.join("buildroot/share/PlatformIO/variants", variant) + assert os.path.isdir(source_dir) + + marlin.copytree(source_dir, variant_dir) diff --git a/buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py b/buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py index a4001a240ca1b..0af9c1046d1e6 100644 --- a/buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py +++ b/buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py @@ -1,39 +1,40 @@ # -# buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py +# jgaurora_a5s_a1_with_bootloader.py # Customizations for env:jgaurora_a5s_a1 # -import os,marlin +import pioutil +if pioutil.is_pio_build(): + import os,marlin + # Append ${PROGNAME}.bin firmware after bootloader and save it as 'jgaurora_firmware.bin' + def addboot(source, target, env): + firmware = open(target[0].path, "rb") + lengthfirmware = os.path.getsize(target[0].path) + bootloader_bin = "buildroot/share/PlatformIO/scripts/" + "jgaurora_bootloader.bin" + bootloader = open(bootloader_bin, "rb") + lengthbootloader = os.path.getsize(bootloader_bin) -# Append ${PROGNAME}.bin firmware after bootloader and save it as 'jgaurora_firmware.bin' -def addboot(source, target, env): - firmware = open(target[0].path, "rb") - lengthfirmware = os.path.getsize(target[0].path) - bootloader_bin = "buildroot/share/PlatformIO/scripts/" + "jgaurora_bootloader.bin" - bootloader = open(bootloader_bin, "rb") - lengthbootloader = os.path.getsize(bootloader_bin) + firmware_with_boothloader_bin = target[0].dir.path + '/firmware_with_bootloader.bin' + if os.path.exists(firmware_with_boothloader_bin): + os.remove(firmware_with_boothloader_bin) + firmwareimage = open(firmware_with_boothloader_bin, "wb") + position = 0 + while position < lengthbootloader: + byte = bootloader.read(1) + firmwareimage.write(byte) + position += 1 + position = 0 + while position < lengthfirmware: + byte = firmware.read(1) + firmwareimage.write(byte) + position += 1 + bootloader.close() + firmware.close() + firmwareimage.close() - firmware_with_boothloader_bin = target[0].dir.path + '/firmware_with_bootloader.bin' - if os.path.exists(firmware_with_boothloader_bin): - os.remove(firmware_with_boothloader_bin) - firmwareimage = open(firmware_with_boothloader_bin, "wb") - position = 0 - while position < lengthbootloader: - byte = bootloader.read(1) - firmwareimage.write(byte) - position += 1 - position = 0 - while position < lengthfirmware: - byte = firmware.read(1) - firmwareimage.write(byte) - position += 1 - bootloader.close() - firmware.close() - firmwareimage.close() + firmware_without_bootloader_bin = target[0].dir.path + '/firmware_for_sd_upload.bin' + if os.path.exists(firmware_without_bootloader_bin): + os.remove(firmware_without_bootloader_bin) + os.rename(target[0].path, firmware_without_bootloader_bin) + #os.rename(target[0].dir.path+'/firmware_with_bootloader.bin', target[0].dir.path+'/firmware.bin') - firmware_without_bootloader_bin = target[0].dir.path + '/firmware_for_sd_upload.bin' - if os.path.exists(firmware_without_bootloader_bin): - os.remove(firmware_without_bootloader_bin) - os.rename(target[0].path, firmware_without_bootloader_bin) - #os.rename(target[0].dir.path+'/firmware_with_bootloader.bin', target[0].dir.path+'/firmware.bin') - -marlin.add_post_action(addboot); + marlin.add_post_action(addboot); diff --git a/buildroot/share/PlatformIO/scripts/lerdge.py b/buildroot/share/PlatformIO/scripts/lerdge.py index 144ab64a9a235..505a935560a94 100644 --- a/buildroot/share/PlatformIO/scripts/lerdge.py +++ b/buildroot/share/PlatformIO/scripts/lerdge.py @@ -1,47 +1,49 @@ # -# buildroot/share/PlatformIO/scripts/lerdge.py +# lerdge.py # Customizations for Lerdge build environments: # env:LERDGEX env:LERDGEX_usb_flash_drive # env:LERDGES env:LERDGES_usb_flash_drive # env:LERDGEK env:LERDGEK_usb_flash_drive # -import os,marlin -Import("env") +import pioutil +if pioutil.is_pio_build(): + import os,marlin + Import("env") -from SCons.Script import DefaultEnvironment -board = DefaultEnvironment().BoardConfig() + from SCons.Script import DefaultEnvironment + board = DefaultEnvironment().BoardConfig() -def encryptByte(byte): - byte = 0xFF & ((byte << 6) | (byte >> 2)) - i = 0x58 + byte - j = 0x05 + byte + (i >> 8) - byte = (0xF8 & i) | (0x07 & j) - return byte + def encryptByte(byte): + byte = 0xFF & ((byte << 6) | (byte >> 2)) + i = 0x58 + byte + j = 0x05 + byte + (i >> 8) + byte = (0xF8 & i) | (0x07 & j) + return byte -def encrypt_file(input, output_file, file_length): - input_file = bytearray(input.read()) - for i in range(len(input_file)): - input_file[i] = encryptByte(input_file[i]) - output_file.write(input_file) + def encrypt_file(input, output_file, file_length): + input_file = bytearray(input.read()) + for i in range(len(input_file)): + input_file[i] = encryptByte(input_file[i]) + output_file.write(input_file) -# Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt -def encrypt(source, target, env): - fwpath = target[0].path - enname = board.get("build.encrypt") - print("Encrypting %s to %s" % (fwpath, enname)) - fwfile = open(fwpath, "rb") - enfile = open(target[0].dir.path + "/" + enname, "wb") - length = os.path.getsize(fwpath) + # Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt + def encrypt(source, target, env): + fwpath = target[0].path + enname = board.get("build.encrypt") + print("Encrypting %s to %s" % (fwpath, enname)) + fwfile = open(fwpath, "rb") + enfile = open(target[0].dir.path + "/" + enname, "wb") + length = os.path.getsize(fwpath) - encrypt_file(fwfile, enfile, length) + encrypt_file(fwfile, enfile, length) - fwfile.close() - enfile.close() - os.remove(fwpath) + fwfile.close() + enfile.close() + os.remove(fwpath) -if 'encrypt' in board.get("build").keys(): - if board.get("build.encrypt") != "": - marlin.add_post_action(encrypt) -else: - print("LERDGE builds require output file via board_build.encrypt = 'filename' parameter") - exit(1) + if 'encrypt' in board.get("build").keys(): + if board.get("build.encrypt") != "": + marlin.add_post_action(encrypt) + else: + print("LERDGE builds require output file via board_build.encrypt = 'filename' parameter") + exit(1) diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py index caa0c89749c1a..b8a6283cedf1b 100644 --- a/buildroot/share/PlatformIO/scripts/marlin.py +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -1,5 +1,5 @@ # -# buildroot/share/PlatformIO/scripts/marlin.py +# marlin.py # Helper module with some commonly-used functions # import os,shutil @@ -10,13 +10,13 @@ from os.path import join def copytree(src, dst, symlinks=False, ignore=None): - for item in os.listdir(src): - s = join(src, item) - d = join(dst, item) - if os.path.isdir(s): - shutil.copytree(s, d, symlinks, ignore) - else: - shutil.copy2(s, d) + for item in os.listdir(src): + s = join(src, item) + d = join(dst, item) + if os.path.isdir(s): + shutil.copytree(s, d, symlinks, ignore) + else: + shutil.copy2(s, d) def replace_define(field, value): for define in env['CPPDEFINES']: diff --git a/buildroot/share/PlatformIO/scripts/mks_robin.py b/buildroot/share/PlatformIO/scripts/mks_robin.py index 2dea7c615f798..7b423bedabc77 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin.py @@ -1,5 +1,5 @@ # -# buildroot/share/PlatformIO/scripts/mks_robin.py +# mks_robin.py # import robin robin.prepare("0x08007000", "mks_robin.ld", "Robin.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_e3.py b/buildroot/share/PlatformIO/scripts/mks_robin_e3.py index 6ddeccbf80f46..645230c625c2e 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_e3.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_e3.py @@ -1,5 +1,5 @@ # -# buildroot/share/PlatformIO/scripts/mks_robin_e3.py +# mks_robin_e3.py # import robin robin.prepare("0x08005000", "mks_robin_e3.ld", "Robin_e3.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py b/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py index 5eeb93c09663b..bb15cb5a70f2d 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_e3p.py @@ -1,5 +1,5 @@ # -# buildroot/share/PlatformIO/scripts/mks_robin_e3p.py +# mks_robin_e3p.py # import robin robin.prepare("0x08007000", "mks_robin_e3p.ld", "Robin_e3p.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_lite.py b/buildroot/share/PlatformIO/scripts/mks_robin_lite.py index c2018336fd1f9..123b043f7cfb3 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_lite.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_lite.py @@ -1,5 +1,5 @@ # -# buildroot/share/PlatformIO/scripts/mks_robin_lite.py +# mks_robin_lite.py # import robin robin.prepare("0x08005000", "mks_robin_lite.ld", "mksLite.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py b/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py index 42c8fb18b691a..092231eae81ff 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_lite3.py @@ -1,5 +1,5 @@ # -# buildroot/share/PlatformIO/scripts/mks_robin_lite3.py +# mks_robin_lite3.py # import robin robin.prepare("0x08005000", "mks_robin_lite.ld", "mksLite3.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_mini.py b/buildroot/share/PlatformIO/scripts/mks_robin_mini.py index b0d83886533ac..d1d175dd1c170 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_mini.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_mini.py @@ -1,5 +1,5 @@ # -# buildroot/share/PlatformIO/scripts/mks_robin_mini.py +# mks_robin_mini.py # import robin robin.prepare("0x08007000", "mks_robin_mini.ld", "Robin_mini.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_nano.py b/buildroot/share/PlatformIO/scripts/mks_robin_nano.py index 35e99830c4dfb..32d1af23662cb 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_nano.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_nano.py @@ -1,5 +1,5 @@ # -# buildroot/share/PlatformIO/scripts/mks_robin_nano.py +# mks_robin_nano.py # import robin robin.prepare("0x08007000", "mks_robin_nano.ld", "Robin_nano.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py b/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py index 4a5726ad5b98a..7e635bd6ecf7c 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py @@ -1,5 +1,5 @@ # -# buildroot/share/PlatformIO/scripts/mks_robin_nano35.py +# mks_robin_nano35.py # import robin robin.prepare("0x08007000", "mks_robin_nano.ld", "Robin_nano35.bin") diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_pro.py b/buildroot/share/PlatformIO/scripts/mks_robin_pro.py index 60e2482bb0308..54526aeaef57f 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_pro.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_pro.py @@ -1,5 +1,5 @@ # -# buildroot/share/PlatformIO/scripts/mks_robin_pro.py +# mks_robin_pro.py # import robin robin.prepare("0x08007000", "mks_robin_pro.ld", "Robin_pro.bin") diff --git a/buildroot/share/PlatformIO/scripts/offset_and_rename.py b/buildroot/share/PlatformIO/scripts/offset_and_rename.py index 9caed298e4348..00803b722efff 100644 --- a/buildroot/share/PlatformIO/scripts/offset_and_rename.py +++ b/buildroot/share/PlatformIO/scripts/offset_and_rename.py @@ -8,54 +8,56 @@ # # - For 'board_build.rename' add a post-action to rename the firmware file. # -import os,sys,marlin -Import("env") - -from SCons.Script import DefaultEnvironment -board = DefaultEnvironment().BoardConfig() - -board_keys = board.get("build").keys() - -# -# For build.offset define LD_FLASH_OFFSET, used by ldscript.ld -# -if 'offset' in board_keys: - LD_FLASH_OFFSET = board.get("build.offset") - marlin.relocate_vtab(LD_FLASH_OFFSET) - - # Flash size - maximum_flash_size = int(board.get("upload.maximum_size") / 1024) - marlin.replace_define('STM32_FLASH_SIZE', maximum_flash_size) - - # Get upload.maximum_ram_size (defined by /buildroot/share/PlatformIO/boards/VARIOUS.json) - maximum_ram_size = board.get("upload.maximum_ram_size") - - for i, flag in enumerate(env["LINKFLAGS"]): - if "-Wl,--defsym=LD_FLASH_OFFSET" in flag: - env["LINKFLAGS"][i] = "-Wl,--defsym=LD_FLASH_OFFSET=" + LD_FLASH_OFFSET - if "-Wl,--defsym=LD_MAX_DATA_SIZE" in flag: - env["LINKFLAGS"][i] = "-Wl,--defsym=LD_MAX_DATA_SIZE=" + str(maximum_ram_size - 40) - -# -# For build.encrypt rename and encode the firmware file. -# -if 'encrypt' in board_keys: - - # Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt - def encrypt(source, target, env): - marlin.encrypt_mks(source, target, env, board.get("build.encrypt")) - - if board.get("build.encrypt") != "": - marlin.add_post_action(encrypt) - -# -# For build.rename simply rename the firmware file. -# -if 'rename' in board_keys: - - def rename_target(source, target, env): - firmware = os.path.join(target[0].dir.path, board.get("build.rename")) - import shutil - shutil.copy(target[0].path, firmware) - - marlin.add_post_action(rename_target) +import pioutil +if pioutil.is_pio_build(): + import os,sys,marlin + Import("env") + + from SCons.Script import DefaultEnvironment + board = DefaultEnvironment().BoardConfig() + + board_keys = board.get("build").keys() + + # + # For build.offset define LD_FLASH_OFFSET, used by ldscript.ld + # + if 'offset' in board_keys: + LD_FLASH_OFFSET = board.get("build.offset") + marlin.relocate_vtab(LD_FLASH_OFFSET) + + # Flash size + maximum_flash_size = int(board.get("upload.maximum_size") / 1024) + marlin.replace_define('STM32_FLASH_SIZE', maximum_flash_size) + + # Get upload.maximum_ram_size (defined by /buildroot/share/PlatformIO/boards/VARIOUS.json) + maximum_ram_size = board.get("upload.maximum_ram_size") + + for i, flag in enumerate(env["LINKFLAGS"]): + if "-Wl,--defsym=LD_FLASH_OFFSET" in flag: + env["LINKFLAGS"][i] = "-Wl,--defsym=LD_FLASH_OFFSET=" + LD_FLASH_OFFSET + if "-Wl,--defsym=LD_MAX_DATA_SIZE" in flag: + env["LINKFLAGS"][i] = "-Wl,--defsym=LD_MAX_DATA_SIZE=" + str(maximum_ram_size - 40) + + # + # For build.encrypt rename and encode the firmware file. + # + if 'encrypt' in board_keys: + + # Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt + def encrypt(source, target, env): + marlin.encrypt_mks(source, target, env, board.get("build.encrypt")) + + if board.get("build.encrypt") != "": + marlin.add_post_action(encrypt) + + # + # For build.rename simply rename the firmware file. + # + if 'rename' in board_keys: + + def rename_target(source, target, env): + firmware = os.path.join(target[0].dir.path, board.get("build.rename")) + import shutil + shutil.copy(target[0].path, firmware) + + marlin.add_post_action(rename_target) diff --git a/buildroot/share/PlatformIO/scripts/openblt.py b/buildroot/share/PlatformIO/scripts/openblt.py index 6e71ca9eb8122..61b38a5e87f7c 100644 --- a/buildroot/share/PlatformIO/scripts/openblt.py +++ b/buildroot/share/PlatformIO/scripts/openblt.py @@ -1,18 +1,20 @@ # # Convert the ELF to an SREC file suitable for some bootloaders # -import os,sys -from os.path import join +import pioutil +if pioutil.is_pio_build(): + import os,sys + from os.path import join -Import("env") + Import("env") -board = env.BoardConfig() -board_keys = board.get("build").keys() -if 'encrypt' in board_keys: - env.AddPostAction( - join("$BUILD_DIR", "${PROGNAME}.bin"), - env.VerboseAction(" ".join([ - "$OBJCOPY", "-O", "srec", - "\"$BUILD_DIR/${PROGNAME}.elf\"", "\"" + join("$BUILD_DIR", board.get("build.encrypt")) + "\"" - ]), "Building $TARGET") - ) + board = env.BoardConfig() + board_keys = board.get("build").keys() + if 'encrypt' in board_keys: + env.AddPostAction( + join("$BUILD_DIR", "${PROGNAME}.bin"), + env.VerboseAction(" ".join([ + "$OBJCOPY", "-O", "srec", + "\"$BUILD_DIR/${PROGNAME}.elf\"", "\"" + join("$BUILD_DIR", board.get("build.encrypt")) + "\"" + ]), "Building $TARGET") + ) diff --git a/buildroot/share/PlatformIO/scripts/pioutil.py b/buildroot/share/PlatformIO/scripts/pioutil.py index f0c021fca73e3..b8c1e9cfca6ca 100644 --- a/buildroot/share/PlatformIO/scripts/pioutil.py +++ b/buildroot/share/PlatformIO/scripts/pioutil.py @@ -1,8 +1,8 @@ # -# buildroot/share/PlatformIO/scripts/pioutil.py +# pioutil.py # -# Detect that 'vscode init' is running -def is_vscode_init(): +# Make sure 'vscode init' is not the current command +def is_pio_build(): from SCons.Script import COMMAND_LINE_TARGETS - return "idedata" in COMMAND_LINE_TARGETS or "_idedata" in COMMAND_LINE_TARGETS + return "idedata" not in COMMAND_LINE_TARGETS and "_idedata" not in COMMAND_LINE_TARGETS diff --git a/buildroot/share/PlatformIO/scripts/preflight-checks.py b/buildroot/share/PlatformIO/scripts/preflight-checks.py index 0dab3e4b1fbdb..1837a7580d242 100644 --- a/buildroot/share/PlatformIO/scripts/preflight-checks.py +++ b/buildroot/share/PlatformIO/scripts/preflight-checks.py @@ -2,100 +2,99 @@ # preflight-checks.py # Check for common issues prior to compiling # -import os,re,sys,pioutil -Import("env") +import pioutil +if pioutil.is_pio_build(): -# Detect that 'vscode init' is running -if pioutil.is_vscode_init(): - env.Exit(0) + import os,re,sys + Import("env") -def get_envs_for_board(board): - with open(os.path.join("Marlin", "src", "pins", "pins.h"), "r") as file: + def get_envs_for_board(board): + with open(os.path.join("Marlin", "src", "pins", "pins.h"), "r") as file: - if sys.platform == 'win32': - envregex = r"(?:env|win):" - elif sys.platform == 'darwin': - envregex = r"(?:env|mac|uni):" - elif sys.platform == 'linux': - envregex = r"(?:env|lin|uni):" - else: - envregex = r"(?:env):" + if sys.platform == 'win32': + envregex = r"(?:env|win):" + elif sys.platform == 'darwin': + envregex = r"(?:env|mac|uni):" + elif sys.platform == 'linux': + envregex = r"(?:env|lin|uni):" + else: + envregex = r"(?:env):" - r = re.compile(r"if\s+MB\((.+)\)") - if board.startswith("BOARD_"): - board = board[6:] + r = re.compile(r"if\s+MB\((.+)\)") + if board.startswith("BOARD_"): + board = board[6:] - for line in file: - mbs = r.findall(line) - if mbs and board in re.split(r",\s*", mbs[0]): - line = file.readline() - found_envs = re.match(r"\s*#include .+" + envregex, line) - if found_envs: - envlist = re.findall(envregex + r"(\w+)", line) - return [ "env:"+s for s in envlist ] - return [] + for line in file: + mbs = r.findall(line) + if mbs and board in re.split(r",\s*", mbs[0]): + line = file.readline() + found_envs = re.match(r"\s*#include .+" + envregex, line) + if found_envs: + envlist = re.findall(envregex + r"(\w+)", line) + return [ "env:"+s for s in envlist ] + return [] -def check_envs(build_env, board_envs, config): - if build_env in board_envs: - return True - ext = config.get(build_env, 'extends', default=None) - if ext: - if isinstance(ext, str): - return check_envs(ext, board_envs, config) - elif isinstance(ext, list): - for ext_env in ext: - if check_envs(ext_env, board_envs, config): - return True - return False + def check_envs(build_env, board_envs, config): + if build_env in board_envs: + return True + ext = config.get(build_env, 'extends', default=None) + if ext: + if isinstance(ext, str): + return check_envs(ext, board_envs, config) + elif isinstance(ext, list): + for ext_env in ext: + if check_envs(ext_env, board_envs, config): + return True + return False -def sanity_check_target(): - # Sanity checks: - if 'PIOENV' not in env: - raise SystemExit("Error: PIOENV is not defined. This script is intended to be used with PlatformIO") + def sanity_check_target(): + # Sanity checks: + if 'PIOENV' not in env: + raise SystemExit("Error: PIOENV is not defined. This script is intended to be used with PlatformIO") - if 'MARLIN_FEATURES' not in env: - raise SystemExit("Error: this script should be used after common Marlin scripts") + if 'MARLIN_FEATURES' not in env: + raise SystemExit("Error: this script should be used after common Marlin scripts") - if 'MOTHERBOARD' not in env['MARLIN_FEATURES']: - raise SystemExit("Error: MOTHERBOARD is not defined in Configuration.h") + if 'MOTHERBOARD' not in env['MARLIN_FEATURES']: + raise SystemExit("Error: MOTHERBOARD is not defined in Configuration.h") - build_env = env['PIOENV'] - motherboard = env['MARLIN_FEATURES']['MOTHERBOARD'] - board_envs = get_envs_for_board(motherboard) - config = env.GetProjectConfig() - result = check_envs("env:"+build_env, board_envs, config) + build_env = env['PIOENV'] + motherboard = env['MARLIN_FEATURES']['MOTHERBOARD'] + board_envs = get_envs_for_board(motherboard) + config = env.GetProjectConfig() + 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" % \ - ( build_env, motherboard, ", ".join([ e[4:] for e in board_envs if e.startswith("env:") ]) ) - raise SystemExit(err) + if not result: + err = "Error: Build environment '%s' is incompatible with %s. Use one of these: %s" % \ + ( build_env, motherboard, ", ".join([ e[4:] for e in board_envs if e.startswith("env:") ]) ) + raise SystemExit(err) - # - # Check for Config files in two common incorrect places - # - for p in [ env['PROJECT_DIR'], os.path.join(env['PROJECT_DIR'], "config") ]: - for f in [ "Configuration.h", "Configuration_adv.h" ]: - if os.path.isfile(os.path.join(p, f)): - err = "ERROR: Config files found in directory %s. Please move them into the Marlin subfolder." % p - raise SystemExit(err) + # + # Check for Config files in two common incorrect places + # + for p in [ env['PROJECT_DIR'], os.path.join(env['PROJECT_DIR'], "config") ]: + for f in [ "Configuration.h", "Configuration_adv.h" ]: + if os.path.isfile(os.path.join(p, f)): + err = "ERROR: Config files found in directory %s. Please move them into the Marlin subfolder." % p + raise SystemExit(err) - # - # Give warnings on every build - # - warnfile = os.path.join(env['PROJECT_BUILD_DIR'], build_env, "src", "src", "inc", "Warnings.cpp.o") - if os.path.exists(warnfile): - os.remove(warnfile) + # + # Give warnings on every build + # + warnfile = os.path.join(env['PROJECT_BUILD_DIR'], build_env, "src", "src", "inc", "Warnings.cpp.o") + if os.path.exists(warnfile): + os.remove(warnfile) - # - # Check for old files indicating an entangled Marlin (mixing old and new code) - # - mixedin = [] - p = os.path.join(env['PROJECT_DIR'], "Marlin", "src", "lcd", "dogm") - for f in [ "ultralcd_DOGM.cpp", "ultralcd_DOGM.h" ]: - if os.path.isfile(os.path.join(p, f)): - mixedin += [ f ] - if mixedin: - err = "ERROR: Old files fell into your Marlin folder. Remove %s and try again" % ", ".join(mixedin) - raise SystemExit(err) + # + # Check for old files indicating an entangled Marlin (mixing old and new code) + # + mixedin = [] + p = os.path.join(env['PROJECT_DIR'], "Marlin", "src", "lcd", "dogm") + for f in [ "ultralcd_DOGM.cpp", "ultralcd_DOGM.h" ]: + if os.path.isfile(os.path.join(p, f)): + mixedin += [ f ] + if mixedin: + err = "ERROR: Old files fell into your Marlin folder. Remove %s and try again" % ", ".join(mixedin) + raise SystemExit(err) -sanity_check_target() + sanity_check_target() diff --git a/buildroot/share/PlatformIO/scripts/random-bin.py b/buildroot/share/PlatformIO/scripts/random-bin.py index c03b8634487a9..5a88906c30925 100644 --- a/buildroot/share/PlatformIO/scripts/random-bin.py +++ b/buildroot/share/PlatformIO/scripts/random-bin.py @@ -2,8 +2,8 @@ # random-bin.py # Set a unique firmware name based on current date and time # -Import("env") - -from datetime import datetime - -env['PROGNAME'] = datetime.now().strftime("firmware-%Y%m%d-%H%M%S") +import pioutil +if pioutil.is_pio_build(): + from datetime import datetime + Import("env") + env['PROGNAME'] = datetime.now().strftime("firmware-%Y%m%d-%H%M%S") diff --git a/buildroot/share/PlatformIO/scripts/robin.py b/buildroot/share/PlatformIO/scripts/robin.py index 50d0d92d2ff73..ffc9a43b90042 100644 --- a/buildroot/share/PlatformIO/scripts/robin.py +++ b/buildroot/share/PlatformIO/scripts/robin.py @@ -1,12 +1,14 @@ # -# buildroot/share/PlatformIO/scripts/robin.py +# robin.py # -import marlin # Apply customizations for a MKS Robin def prepare(address, ldname, fwname): - def encrypt(source, target, env): - marlin.encrypt_mks(source, target, env, fwname) - marlin.relocate_firmware(address) - marlin.custom_ld_script(ldname) - marlin.add_post_action(encrypt); + import pioutil + if pioutil.is_pio_build(): + import marlin + def encrypt(source, target, env): + marlin.encrypt_mks(source, target, env, fwname) + marlin.relocate_firmware(address) + marlin.custom_ld_script(ldname) + marlin.add_post_action(encrypt); diff --git a/buildroot/share/PlatformIO/scripts/simulator.py b/buildroot/share/PlatformIO/scripts/simulator.py index fb9d93ccebccb..c6a5277b92ade 100644 --- a/buildroot/share/PlatformIO/scripts/simulator.py +++ b/buildroot/share/PlatformIO/scripts/simulator.py @@ -1,52 +1,54 @@ # +# simulator.py # PlatformIO pre: script for simulator builds # +import pioutil +if pioutil.is_pio_build(): + # Get the environment thus far for the build + Import("env") -# Get the environment thus far for the build -Import("env") + #print(env.Dump()) -#print(env.Dump()) + # + # Give the binary a distinctive name + # -# -# Give the binary a distinctive name -# - -env['PROGNAME'] = "MarlinSimulator" + env['PROGNAME'] = "MarlinSimulator" -# -# If Xcode is installed add the path to its Frameworks folder, -# or if Mesa is installed try to use its GL/gl.h. -# + # + # If Xcode is installed add the path to its Frameworks folder, + # or if Mesa is installed try to use its GL/gl.h. + # -import sys -if sys.platform == 'darwin': + import sys + if sys.platform == 'darwin': - # - # Silence half of the ranlib warnings. (No equivalent for 'ARFLAGS') - # - env['RANLIBFLAGS'] += [ "-no_warning_for_no_symbols" ] + # + # Silence half of the ranlib warnings. (No equivalent for 'ARFLAGS') + # + env['RANLIBFLAGS'] += [ "-no_warning_for_no_symbols" ] - # Default paths for Xcode and a lucky GL/gl.h dropped by Mesa - xcode_path = "/Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX.sdk/System/Library/Frameworks" - mesa_path = "/opt/local/include/GL/gl.h" + # Default paths for Xcode and a lucky GL/gl.h dropped by Mesa + xcode_path = "/Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX.sdk/System/Library/Frameworks" + mesa_path = "/opt/local/include/GL/gl.h" - import os.path + import os.path - if os.path.exists(xcode_path): + if os.path.exists(xcode_path): - env['BUILD_FLAGS'] += [ "-F" + xcode_path ] - print("Using OpenGL framework headers from Xcode.app") + env['BUILD_FLAGS'] += [ "-F" + xcode_path ] + print("Using OpenGL framework headers from Xcode.app") - elif os.path.exists(mesa_path): + elif os.path.exists(mesa_path): - env['BUILD_FLAGS'] += [ '-D__MESA__' ] - print("Using OpenGL header from", mesa_path) + env['BUILD_FLAGS'] += [ '-D__MESA__' ] + print("Using OpenGL header from", mesa_path) - else: + else: - print("\n\nNo OpenGL headers found. Install Xcode for matching headers, or use 'sudo port install mesa' to get a GL/gl.h.\n\n") + print("\n\nNo OpenGL headers found. Install Xcode for matching headers, or use 'sudo port install mesa' to get a GL/gl.h.\n\n") - # Break out of the PIO build immediately - sys.exit(1) + # Break out of the PIO build immediately + sys.exit(1) -env.AddCustomTarget("upload", "$BUILD_DIR/${PROGNAME}", "$BUILD_DIR/${PROGNAME}") + env.AddCustomTarget("upload", "$BUILD_DIR/${PROGNAME}", "$BUILD_DIR/${PROGNAME}") diff --git a/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py b/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py index c3779289e0f3d..033803009e520 100644 --- a/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py +++ b/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py @@ -1,59 +1,61 @@ # # stm32_serialbuffer.py # -Import("env") - -# Marlin uses the `RX_BUFFER_SIZE` \ `TX_BUFFER_SIZE` options to -# configure buffer sizes for receiving \ transmitting serial data. -# Stm32duino uses another set of defines for the same purpose, so this -# script gets the values from the configuration and uses them to define -# `SERIAL_RX_BUFFER_SIZE` and `SERIAL_TX_BUFFER_SIZE` as global build -# flags so they are available for use by the platform. -# -# The script will set the value as the default one (64 bytes) -# or the user-configured one, whichever is higher. -# -# Marlin's default buffer sizes are 128 for RX and 32 for TX. -# The highest value is taken (128/64). -# -# If MF_*_BUFFER_SIZE, SERIAL_*_BUFFER_SIZE, USART_*_BUF_SIZE, are -# defined, the first of these values will be used as the minimum. -build_flags = env.ParseFlags(env.get('BUILD_FLAGS'))["CPPDEFINES"] -mf = env["MARLIN_FEATURES"] - -# Get a build flag's value or None -def getBuildFlagValue(name): - for flag in build_flags: - if isinstance(flag, list) and flag[0] == name: - return flag[1] - - return None - -# Get an overriding buffer size for RX or TX from the build flags -def getInternalSize(side): - return getBuildFlagValue(f"MF_{side}_BUFFER_SIZE") or \ - getBuildFlagValue(f"SERIAL_{side}_BUFFER_SIZE") or \ - getBuildFlagValue(f"USART_{side}_BUF_SIZE") - -# Get the largest defined buffer size for RX or TX -def getBufferSize(side, default): - # Get a build flag value or fall back to the given default - internal = int(getInternalSize(side) or default) - flag = side + "_BUFFER_SIZE" - # Return the largest value - return max(int(mf[flag]), internal) if flag in mf else internal - -# Add a build flag if it's not already defined -def tryAddFlag(name, value): - if getBuildFlagValue(name) is None: - env.Append(BUILD_FLAGS=[f"-D{name}={value}"]) - -# Get the largest defined buffer sizes for RX or TX, using defaults for undefined -rxBuf = getBufferSize("RX", 128) -txBuf = getBufferSize("TX", 64) - -# Provide serial buffer sizes to the stm32duino platform -tryAddFlag("SERIAL_RX_BUFFER_SIZE", rxBuf) -tryAddFlag("SERIAL_TX_BUFFER_SIZE", txBuf) -tryAddFlag("USART_RX_BUF_SIZE", rxBuf) -tryAddFlag("USART_TX_BUF_SIZE", txBuf) +import pioutil +if pioutil.is_pio_build(): + Import("env") + + # Get a build flag's value or None + def getBuildFlagValue(name): + for flag in build_flags: + if isinstance(flag, list) and flag[0] == name: + return flag[1] + + return None + + # Get an overriding buffer size for RX or TX from the build flags + def getInternalSize(side): + return getBuildFlagValue(f"MF_{side}_BUFFER_SIZE") or \ + getBuildFlagValue(f"SERIAL_{side}_BUFFER_SIZE") or \ + getBuildFlagValue(f"USART_{side}_BUF_SIZE") + + # Get the largest defined buffer size for RX or TX + def getBufferSize(side, default): + # Get a build flag value or fall back to the given default + internal = int(getInternalSize(side) or default) + flag = side + "_BUFFER_SIZE" + # Return the largest value + return max(int(mf[flag]), internal) if flag in mf else internal + + # Add a build flag if it's not already defined + def tryAddFlag(name, value): + if getBuildFlagValue(name) is None: + env.Append(BUILD_FLAGS=[f"-D{name}={value}"]) + + # Marlin uses the `RX_BUFFER_SIZE` \ `TX_BUFFER_SIZE` options to + # configure buffer sizes for receiving \ transmitting serial data. + # Stm32duino uses another set of defines for the same purpose, so this + # script gets the values from the configuration and uses them to define + # `SERIAL_RX_BUFFER_SIZE` and `SERIAL_TX_BUFFER_SIZE` as global build + # flags so they are available for use by the platform. + # + # The script will set the value as the default one (64 bytes) + # or the user-configured one, whichever is higher. + # + # Marlin's default buffer sizes are 128 for RX and 32 for TX. + # The highest value is taken (128/64). + # + # If MF_*_BUFFER_SIZE, SERIAL_*_BUFFER_SIZE, USART_*_BUF_SIZE, are + # defined, the first of these values will be used as the minimum. + build_flags = env.ParseFlags(env.get('BUILD_FLAGS'))["CPPDEFINES"] + mf = env["MARLIN_FEATURES"] + + # Get the largest defined buffer sizes for RX or TX, using defaults for undefined + rxBuf = getBufferSize("RX", 128) + txBuf = getBufferSize("TX", 64) + + # Provide serial buffer sizes to the stm32duino platform + tryAddFlag("SERIAL_RX_BUFFER_SIZE", rxBuf) + tryAddFlag("SERIAL_TX_BUFFER_SIZE", txBuf) + tryAddFlag("USART_RX_BUF_SIZE", rxBuf) + tryAddFlag("USART_TX_BUF_SIZE", txBuf) diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index e0b4ad711a375..969bb815dacdd 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -326,7 +326,6 @@ platform = ${common_stm32f1.platform} extends = common_stm32f1 board = marlin_CHITU_F103 extra_scripts = ${common_stm32f1.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/common-dependencies.py pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py buildroot/share/PlatformIO/scripts/chitu_crypt.py build_flags = ${common_stm32f1.build_flags} From 7b792014703e778d8fc0b1760747d50ab8f340d1 Mon Sep 17 00:00:00 2001 From: BigTreeTech <38851044+bigtreetech@users.noreply.github.com> Date: Thu, 4 Nov 2021 18:54:38 +0800 Subject: [PATCH 024/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Octopus-Pro=20Max3?= =?UTF-8?q?1865=20/=20SPI=20(#23072)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../src/pins/stm32f4/pins_BTT_OCTOPUS_PRO_V1_0.h | 1 + .../src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 14 +++++++------- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_PRO_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_PRO_V1_0.h index a93ed68201b02..fd367e87c04fc 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_PRO_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_PRO_V1_0.h @@ -32,6 +32,7 @@ #define TEMP_0_MISO_PIN PA6 #define TEMP_0_MOSI_PIN PA7 #define SOFTWARE_SPI // Max31865 and LCD SD share a set of SPIs, Set SD to softwareSPI for Max31865 + #define FORCE_SOFT_SPI #else #define TEMP_0_PIN PF4 // TH0 #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 6dc90bf910ef9..efeff04f256af 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -168,13 +168,6 @@ #define POWER_LOSS_PIN PC0 // PWRDET #endif -// -// NeoPixel LED -// -#ifndef NEOPIXEL_PIN - #define NEOPIXEL_PIN PB0 -#endif - // // Steppers // @@ -524,6 +517,13 @@ #define BTN_ENC EXP1_09_PIN #endif +// +// NeoPixel LED +// +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PB0 +#endif + // // WIFI // From a9dc737624cf45bceff1866ce4807bb2cc36ac44 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Thu, 4 Nov 2021 18:04:04 +0100 Subject: [PATCH 025/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20TFT=20backlight=20?= =?UTF-8?q?[STM32]=20(#23062)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/fast_pwm.cpp | 4 +++- Marlin/src/HAL/STM32F1/fast_pwm.cpp | 1 + Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 4 +++- Marlin/src/lcd/tft/ui_common.cpp | 4 +++- Marlin/src/lcd/tft_io/tft_io.cpp | 3 +-- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 14 +++++++++++--- 6 files changed, 22 insertions(+), 8 deletions(-) diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index d4d695b969b5f..4d450374d32ba 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -28,11 +28,13 @@ #include "timers.h" void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { + if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer + PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); + uint16_t adj_val = Instance->ARR * v / v_size; if (invert) adj_val = Instance->ARR - adj_val; - switch (get_pwm_channel(pin_name)) { case TIM_CHANNEL_1: LL_TIM_OC_SetCompareCH1(Instance, adj_val); break; case TIM_CHANNEL_2: LL_TIM_OC_SetCompareCH2(Instance, adj_val); break; diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp index 6a9d7e8a19479..5171c11545f5b 100644 --- a/Marlin/src/HAL/STM32F1/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp @@ -28,6 +28,7 @@ #include "timers.h" void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { + if (!PWM_PIN(pin)) return; timer_dev *timer = PIN_MAP[pin].timer_device; uint16_t max_val = timer->regs.bas->ARR * v / v_size; if (invert) max_val = v_size - max_val; diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index f339cad70614a..59c74148adef3 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -339,12 +339,14 @@ void MarlinUI::draw_kill_screen() { void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop #if HAS_LCD_BRIGHTNESS + void MarlinUI::_set_brightness() { #if PIN_EXISTS(TFT_BACKLIGHT) if (PWM_PIN(TFT_BACKLIGHT_PIN)) - set_pwm_duty(pin_t(TFT_BACKLIGHT_PIN), brightness); + analogWrite(pin_t(TFT_BACKLIGHT_PIN), backlight ? brightness : 0); #endif } + #endif #if HAS_LCD_MENU diff --git a/Marlin/src/lcd/tft/ui_common.cpp b/Marlin/src/lcd/tft/ui_common.cpp index 85ae21e867fa0..acc91f51fa832 100644 --- a/Marlin/src/lcd/tft/ui_common.cpp +++ b/Marlin/src/lcd/tft/ui_common.cpp @@ -210,12 +210,14 @@ void MarlinUI::clear_lcd() { } #if HAS_LCD_BRIGHTNESS + void MarlinUI::_set_brightness() { #if PIN_EXISTS(TFT_BACKLIGHT) if (PWM_PIN(TFT_BACKLIGHT_PIN)) - set_pwm_duty(pin_t(TFT_BACKLIGHT_PIN), brightness); + analogWrite(pin_t(TFT_BACKLIGHT_PIN), backlight ? brightness : 0); #endif } + #endif #if ENABLED(TOUCH_SCREEN_CALIBRATION) diff --git a/Marlin/src/lcd/tft_io/tft_io.cpp b/Marlin/src/lcd/tft_io/tft_io.cpp index 6ec3bedcdff67..acb78c3e6e9fa 100644 --- a/Marlin/src/lcd/tft_io/tft_io.cpp +++ b/Marlin/src/lcd/tft_io/tft_io.cpp @@ -152,8 +152,7 @@ if (lcd_id != 0xFFFFFFFF) return; #endif #if PIN_EXISTS(TFT_BACKLIGHT) && ENABLED(DELAYED_BACKLIGHT_INIT) - WRITE(TFT_BACKLIGHT_PIN, HIGH); - TERN_(HAS_LCD_BRIGHTNESS, ui._set_brightness()); + TERN(HAS_LCD_BRIGHTNESS, ui._set_brightness(), WRITE(TFT_BACKLIGHT_PIN, HIGH)); #endif } diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index 7585a6e289515..3a8019a27e9c6 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -89,9 +89,17 @@ #define HEATER_BED_PIN PA8 // pin 67 (Hot Bed Mosfet) #define FAN_PIN PA15 // pin 77 (4cm Fan) -#define FAN_SOFT_PWM // Required to avoid issues with heating or STLink -#define FAN_MIN_PWM 35 // Fan will not start in 1-30 range -#define FAN_MAX_PWM 255 +#ifdef MAPLE_STM32F1 + #define FAN_SOFT_PWM // Required to avoid issues with heating or STLink + #define FAN_MIN_PWM 35 // Fan will not start in 1-30 range + #define FAN_MAX_PWM 255 +#else + #define FAST_PWM_FAN // STM32 Variant allow TIMER2 Hardware PWM + #define FAST_PWM_FAN_FREQUENCY 31400 // This frequency allow a good range, fan starts at 3%, half noise at 50% + #define NEEDS_HARDWARE_PWM 1 + #define FAN_MIN_PWM 5 + #define FAN_MAX_PWM 255 +#endif //#define BEEPER_PIN PD13 // pin 60 (Servo PWM output 5V/GND on Board V0G+) made for BL-Touch sensor // Can drive a PC Buzzer, if connected between PWM and 5V pins From f53d627750ab0cf377ea1738bdcf792f2ef37de9 Mon Sep 17 00:00:00 2001 From: Skruppy Date: Thu, 4 Nov 2021 18:11:57 +0100 Subject: [PATCH 026/273] =?UTF-8?q?=F0=9F=90=9B=20Prevent=20AVR=20watchdog?= =?UTF-8?q?pile=20(#23075)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 3 +++ Marlin/src/HAL/AVR/HAL.cpp | 21 ++++++++++++++++++++- Marlin/src/HAL/AVR/HAL.h | 6 +++--- Marlin/src/inc/SanityCheck.h | 5 +++++ 4 files changed, 31 insertions(+), 4 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 934ceceafd20e..fc495a6ea6327 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -4224,3 +4224,6 @@ */ //#define SOFT_RESET_VIA_SERIAL // 'KILL' and '^X' commands will soft-reset the controller //#define SOFT_RESET_ON_KILL // Use a digital button to soft-reset the controller after KILL + +// Report uncleaned reset reason from register r2 instead of MCUSR. Supported by Optiboot on AVR. +//#define OPTIBOOT_RESET_REASON diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index 708583b262a62..d7bf2a6f6fbb8 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -35,12 +35,31 @@ // Public Variables // ------------------------ -//uint8_t MCUSR; +// Don't initialize/override variable (which would happen in .init4) +uint8_t reset_reason __attribute__((section(".noinit"))); // ------------------------ // Public functions // ------------------------ +__attribute__((naked)) // Don't output function pro- and epilogue +__attribute__((used)) // Output the function, even if "not used" +__attribute__((section(".init3"))) // Put in an early user definable section +void HAL_save_reset_reason() { + #if ENABLED(OPTIBOOT_RESET_REASON) + __asm__ __volatile__( + A("STS %0, r2") + : "=m"(reset_reason) + ); + #else + reset_reason = MCUSR; + #endif + + // Clear within 16ms since WDRF bit enables a 16ms watchdog timer -> Boot loop + MCUSR = 0; + wdt_disable(); +} + void HAL_init() { // Init Servo Pins #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index ad1f47a4e685e..2217f239d64ea 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -91,7 +91,7 @@ typedef int8_t pin_t; // Public Variables // ------------------------ -//extern uint8_t MCUSR; +extern uint8_t reset_reason; // Serial ports #ifdef USBCON @@ -152,8 +152,8 @@ void HAL_init(); //void _delay_ms(const int delay); -inline void HAL_clear_reset_source() { MCUSR = 0; } -inline uint8_t HAL_get_reset_source() { return MCUSR; } +inline void HAL_clear_reset_source() { } +inline uint8_t HAL_get_reset_source() { return reset_reason; } void HAL_reboot(); diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index b4eaf242b7073..fbdda2c127585 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2489,6 +2489,11 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "An encoder button is required or SOFT_RESET_ON_KILL will reset the printer without notice!" #endif +// Reset reason for AVR +#if ENABLED(OPTIBOOT_RESET_REASON) && !defined(__AVR__) + #error "OPTIBOOT_RESET_REASON only applies to AVR." +#endif + /** * I2C bus */ From f6147e038bbd4b4b96c8c188107b9e7d4f02d534 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 4 Nov 2021 12:18:23 -0500 Subject: [PATCH 027/273] =?UTF-8?q?=F0=9F=8D=BB=20Get/clear=20reset=20sour?= =?UTF-8?q?ce=20earlier?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #23075 --- Marlin/src/MarlinCore.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index eb57835f969d0..5e8881d1c6477 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1104,6 +1104,10 @@ void setup() { tmc_standby_setup(); // TMC Low Power Standby pins must be set early or they're not usable + // Check startup - does nothing if bootloader sets MCUSR to 0 + const byte mcu = HAL_get_reset_source(); + HAL_clear_reset_source(); + #if ENABLED(MARLIN_DEV_MODE) auto log_current_ms = [&](PGM_P const msg) { SERIAL_ECHO_START(); @@ -1232,15 +1236,14 @@ void setup() { SETUP_RUN(esp_wifi_init()); - // Check startup - does nothing if bootloader sets MCUSR to 0 - const byte mcu = HAL_get_reset_source(); + // Report Reset Reason if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP); if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET); if (mcu & RST_BROWN_OUT) SERIAL_ECHOLNPGM(STR_BROWNOUT_RESET); if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET); if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); - HAL_clear_reset_source(); + // Identify myself as Marlin x.x.x SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION); #if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR) SERIAL_ECHO_MSG( From 3e8cdef36b42d4cae1efc8fe3272497827dcc440 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 5 Nov 2021 01:00:14 +0000 Subject: [PATCH 028/273] [cron] Bump distribution date (2021-11-05) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e562730ae3f6e..b94659a0447c9 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 "2021-11-04" +//#define STRING_DISTRIBUTION_DATE "2021-11-05" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index f695d0a1b24a7..115eb4bbd2c09 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 "2021-11-04" + #define STRING_DISTRIBUTION_DATE "2021-11-05" #endif /** From f5284715fb7c35a5ba9caf98f45f533db709eeb4 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 6 Nov 2021 00:58:50 +0000 Subject: [PATCH 029/273] [cron] Bump distribution date (2021-11-06) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index b94659a0447c9..c3618ba586429 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 "2021-11-05" +//#define STRING_DISTRIBUTION_DATE "2021-11-06" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 115eb4bbd2c09..670be92f4ba7e 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 "2021-11-05" + #define STRING_DISTRIBUTION_DATE "2021-11-06" #endif /** From dfdffca2bddb2c7301b6befe5d453da5b84dc16f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 7 Nov 2021 01:06:43 +0000 Subject: [PATCH 030/273] [cron] Bump distribution date (2021-11-07) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c3618ba586429..ce8acbbc3e2c3 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 "2021-11-06" +//#define STRING_DISTRIBUTION_DATE "2021-11-07" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 670be92f4ba7e..7626b58e3eb3e 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 "2021-11-06" + #define STRING_DISTRIBUTION_DATE "2021-11-07" #endif /** From c07aa875bc8c285adf7f967df656f6bf8a13bf92 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sun, 7 Nov 2021 15:27:53 +1300 Subject: [PATCH 031/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20DGUS=20Reloaded=20?= =?UTF-8?q?status=20message=20(#23090)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp index 9bae2b95d3037..17e7a3844592b 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp @@ -409,7 +409,7 @@ void DGUSScreenHandler::SetStatusMessage(const char* msg, const millis_t duratio } void DGUSScreenHandler::SetStatusMessage(FSTR_P const fmsg, const millis_t duration) { - dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Status, FTOP(msg), DGUS_STATUS_LEN, false, true); + dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Status, FTOP(fmsg), DGUS_STATUS_LEN, false, true); status_expire = (duration > 0 ? ExtUI::safe_millis() + duration : 0); } From 30a69f76a3dc9deaef6974d18107d7f759502092 Mon Sep 17 00:00:00 2001 From: dwzg <50058606+dwzg@users.noreply.github.com> Date: Sun, 7 Nov 2021 04:48:00 +0100 Subject: [PATCH 032/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20JyersUI=20scrollin?= =?UTF-8?q?g=20filename,=20etc.=20(#23082)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 50 +++++++++++++++------------- 1 file changed, 26 insertions(+), 24 deletions(-) diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 80ef88d0b214b..4c838a2e21432 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -678,31 +678,31 @@ void CrealityDWINClass::Draw_Print_Filename(const bool reset/*=false*/) { static uint8_t namescrl = 0; if (reset) namescrl = 0; if (process == Print) { - size_t len = strlen(filename); - int8_t pos = len; - if (pos > 30) { - pos -= namescrl; - len = _MIN(pos, 30); - char dispname[len + 1]; + constexpr int8_t maxlen = 30; + char *outstr = filename; + size_t slen = strlen(filename); + int8_t outlen = slen; + if (slen > maxlen) { + char dispname[maxlen + 1]; + int8_t pos = slen - namescrl, len = maxlen; if (pos >= 0) { + NOMORE(len, pos); LOOP_L_N(i, len) dispname[i] = filename[i + namescrl]; } else { - LOOP_L_N(i, 30 + pos) dispname[i] = ' '; - LOOP_S_L_N(i, 30 + pos, 30) dispname[i] = filename[i - (30 + pos)]; + const int8_t mp = maxlen + pos; + LOOP_L_N(i, mp) dispname[i] = ' '; + LOOP_S_L_N(i, mp, maxlen) dispname[i] = filename[i - mp]; + if (mp <= 0) namescrl = 0; } dispname[len] = '\0'; - DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 50, DWIN_WIDTH - 8, 80); - const int8_t npos = (DWIN_WIDTH - 30 * MENU_CHR_W) / 2; - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, npos, 60, dispname); - if (-pos >= 30) namescrl = 0; + outstr = dispname; + outlen = maxlen; namescrl++; } - else { - DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 50, DWIN_WIDTH - 8, 80); - const int8_t npos = (DWIN_WIDTH - strlen(filename) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, npos, 60, filename); - } + DWIN_Draw_Rectangle(1, Color_Bg_Black, 8, 50, DWIN_WIDTH - 8, 80); + const int8_t npos = (DWIN_WIDTH - outlen * MENU_CHR_W) / 2; + DWIN_Draw_String(false, DWIN_FONT_MENU, Color_White, Color_Bg_Black, npos, 60, outstr); } } @@ -4702,7 +4702,7 @@ void CrealityDWINClass::Update_Status(const char * const text) { char header[4]; LOOP_L_N(i, 3) header[i] = text[i]; header[3] = '\0'; - if (strcmp_P(header,"") == 0) { + if (strcmp_P(header, PSTR("")) == 0) { LOOP_L_N(i, _MIN((size_t)LONG_FILENAME_LENGTH, strlen(text))) filename[i] = text[i + 3]; filename[_MIN((size_t)LONG_FILENAME_LENGTH - 1, strlen(text))] = '\0'; Draw_Print_Filename(true); @@ -4798,22 +4798,23 @@ void CrealityDWINClass::State_Update() { } void CrealityDWINClass::Screen_Update() { + const millis_t ms = millis(); static millis_t scrltime = 0; - if (ELAPSED(millis(), scrltime)) { - scrltime = millis() + 200; + if (ELAPSED(ms, scrltime)) { + scrltime = ms + 200; Update_Status_Bar(); if (process == Print) Draw_Print_Filename(); } static millis_t statustime = 0; - if (ELAPSED(millis(), statustime)) { - statustime = millis() + 500; + if (ELAPSED(ms, statustime)) { + statustime = ms + 500; Draw_Status_Area(); } static millis_t printtime = 0; - if (ELAPSED(millis(), printtime)) { - printtime = millis() + 1000; + if (ELAPSED(ms, printtime)) { + printtime = ms + 1000; if (process == Print) { Draw_Print_ProgressBar(); Draw_Print_ProgressElapsed(); @@ -5000,6 +5001,7 @@ void MarlinUI::init() { void MarlinUI::pause_show_message(const PauseMessage message, const PauseMode mode/*=PAUSE_MODE_SAME*/, const uint8_t extruder/*=active_extruder*/) { switch (message) { case PAUSE_MESSAGE_INSERT: CrealityDWIN.Confirm_Handler(FilInsert); break; + case PAUSE_MESSAGE_PURGE: case PAUSE_MESSAGE_OPTION: CrealityDWIN.Popup_Handler(PurgeMore); break; case PAUSE_MESSAGE_HEAT: CrealityDWIN.Confirm_Handler(HeaterTime); break; case PAUSE_MESSAGE_WAITING: CrealityDWIN.Draw_Print_Screen(); break; From 27220f09440e90ed490087273a2357b84a41663c Mon Sep 17 00:00:00 2001 From: Jin <3448324+jinhong-@users.noreply.github.com> Date: Sun, 7 Nov 2021 11:53:36 +0800 Subject: [PATCH 033/273] =?UTF-8?q?=F0=9F=8D=BB=20Preliminary=20fix=20for?= =?UTF-8?q?=20Max31865=20SPI=20(#22682)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/HAL/shared/Delay.h | 15 +++- Marlin/src/HAL/shared/Marduino.h | 2 +- Marlin/src/libs/MAX31865.cpp | 125 +++++++++++++++---------------- Marlin/src/libs/MAX31865.h | 11 ++- buildroot/tests/LPC1769 | 3 +- buildroot/tests/teensy41 | 5 +- 6 files changed, 90 insertions(+), 71 deletions(-) diff --git a/Marlin/src/HAL/shared/Delay.h b/Marlin/src/HAL/shared/Delay.h index 04df35d88d6a6..df07881f01d90 100644 --- a/Marlin/src/HAL/shared/Delay.h +++ b/Marlin/src/HAL/shared/Delay.h @@ -92,6 +92,12 @@ void calibrate_delay_loop(); #define DELAY_CYCLES(X) do { SmartDelay _smrtdly_X(X); } while(0) + #if GCC_VERSION <= 70000 + #define DELAY_CYCLES_VAR(X) DelayCycleFnc(X) + #else + #define DELAY_CYCLES_VAR DELAY_CYCLES + #endif + // For delay in microseconds, no smart delay selection is required, directly call the delay function // Teensy compiler is too old and does not accept smart delay compile-time / run-time selection correctly #define DELAY_US(x) DelayCycleFnc((x) * ((F_CPU) / 1000000UL)) @@ -200,9 +206,12 @@ void calibrate_delay_loop(); #endif #if ENABLED(DELAY_NS_ROUND_DOWN) - #define DELAY_NS(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL) / 1000UL) // floor + #define _NS_TO_CYCLES(x) ( (x) * ((F_CPU) / 1000000UL) / 1000UL) // floor #elif ENABLED(DELAY_NS_ROUND_CLOSEST) - #define DELAY_NS(x) DELAY_CYCLES(((x) * ((F_CPU) / 1000000UL) + 500) / 1000UL) // round + #define _NS_TO_CYCLES(x) (((x) * ((F_CPU) / 1000000UL) + 500) / 1000UL) // round #else - #define DELAY_NS(x) DELAY_CYCLES(((x) * ((F_CPU) / 1000000UL) + 999) / 1000UL) // "ceil" + #define _NS_TO_CYCLES(x) (((x) * ((F_CPU) / 1000000UL) + 999) / 1000UL) // "ceil" #endif + +#define DELAY_NS(x) DELAY_CYCLES(_NS_TO_CYCLES(x)) +#define DELAY_NS_VAR(x) DELAY_CYCLES_VAR(_NS_TO_CYCLES(x)) diff --git a/Marlin/src/HAL/shared/Marduino.h b/Marlin/src/HAL/shared/Marduino.h index 3b5a68a373201..0e2a021a3c4e9 100644 --- a/Marlin/src/HAL/shared/Marduino.h +++ b/Marlin/src/HAL/shared/Marduino.h @@ -39,7 +39,7 @@ #define DISABLED(V...) DO(DIS,&&,V) #undef _BV -#define _BV(b) (1UL << (b)) +#define _BV(b) (1 << (b)) #ifndef SBI #define SBI(A,B) (A |= _BV(B)) #endif diff --git a/Marlin/src/libs/MAX31865.cpp b/Marlin/src/libs/MAX31865.cpp index df0702b9fb58e..94048af2089cd 100644 --- a/Marlin/src/libs/MAX31865.cpp +++ b/Marlin/src/libs/MAX31865.cpp @@ -48,20 +48,17 @@ #if HAS_MAX31865 && !USE_ADAFRUIT_MAX31865 -//#include // TODO: switch to SPIclass/SoftSPI #include "MAX31865.h" +#ifdef TARGET_LPC1768 + #include +#endif + // The maximum speed the MAX31865 can do is 5 MHz SPISettings MAX31865::spiConfig = SPISettings( - #if defined(TARGET_LPC1768) - SPI_QUARTER_SPEED - #elif defined(ARDUINO_ARCH_STM32) - SPI_CLOCK_DIV4 - #else - 500000 - #endif - , MSBFIRST - , SPI_MODE_1 // CPOL0 CPHA1 + TERN(TARGET_LPC1768, SPI_QUARTER_SPEED, TERN(ARDUINO_ARCH_STM32, SPI_CLOCK_DIV4, 500000)), + MSBFIRST, + SPI_MODE1 // CPOL0 CPHA1 ); #ifndef LARGE_PINMAP @@ -93,7 +90,7 @@ SPISettings MAX31865::spiConfig = SPISettings( _sclk = _miso = _mosi = -1; } -#else +#else // LARGE_PINMAP /** * Create the interface object using software (bitbang) SPI for PIN values @@ -106,9 +103,7 @@ SPISettings MAX31865::spiConfig = SPISettings( * @param spi_clk the SPI clock pin to use * @param pin_mapping set to 1 for positive pin values */ - MAX31865::MAX31865(uint32_t spi_cs, uint32_t spi_mosi, - uint32_t spi_miso, uint32_t spi_clk, - uint8_t pin_mapping) { + MAX31865::MAX31865(uint32_t spi_cs, uint32_t spi_mosi, uint32_t spi_miso, uint32_t spi_clk, uint8_t pin_mapping) { _cs = spi_cs; _mosi = spi_mosi; _miso = spi_miso; @@ -130,14 +125,12 @@ SPISettings MAX31865::spiConfig = SPISettings( #endif // LARGE_PINMAP - /** * * Instance & Class methods * */ - /** * Initialize the SPI interface and set the number of RTD wires used * @@ -152,22 +145,13 @@ void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { OUT_WRITE(_cs, HIGH); if (_sclk != TERN(LARGE_PINMAP, -1UL, -1)) { - // Define pin modes for Software SPI - #ifdef MAX31865_DEBUG - SERIAL_ECHOLN("Initializing MAX31865 Software SPI"); - #endif - - OUT_WRITE(_sclk, LOW); - SET_OUTPUT(_mosi); - SET_INPUT(_miso); + softSpiBegin(SPI_QUARTER_SPEED); // Define pin modes for Software SPI } else { - // Start and configure hardware SPI #ifdef MAX31865_DEBUG - SERIAL_ECHOLN("Initializing MAX31865 Hardware SPI"); + SERIAL_ECHOLNPGM("Initializing MAX31865 Hardware SPI"); #endif - - SPI.begin(); + SPI.begin(); // Start and configure hardware SPI } setWires(wires); @@ -176,25 +160,15 @@ void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { clearFault(); #ifdef MAX31865_DEBUG_SPI - #ifndef LARGE_PINMAP - SERIAL_ECHOLNPGM( - "Regular begin call with _cs: ", _cs, - " _miso: ", _miso, - " _sclk: ", _sclk, - " _mosi: ", _mosi - ); - #else - SERIAL_ECHOLNPGM( - "LARGE_PINMAP begin call with _cs: ", _cs, - " _miso: ", _miso, - " _sclk: ", _sclk, - " _mosi: ", _mosi - ); - #endif // LARGE_PINMAP - - SERIAL_ECHOLNPGM("config: ", readRegister8(MAX31856_CONFIG_REG)); - SERIAL_EOL(); - #endif // MAX31865_DEBUG_SPI + SERIAL_ECHOLNPGM( + TERN(LARGE_PINMAP, "LARGE_PINMAP", "Regular") + " begin call with _cs: ", _cs, + " _miso: ", _miso, + " _sclk: ", _sclk, + " _mosi: ", _mosi, + " config: ", readRegister8(MAX31856_CONFIG_REG) + ); + #endif } /** @@ -371,7 +345,6 @@ float MAX31865::temperature(float Rrtd) { // private: // - /** * Set a value in the configuration register. * @@ -432,10 +405,15 @@ void MAX31865::readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n) { WRITE(_sclk, LOW); WRITE(_cs, LOW); - spixfer(addr); + + #ifdef TARGET_LPC1768 + DELAY_CYCLES(_spi_speed); + #endif + + spiTransfer(addr); while (n--) { - buffer[0] = spixfer(0xFF); + buffer[0] = spiTransfer(0xFF); #ifdef MAX31865_DEBUG_SPI SERIAL_ECHOLNPGM("buffer read ", n, " data: ", buffer[0]); #endif @@ -462,8 +440,12 @@ void MAX31865::writeRegister8(uint8_t addr, uint8_t data) { WRITE(_cs, LOW); - spixfer(addr | 0x80); // make sure top bit is set - spixfer(data); + #ifdef TARGET_LPC1768 + DELAY_CYCLES(_spi_speed); + #endif + + spiTransfer(addr | 0x80); // make sure top bit is set + spiTransfer(data); if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) SPI.endTransaction(); @@ -480,21 +462,38 @@ void MAX31865::writeRegister8(uint8_t addr, uint8_t data) { * @param x an 8-bit chunk of data to write * @return the 8-bit response */ -uint8_t MAX31865::spixfer(uint8_t x) { +uint8_t MAX31865::spiTransfer(uint8_t x) { if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) return SPI.transfer(x); - uint8_t reply = 0; - for (int i = 7; i >= 0; i--) { - reply <<= 1; - WRITE(_sclk, HIGH); - WRITE(_mosi, x & (1 << i)); - WRITE(_sclk, LOW); - if (READ(_miso)) - reply |= 1; - } + #ifdef TARGET_LPC1768 + return swSpiTransfer(x, _spi_speed, _sclk, _miso, _mosi); + #else + uint8_t reply = 0; + for (int i = 7; i >= 0; i--) { + WRITE(_sclk, HIGH); DELAY_NS_VAR(_spi_delay); + reply <<= 1; + WRITE(_mosi, x & _BV(i)); DELAY_NS_VAR(_spi_delay); + if (READ(_miso)) reply |= 1; + WRITE(_sclk, LOW); DELAY_NS_VAR(_spi_delay); + } + return reply; + #endif +} - return reply; +void MAX31865::softSpiBegin(const uint8_t spi_speed) { + #ifdef MAX31865_DEBUG + SERIAL_ECHOLNPGM("Initializing MAX31865 Software SPI"); + #endif + #ifdef TARGET_LPC1768 + swSpiBegin(_sclk, _miso, _mosi); + _spi_speed = swSpiInit(spi_speed, _sclk, _mosi); + #else + _spi_delay = (100UL << spi_speed) / 3; // Calculate delay in ns. Top speed is ~10MHz, or 100ns delay between bits. + OUT_WRITE(_sclk, LOW); + SET_OUTPUT(_mosi); + SET_INPUT(_miso); + #endif } #endif // HAS_MAX31865 && !USE_ADAFRUIT_MAX31865 diff --git a/Marlin/src/libs/MAX31865.h b/Marlin/src/libs/MAX31865.h index 5d50e870ecd2a..7610924c2313c 100644 --- a/Marlin/src/libs/MAX31865.h +++ b/Marlin/src/libs/MAX31865.h @@ -90,6 +90,13 @@ class MAX31865 { static SPISettings spiConfig; TERN(LARGE_PINMAP, uint32_t, uint8_t) _sclk, _miso, _mosi, _cs; + + #ifdef TARGET_LPC1768 + uint8_t _spi_speed; + #else + uint16_t _spi_delay; + #endif + float Rzero, Rref; void setConfig(uint8_t config, bool enable); @@ -99,7 +106,9 @@ class MAX31865 { uint16_t readRegister16(uint8_t addr); void writeRegister8(uint8_t addr, uint8_t reg); - uint8_t spixfer(uint8_t addr); + uint8_t spiTransfer(uint8_t addr); + + void softSpiBegin(const uint8_t spi_speed); public: #ifdef LARGE_PINMAP diff --git a/buildroot/tests/LPC1769 b/buildroot/tests/LPC1769 index f0dab630e5e53..3fe99734ca6b0 100755 --- a/buildroot/tests/LPC1769 +++ b/buildroot/tests/LPC1769 @@ -14,11 +14,12 @@ exec_test $1 $2 "Azteeg X5GT Example Configuration" "$3" restore_configs opt_set MOTHERBOARD BOARD_SMOOTHIEBOARD \ - EXTRUDERS 2 TEMP_SENSOR_1 -1 TEMP_SENSOR_BED 5 \ + EXTRUDERS 2 TEMP_SENSOR_0 -5 TEMP_SENSOR_1 -1 TEMP_SENSOR_BED 5 TEMP_0_CS_PIN P1_29 \ GRID_MAX_POINTS_X 16 \ NOZZLE_CLEAN_START_POINT "{ { 10, 10, 3 }, { 10, 10, 3 } }" \ NOZZLE_CLEAN_END_POINT "{ { 10, 20, 3 }, { 10, 20, 3 } }" opt_enable TFTGLCD_PANEL_SPI SDSUPPORT ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ + MAX31865_SENSOR_OHMS_0 MAX31865_CALIBRATION_OHMS_0 \ FIX_MOUNTED_PROBE AUTO_BED_LEVELING_BILINEAR G29_RETRY_AND_RECOVER Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET LEVEL_CORNERS_USE_PROBE LEVEL_CORNERS_VERIFY_RAISED \ PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ diff --git a/buildroot/tests/teensy41 b/buildroot/tests/teensy41 index fd89512ea57bc..1affd7c89e125 100755 --- a/buildroot/tests/teensy41 +++ b/buildroot/tests/teensy41 @@ -15,12 +15,13 @@ exec_test $1 $2 "Teensy4.1 with default config" "$3" # restore_configs opt_set MOTHERBOARD BOARD_TEENSY41 \ - EXTRUDERS 2 TEMP_SENSOR_0 1 TEMP_SENSOR_1 5 TEMP_SENSOR_BED 1 \ + EXTRUDERS 2 TEMP_SENSOR_0 -5 TEMP_SENSOR_1 5 TEMP_SENSOR_BED 1 TEMP_0_CS_PIN 23 \ I2C_SLAVE_ADDRESS 63 \ GRID_MAX_POINTS_X 16 \ NOZZLE_CLEAN_START_POINT "{ { 10, 10, 3 }, { 10, 10, 3 } }" \ NOZZLE_CLEAN_END_POINT "{ { 10, 20, 3 }, { 10, 20, 3 } }" -opt_enable EXTENSIBLE_UI LCD_INFO_MENU SDSUPPORT SDCARD_SORT_ALPHA \ +opt_enable MAX31865_SENSOR_OHMS_0 MAX31865_CALIBRATION_OHMS_0 \ + EXTENSIBLE_UI LCD_INFO_MENU SDSUPPORT SDCARD_SORT_ALPHA \ FILAMENT_LCD_DISPLAY CALIBRATION_GCODE BAUD_RATE_GCODE \ FIX_MOUNTED_PROBE Z_SAFE_HOMING AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET \ From dc972990f35ed0f6c1ddc7d2d6c15df9e8a4cb3c Mon Sep 17 00:00:00 2001 From: Evgeniy Zhabotinskiy Date: Sun, 7 Nov 2021 07:16:18 +0300 Subject: [PATCH 034/273] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20M503=20report=20(#?= =?UTF-8?q?23084)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/config/M304.cpp | 2 +- Marlin/src/module/settings.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/gcode/config/M304.cpp b/Marlin/src/gcode/config/M304.cpp index 4bd415db1e0a0..97dc4be25e1c8 100644 --- a/Marlin/src/gcode/config/M304.cpp +++ b/Marlin/src/gcode/config/M304.cpp @@ -43,7 +43,7 @@ void GcodeSuite::M304() { void GcodeSuite::M304_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, F(STR_BED_PID)); - SERIAL_ECHO_MSG( + SERIAL_ECHOLNPGM( " M304 P", thermalManager.temp_bed.pid.Kp , " I", unscalePID_i(thermalManager.temp_bed.pid.Ki) , " D", unscalePID_d(thermalManager.temp_bed.pid.Kd) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 01a5c47fd54ee..f4eba776b608c 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -3068,9 +3068,9 @@ void MarlinSettings::reset() { // CONFIG_ECHO_HEADING("Linear Units"); #if ENABLED(INCH_MODE_SUPPORT) - SERIAL_ECHOPGM(" G2", AS_DIGIT(parser.linear_unit_factor == 1.0), " ;"); + SERIAL_ECHO_MSG(" G2", AS_DIGIT(parser.linear_unit_factor == 1.0), " ;"); #else - SERIAL_ECHOPGM(" G21 ;"); + SERIAL_ECHO_MSG(" G21 ;"); #endif gcode.say_units(); From e15f9fdcd9ccff010f188d6b0762cf00956a55c1 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Sat, 6 Nov 2021 23:09:15 -0700 Subject: [PATCH 035/273] =?UTF-8?q?=F0=9F=9A=B8=20Indicate=20Preheating=20?= =?UTF-8?q?for=20probe=20/=20leveling=20(#23088)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/module/probe.cpp | 2 ++ 2 files changed, 3 insertions(+) diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 9a92a7e268fb3..ecd5ef56601a4 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -531,6 +531,7 @@ namespace Language_en { LSTR MSG_ERR_MINTEMP = _UxGT("Err: MINTEMP"); LSTR MSG_HALTED = _UxGT("PRINTER HALTED"); LSTR MSG_PLEASE_RESET = _UxGT("Please Reset"); + LSTR MSG_PREHEATING = _UxGT("Preheating..."); LSTR MSG_HEATING = _UxGT("Heating..."); LSTR MSG_COOLING = _UxGT("Cooling..."); LSTR MSG_BED_HEATING = _UxGT("Bed Heating..."); diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index d9e52a9b431a5..984a3aabb505c 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -362,6 +362,8 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #define WAIT_FOR_BED_HEAT #endif + LCD_MESSAGE(MSG_PREHEATING); + DEBUG_ECHOPGM("Preheating "); #if ENABLED(WAIT_FOR_NOZZLE_HEAT) From 030b66eb2710165a2081c625a7a0573a6d04b5ae Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 7 Nov 2021 01:11:51 -0600 Subject: [PATCH 036/273] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20code=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 5 +++-- Marlin/src/feature/twibus.cpp | 2 +- .../src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h | 4 ++-- .../variant.cpp | 18 +++++++++--------- 4 files changed, 15 insertions(+), 14 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5e8881d1c6477..8b6b278f1ff05 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1554,6 +1554,7 @@ void setup() { #endif #if HAS_DWIN_E3V2_BASIC + SETUP_LOG("E3V2 Init"); Encoder_Configuration(); HMI_Init(); HMI_SetLanguageCache(); @@ -1562,7 +1563,7 @@ void setup() { #endif #if HAS_SERVICE_INTERVALS && !HAS_DWIN_E3V2_BASIC - ui.reset_status(true); // Show service messages or keep current status + SETUP_RUN(ui.reset_status(true)); // Show service messages or keep current status #endif #if ENABLED(MAX7219_DEBUG) @@ -1593,7 +1594,7 @@ void setup() { #endif #if BOTH(HAS_LCD_MENU, TOUCH_SCREEN_CALIBRATION) && EITHER(TFT_CLASSIC_UI, TFT_COLOR_UI) - ui.check_touch_calibration(); + SETUP_RUN(ui.check_touch_calibration()); #endif marlin_state = MF_RUNNING; diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index 0e23b48a40808..e33581676c4a3 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -98,7 +98,7 @@ void TWIBus::echodata(uint8_t bytes, FSTR_P const pref, uint8_t adr, const uint8 union TwoBytesToInt16 { uint8_t bytes[2]; int16_t integervalue; }; TwoBytesToInt16 ConversionUnion; - echoprefix(bytes, pref, adr); + echoprefix(bytes, pref, adr); while (bytes-- && Wire.available()) { int value = Wire.read(); diff --git a/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h b/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h index 7ce21a20afbda..fea5b00b50d8b 100644 --- a/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h @@ -54,7 +54,7 @@ // // Limit Switches -// +// #define X_STOP_PIN PD8 #define Y_STOP_PIN PD15 #define Z_MIN_PIN PA11 @@ -173,7 +173,7 @@ #define LCD_PINS_D5 PE7 #define LCD_PINS_D6 PB2 #define LCD_PINS_D7 PB1 - + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_PRO_V1_F429/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_PRO_V1_F429/variant.cpp index c8ed0d1e52ecd..7979f3f804642 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_PRO_V1_F429/variant.cpp +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_PRO_V1_F429/variant.cpp @@ -190,12 +190,12 @@ WEAK void SystemClock_Config(void) /* Enable Power Control clock */ __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value regarding system frequency refer to product datasheet. */ __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - + /* Enable HSE Oscillator and activate PLL with HSE as source */ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; RCC_OscInitStruct.HSEState = RCC_HSE_ON; @@ -209,19 +209,19 @@ WEAK void SystemClock_Config(void) { /* Initialization Error */ } - + if(HAL_PWREx_EnableOverDrive() != HAL_OK) { /* Initialization Error */ } - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; if(HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK) { /* Initialization Error */ From fa5bfca3678ef6e695e8e5d4a51af2bcd02e8e85 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 8 Nov 2021 01:01:19 +0000 Subject: [PATCH 037/273] [cron] Bump distribution date (2021-11-08) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ce8acbbc3e2c3..6cba2f4558a67 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 "2021-11-07" +//#define STRING_DISTRIBUTION_DATE "2021-11-08" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7626b58e3eb3e..a1c65c210f007 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 "2021-11-07" + #define STRING_DISTRIBUTION_DATE "2021-11-08" #endif /** From 467e883e17dd8a67c26a3273f0586ce474e959f5 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 9 Nov 2021 01:01:17 +0000 Subject: [PATCH 038/273] [cron] Bump distribution date (2021-11-09) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 6cba2f4558a67..38c122bdb490a 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 "2021-11-08" +//#define STRING_DISTRIBUTION_DATE "2021-11-09" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a1c65c210f007..45bf84a537852 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 "2021-11-08" + #define STRING_DISTRIBUTION_DATE "2021-11-09" #endif /** From cee50552ab4dc3463717920b792a8825a783cd83 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Tue, 9 Nov 2021 08:30:02 -0800 Subject: [PATCH 039/273] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20BTT002=20(STM32F40?= =?UTF-8?q?7VET6)=20variant,=20MK3=5FFAN=5FPINS=20flag=20(#23093)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 2 +- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 20 +++++++- .../boards/marlin_BigTree_BTT002_VET6.json | 46 +++++++++++++++++++ ini/stm32f4.ini | 8 ++++ 4 files changed, 73 insertions(+), 3 deletions(-) create mode 100644 buildroot/share/PlatformIO/boards/marlin_BigTree_BTT002_VET6.json diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 369a78be7add0..57648b3e16fe0 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -616,7 +616,7 @@ #elif MB(BTT_GTR_V1_0) #include "stm32f4/pins_BTT_GTR_V1_0.h" // STM32F4 env:BIGTREE_GTR_V1_0 env:BIGTREE_GTR_V1_0_usb_flash_drive #elif MB(BTT_BTT002_V1_0) - #include "stm32f4/pins_BTT_BTT002_V1_0.h" // STM32F4 env:BIGTREE_BTT002 + #include "stm32f4/pins_BTT_BTT002_V1_0.h" // STM32F4 env:BIGTREE_BTT002 env:BIGTREE_BTT002_VET6 #elif MB(BTT_E3_RRF) #include "stm32f4/pins_BTT_E3_RRF.h" // STM32F4 env:BIGTREE_E3_RRF #elif MB(BTT_SKR_V2_0_REV_A) 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 b7ffcce4a86cc..7b99352ef4952 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -29,6 +29,8 @@ #define BOARD_INFO_NAME "BTT BTT002 V1.0" +//#define MK3_FAN_PINS + #define USES_DIAG_PINS // Ignore temp readings during development. @@ -169,8 +171,22 @@ // #define HEATER_0_PIN PE6 // Heater0 #define HEATER_BED_PIN PE5 // Hotbed -#define FAN_PIN PB8 // Fan1 -#define FAN1_PIN PB9 // Fan0 + +#ifndef FAN_PIN + #ifdef MK3_FAN_PINS + #define FAN_PIN PB8 // Fan1 + #else + #define FAN_PIN PB9 // Fan0 + #endif +#endif + +#ifndef FAN1_PIN + #ifdef MK3_FAN_PINS + #define FAN1_PIN PB9 // Fan0 + #else + #define FAN1_PIN PB8 // Fan1 + #endif +#endif /** * -----------------------------------BTT002 V1.0---------------------------------------- diff --git a/buildroot/share/PlatformIO/boards/marlin_BigTree_BTT002_VET6.json b/buildroot/share/PlatformIO/boards/marlin_BigTree_BTT002_VET6.json new file mode 100644 index 0000000000000..77d3af0112833 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_BigTree_BTT002_VET6.json @@ -0,0 +1,46 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F4 -DSTM32F407xx -DSTM32F40_41xxx", + "f_cpu": "168000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "mcu": "stm32f407vet6", + "variant": "MARLIN_BIGTREE_BTT002" + }, + "debug": { + "jlink_device": "STM32F407VE", + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd" + }, + "frameworks": [ + "arduino" + ], + "name": "STM32F407VE (192k RAM. 512k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 131072, + "maximum_size": 524288, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "offset_address": "0x8008000", + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f407ve.html", + "vendor": "ST" +} diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 0e9b507c8b221..6fec1d46fce7d 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -204,6 +204,14 @@ build_flags = ${stm32_variant.build_flags} -DPIN_SERIAL2_RX=PD_6 -DPIN_SERIAL2_TX=PD_5 +# +# BigTreeTech BTT002 V1.x with 512k of flash (STM32F407VET6 ARM Cortex-M4) +# +[env:BIGTREE_BTT002_VET6] +platform = ${env:BIGTREE_BTT002.platform} +extends = env:BIGTREE_BTT002 +board = marlin_BigTree_BTT002_VET6 + # # BigTreeTech SKR V2.0 (STM32F407VGT6 ARM Cortex-M4) with USB Flash Drive Support # From e776fa1e93d5a8ac1d6ebd7c084e18e1a009ad6b Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 10 Nov 2021 01:01:08 +0000 Subject: [PATCH 040/273] [cron] Bump distribution date (2021-11-10) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 38c122bdb490a..0f2136cbddbcb 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 "2021-11-09" +//#define STRING_DISTRIBUTION_DATE "2021-11-10" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 45bf84a537852..e61948958d9ba 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 "2021-11-09" + #define STRING_DISTRIBUTION_DATE "2021-11-10" #endif /** From 07befb545b2bc6ea284d444637a039127af6b4d1 Mon Sep 17 00:00:00 2001 From: BigTreeTech <38851044+bigtreetech@users.noreply.github.com> Date: Wed, 10 Nov 2021 23:56:10 +0800 Subject: [PATCH 041/273] =?UTF-8?q?=E2=9C=A8=20Support=20for=20BIQU=20B1-S?= =?UTF-8?q?E-Plus=20strain=20gauge=20probe=20(#23101)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 9 +++++++++ Marlin/src/module/endstops.cpp | 3 +++ Marlin/src/pins/pinsDebug_list.h | 9 +++++++++ Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h | 4 +++- Marlin/src/pins/stm32f1/pins_CREALITY_V452.h | 5 ++++- Marlin/src/pins/stm32f1/pins_CREALITY_V453.h | 5 ++++- Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 7 +++++++ 7 files changed, 39 insertions(+), 3 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 8ab3929c41141..2c53498d0272c 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1220,6 +1220,15 @@ #endif #endif +/** + * Probe Enable / Disable + * The probe only provides a triggered signal when enabled. + */ +//#define PROBE_ENABLE_DISABLE +#if ENABLED(PROBE_ENABLE_DISABLE) + //#define PROBE_ENABLE_PIN -1 // Override the default pin here +#endif + /** * Multiple Probing * diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 04f20ca3a4e27..aa5907477eb1e 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -392,6 +392,9 @@ void Endstops::not_homing() { #if HAS_BED_PROBE void Endstops::enable_z_probe(const bool onoff) { z_probe_enabled = onoff; + #if PIN_EXISTS(PROBE_ENABLE) + WRITE(PROBE_ENABLE_PIN, onoff); + #endif resync(); } #endif diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 05756d6004204..dc0d5225db32c 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -1439,6 +1439,15 @@ #if PIN_EXISTS(Z_MIN_PROBE) REPORT_NAME_DIGITAL(__LINE__, Z_MIN_PROBE_PIN) #endif +#if PIN_EXISTS(PROBE_ACTIVATION_SWITCH) + REPORT_NAME_DIGITAL(__LINE__, PROBE_ACTIVATION_SWITCH_PIN) +#endif +#if PIN_EXISTS(PROBE_ENABLE) + REPORT_NAME_DIGITAL(__LINE__, PROBE_ENABLE_PIN) +#endif +#if PIN_EXISTS(PROBE_TARE) + REPORT_NAME_DIGITAL(__LINE__, PROBE_TARE_PIN) +#endif #if PIN_EXISTS(I_ATT) REPORT_NAME_DIGITAL(__LINE__, I_ATT_PIN) #endif diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h index 8bae916a463cd..8368fd03cd9c2 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -71,7 +71,9 @@ // Probe // #define PROBE_TARE_PIN PA1 -#define PROBE_ACTIVATION_SWITCH_PIN PC2 // Optoswitch to Enable Z Probe +#if ENABLED(PROBE_ACTIVATION_SWITCH) + #define PROBE_ACTIVATION_SWITCH_PIN PC2 // Optoswitch to Enable Z Probe +#endif // // Steppers diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h index a2add81c8b11c..7d3140056a0dd 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h @@ -34,6 +34,9 @@ #define HEATER_0_PIN PA1 // HEATER1 #define HEATER_BED_PIN PA2 // HOT BED #define FAN_PIN PA0 // FAN -#define PROBE_ACTIVATION_SWITCH_PIN PC6 // Optoswitch to Enable Z Probe + +#if ENABLED(PROBE_ACTIVATION_SWITCH) + #define PROBE_ACTIVATION_SWITCH_PIN PC6 // Optoswitch to Enable Z Probe +#endif #include "pins_CREALITY_V45x.h" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h index 7b8c3280d2b75..b669887d1eaf0 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h @@ -34,6 +34,9 @@ #define HEATER_0_PIN PB14 // HEATER1 #define HEATER_BED_PIN PB13 // HOT BED #define FAN_PIN PB15 // FAN -#define PROBE_ACTIVATION_SWITCH_PIN PB2 // Optoswitch to Enable Z Probe + +#if ENABLED(PROBE_ACTIVATION_SWITCH) + #define PROBE_ACTIVATION_SWITCH_PIN PB2 // Optoswitch to Enable Z Probe +#endif #include "pins_CREALITY_V45x.h" 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 9a280eac1643c..762e355626630 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 @@ -132,6 +132,13 @@ #define Z_MIN_PROBE_PIN PE4 #endif +// +// Probe enable +// +#if ENABLED(PROBE_ENABLE_DISABLE) + #define PROBE_ENABLE_PIN SERVO0_PIN +#endif + // // Filament Runout Sensor // From 99df0b86fb3fdf8a671fd553301b7bb5acc4a0a5 Mon Sep 17 00:00:00 2001 From: George Fu Date: Wed, 10 Nov 2021 23:58:20 +0800 Subject: [PATCH 042/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20FYSETC=20Cheetah?= =?UTF-8?q?=202.0=20pins=20for=20production=20(#23104)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h index a604a71c4ba9a..054da62754651 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h @@ -38,9 +38,9 @@ #define FLASH_EEPROM_EMULATION #define FLASH_EEPROM_LEVELING - #define FLASH_SECTOR 2 + #define FLASH_SECTOR 1 #define FLASH_UNIT_SIZE 0x4000 // 16k - #define FLASH_ADDRESS_START 0x8008000 + #define FLASH_ADDRESS_START 0x8004000 #endif // @@ -57,7 +57,7 @@ // Limit Switches // #define X_STOP_PIN PB4 -#define Y_STOP_PIN PB3 +#define Y_STOP_PIN PC8 #define Z_STOP_PIN PB1 // @@ -111,9 +111,10 @@ #define HEATER_0_PIN PC6 #define HEATER_BED_PIN PC7 #ifndef FAN_PIN - #define FAN_PIN PA1 + #define FAN_PIN PA14 #endif -#define FAN1_PIN PC8 +#define FAN1_PIN PA13 +#define FAN2_PIN PA1 // // Temperature Sensors From b4b16b63ff40aaba9e482294e8f34403eb51e632 Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Wed, 10 Nov 2021 11:31:35 -0500 Subject: [PATCH 043/273] =?UTF-8?q?=F0=9F=9A=B8=20Expose=20sub-options=20f?= =?UTF-8?q?or=20E3V2=20Enhanced=20(#23099)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 +- Marlin/src/MarlinCore.cpp | 1 - Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 111 +++++++++++++++++++++----- Marlin/src/lcd/e3v2/enhanced/dwin.h | 4 +- Marlin/src/lcd/marlinui.cpp | 19 ++--- Marlin/src/lcd/marlinui.h | 7 +- 6 files changed, 105 insertions(+), 39 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index fc495a6ea6327..fc9688edb76e8 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1280,7 +1280,7 @@ #endif // HAS_LCD_MENU -#if HAS_DISPLAY +#if EITHER(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED) // The timeout (in ms) to return to the status screen from sub-menus //#define LCD_TIMEOUT_TO_STATUS 15000 diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 8b6b278f1ff05..f2031cdfb9f65 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1559,7 +1559,6 @@ void setup() { HMI_Init(); HMI_SetLanguageCache(); HMI_StartFrame(true); - DWIN_StatusChanged(GET_TEXT_F(WELCOME_MSG)); #endif #if HAS_SERVICE_INTERVALS && !HAS_DWIN_E3V2_BASIC diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 787cf717eb16b..c92bfe57c3bf6 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -170,6 +170,7 @@ select_t select_page{0}, select_file{0}, select_print{0}; uint8_t index_file = MROWS; bool dwin_abort_flag = false; // Flag to reset feedrate, return to Home +bool hash_changed = true; // Flag to know if message status was changed constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE; constexpr float default_max_acceleration[] = DEFAULT_MAX_ACCELERATION; @@ -610,6 +611,86 @@ void Popup_window_PauseOrStop() { #endif +// Draw status line +void DWIN_DrawStatusLine(const uint16_t color, const uint16_t bgcolor, const char *text, const bool center = true) { + DWIN_Draw_Rectangle(1, bgcolor, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); + if (text) { + if (center) DWINUI::Draw_CenteredString(color, STATUS_Y + 2, text); + else DWINUI::Draw_String(color, 0, STATUS_Y + 2, text); + } + DWIN_UpdateLCD(); +} +void DWIN_DrawStatusLine(const char *text, const bool center = true) { + DWIN_DrawStatusLine(HMI_data.StatusTxt_Color, HMI_data.StatusBg_Color, text, center); +} + +// Clear & reset status line +void DWIN_ResetStatusLine() { + ui.status_message[0] = 0; + DWIN_CheckStatusMessage(); +} + +// Djb2 hash algorithm +void DWIN_CheckStatusMessage() { + static uint32_t old_hash = 0; + char * str = &ui.status_message[0]; + uint32_t hash = 5381; + char c; + while ((c = *str++)) hash = ((hash << 5) + hash) + c; /* hash * 33 + c */ + hash_changed = hash != old_hash; + old_hash = hash; +}; + +void DWIN_DrawStatusMessage() { + const uint8_t max_status_chars = DWIN_WIDTH / DWINUI::fontWidth(DWINUI::font); + + #if ENABLED(STATUS_MESSAGE_SCROLLING) + + // Get the UTF8 character count of the string + uint8_t slen = utf8_strlen(ui.status_message); + + // If the string fits the status line do not scroll it + if (slen <= max_status_chars) { + if (hash_changed) { + DWIN_DrawStatusLine(HMI_data.StatusTxt_Color, HMI_data.StatusBg_Color, ui.status_message); + hash_changed = false; + } + } + else { + // String is larger than the available line space + + // Get a pointer to the next valid UTF8 character + // and the string remaining length + uint8_t rlen; + const char *stat = MarlinUI::status_and_len(rlen); + DWIN_Draw_Rectangle(1, HMI_data.StatusBg_Color, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); + DWINUI::MoveTo(0, STATUS_Y + 2); + DWINUI::Draw_String(stat, max_status_chars); + + // If the string doesn't completely fill the line... + if (rlen < max_status_chars) { + DWINUI::Draw_Char('.'); // Always at 1+ spaces left, draw a dot + uint8_t chars = max_status_chars - rlen; // Amount of space left in characters + if (--chars) { // Draw a second dot if there's space + DWINUI::Draw_Char('.'); + if (--chars) + DWINUI::Draw_String(ui.status_message, chars); // Print a second copy of the message + } + } + MarlinUI::advance_status_scroll(); + } + + #else + + if (hash_changed) { + ui.status_message[max_status_chars] = 0; + DWIN_DrawStatusLine(HMI_data.StatusTxt_Color, HMI_data.StatusBg_Color, ui.status_message); + hash_changed = false; + } + + #endif +} + void Draw_Print_Labels() { if (HMI_IsChinese()) { Title.FrameCopy(30, 1, 42, 14); // "Printing" @@ -713,7 +794,7 @@ void Draw_Main_Menu() { void Goto_Main_Menu() { checkkey = MainMenu; - DWIN_StatusChanged(); + ui.reset_status(true); Draw_Main_Menu(); } @@ -1077,6 +1158,7 @@ void Draw_Status_Area(const bool with_update) { void HMI_StartFrame(const bool with_update) { Goto_Main_Menu(); + DWIN_DrawStatusLine(nullptr); Draw_Status_Area(with_update); } @@ -1474,7 +1556,7 @@ void DWIN_Update() { } void EachMomentUpdate() { - static millis_t next_var_update_ms = 0, next_rts_update_ms = 0; + static millis_t next_var_update_ms = 0, next_rts_update_ms = 0, next_status_update_ms = 0; const millis_t ms = millis(); if (ELAPSED(ms, next_var_update_ms)) { @@ -1482,6 +1564,11 @@ void EachMomentUpdate() { update_variable(); } + if (ELAPSED(ms, next_status_update_ms)) { + next_status_update_ms = ms + 500; + DWIN_DrawStatusMessage(); + } + if (PENDING(ms, next_rts_update_ms)) return; next_rts_update_ms = ms + DWIN_SCROLL_UPDATE_INTERVAL; @@ -1745,7 +1832,7 @@ void Draw_Title(TitleClass* title) { void Draw_Menu(MenuClass* menu) { DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); DWIN_Draw_Rectangle(1, DWINUI::backcolor, 0, TITLE_HEIGHT, DWIN_WIDTH - 1, STATUS_Y - 1); - ui.set_status(""); + DWIN_ResetStatusLine(); } // Startup routines @@ -1758,23 +1845,6 @@ void DWIN_Startup() { HMI_SetLanguage(); } -void DWIN_DrawStatusLine(const uint16_t color, const uint16_t bgcolor, const char * const text/*=nullptr*/) { - DWIN_Draw_Rectangle(1, bgcolor, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); - if (text) DWINUI::Draw_CenteredString(color, STATUS_Y + 2, text); - DWIN_UpdateLCD(); -} - -// Update Status line -void DWIN_StatusChanged(const char * const cstr/*=nullptr*/) { - DWIN_DrawStatusLine(HMI_data.StatusTxt_Color, HMI_data.StatusBg_Color, cstr); -} - -void DWIN_StatusChanged(FSTR_P const fstr) { - char str[strlen_P(FTOP(fstr)) + 1]; - strcpy_P(str, FTOP(fstr)); - DWIN_StatusChanged(str); -} - // Started a Print Job void DWIN_Print_Started(const bool sd) { sdprint = card.isPrinting() || sd; @@ -1866,7 +1936,6 @@ void DWIN_RebootScreen() { void DWIN_Redraw_screen() { Draw_Main_Area(); - DWIN_StatusChanged(ui.status_message); Draw_Status_Area(false); } diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.h b/Marlin/src/lcd/e3v2/enhanced/dwin.h index c2220c68a8c08..90b7ceacfa443 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.h @@ -174,9 +174,7 @@ void EachMomentUpdate(); void update_variable(); void DWIN_HandleScreen(); void DWIN_Update(); -void DWIN_DrawStatusLine(const uint16_t color, const uint16_t bgcolor, const char *text=nullptr); -void DWIN_StatusChanged(const char * const cstr=nullptr); -void DWIN_StatusChanged(FSTR_P const fstr); +void DWIN_CheckStatusMessage(); void DWIN_StartHoming(); void DWIN_CompletedHoming(); #if HAS_MESH diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 925e1c1618d31..57157d2c00ce8 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -49,6 +49,7 @@ MarlinUI ui; #if ENABLED(DWIN_CREALITY_LCD) #include "e3v2/creality/dwin.h" #elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "fontutils.h" #include "e3v2/enhanced/dwin.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) #include "e3v2/jyersui/dwin.h" @@ -69,7 +70,7 @@ MarlinUI ui; constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #if HAS_STATUS_MESSAGE - #if BOTH(HAS_WIRED_LCD, STATUS_MESSAGE_SCROLLING) + #if ENABLED(STATUS_MESSAGE_SCROLLING) && EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_ENHANCED) uint8_t MarlinUI::status_scroll_offset; // = 0 #endif char MarlinUI::status_message[MAX_MESSAGE_LENGTH + 1]; @@ -1481,11 +1482,9 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; void MarlinUI::finish_status(const bool persist) { - #if HAS_WIRED_LCD + UNUSED(persist); - #if !(BASIC_PROGRESS_BAR && (PROGRESS_MSG_EXPIRE) > 0) - UNUSED(persist); - #endif + #if HAS_WIRED_LCD #if BASIC_PROGRESS_BAR || BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) const millis_t ms = millis(); @@ -1502,13 +1501,15 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; next_filament_display = ms + 5000UL; // Show status message for 5s #endif - TERN_(STATUS_MESSAGE_SCROLLING, status_scroll_offset = 0); - #else // HAS_WIRED_LCD - UNUSED(persist); + #endif + + #if ENABLED(STATUS_MESSAGE_SCROLLING) && EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_ENHANCED) + status_scroll_offset = 0; #endif TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(status_message)); - TERN_(HAS_DWIN_E3V2_BASIC, DWIN_StatusChanged(status_message)); + TERN_(DWIN_CREALITY_LCD, DWIN_StatusChanged(status_message)); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_CheckStatusMessage()); TERN_(DWIN_CREALITY_LCD_JYERSUI, CrealityDWIN.Update_Status(status_message)); } diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 4f797d899d83a..ed5b539eaf8f6 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -356,6 +356,9 @@ class MarlinUI { #if EITHER(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED) static void kill_screen(FSTR_P const lcd_error, FSTR_P const lcd_component); + #if DISABLED(LIGHTWEIGHT_UI) + static void draw_status_message(const bool blink); + #endif #else static inline void kill_screen(FSTR_P const, FSTR_P const) {} #endif @@ -444,10 +447,6 @@ class MarlinUI { static inline void completion_feedback(const bool=true) { TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); } #endif - #if DISABLED(LIGHTWEIGHT_UI) - static void draw_status_message(const bool blink); - #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) static void draw_hotend_status(const uint8_t row, const uint8_t extruder); #endif From 589a6d7f6bbf2254958aa92d8707c51fcbcd8dd3 Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Wed, 10 Nov 2021 11:55:20 -0500 Subject: [PATCH 044/273] =?UTF-8?q?=F0=9F=9A=B8=20Fix=20up=20E3V2=20Enhanc?= =?UTF-8?q?ed=20(#23100)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/pause.cpp | 1 - Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 106 ++++++++++---------- Marlin/src/lcd/e3v2/enhanced/dwin.h | 5 +- Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp | 4 +- Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h | 11 +- Marlin/src/lcd/e3v2/enhanced/dwinui.cpp | 18 ++-- Marlin/src/lcd/e3v2/enhanced/dwinui.h | 37 ++++--- Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp | 41 ++++++-- Marlin/src/lcd/e3v2/enhanced/meshviewer.h | 4 +- Marlin/src/module/settings.cpp | 2 - Marlin/src/module/temperature.cpp | 3 +- 11 files changed, 128 insertions(+), 104 deletions(-) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index d97ac2a0ac6e5..191c0e4b08ef3 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -254,7 +254,6 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE))); TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE), FPSTR(CONTINUE_STR))); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE), FPSTR(CONTINUE_STR))); wait_for_user = true; // A click or M108 breaks the purge_length loop for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index c92bfe57c3bf6..d1a9ba7077fda 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -23,8 +23,8 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.6.3 - * Date: 2021/09/10 + * Version: 3.7.1 + * Date: 2021/11/09 */ #include "../../../inc/MarlinConfigPre.h" @@ -142,7 +142,7 @@ HMI_data_t HMI_data; millis_t dwin_heat_time = 0; -uint8_t checkkey = MainMenu, last_checkkey = MainMenu; +uint8_t checkkey = 255, last_checkkey = MainMenu; enum SelectItem : uint8_t { PAGE_PRINT = 0, @@ -387,15 +387,15 @@ void ICON_Stop() { ICON_Button(select_print.now == PRINT_STOP, ICON_Stop_0, ico, txt); } -void Draw_Menu_Cursor(const uint8_t line) { +void Draw_Menu_Cursor(const int8_t line) { DWIN_Draw_Rectangle(1, HMI_data.Cursor_color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); } -void Erase_Menu_Cursor(const uint8_t line) { +void Erase_Menu_Cursor(const int8_t line) { DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); } -void Move_Highlight(const int16_t from, const uint16_t newline) { +void Move_Highlight(const int8_t from, const int8_t newline) { Erase_Menu_Cursor(newline - from); Draw_Menu_Cursor(newline); } @@ -578,6 +578,7 @@ void Popup_window_PauseOrStop() { DWINUI::Draw_Icon(ICON_Cancel_E, 146, 280); } Draw_Select_Highlight(true); + DWIN_UpdateLCD(); } #if HAS_HOTEND || HAS_HEATED_BED @@ -608,7 +609,6 @@ void Popup_window_PauseOrStop() { } } } - #endif // Draw status line @@ -752,6 +752,7 @@ void Draw_PrintProcess() { } void Goto_PrintProcess() { + if (checkkey == PrintProcess) return; checkkey = PrintProcess; Draw_PrintProcess(); } @@ -793,6 +794,7 @@ void Draw_Main_Menu() { } void Goto_Main_Menu() { + if (checkkey == MainMenu) return; checkkey = MainMenu; ui.reset_status(true); Draw_Main_Menu(); @@ -1239,10 +1241,10 @@ void HMI_MainMenu() { case PAGE_INFO_LEVELING: #if HAS_ONESTEP_LEVELING - queue.inject(F("G28XYO\nG28Z\nG29")); // TODO: 'G29' should be homing when needed. Does it make sense for every LCD to do this differently? + queue.inject(F("G28Z\nG29")); // Force to get the current Z home position #else - checkkey = Info; - Draw_Info_Menu(); + last_checkkey = MainMenu; + Goto_InfoMenu(); #endif break; } @@ -1327,7 +1329,7 @@ void HMI_SelectFile() { } } else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (select_file.now == 0) { + if (select_file.now == 0) { // Back select_page.set(PAGE_PRINT); Goto_Main_Menu(); } @@ -1523,7 +1525,6 @@ void Draw_Main_Area() { void HMI_ReturnScreen() { checkkey = last_checkkey; Draw_Main_Area(); - DWIN_UpdateLCD(); return; } @@ -2230,7 +2231,7 @@ void SetMoveZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick(Z_MIN_POS, Z_MAX_POS void SetMoveZto0() { char cmd[48] = ""; char str_1[5] = "", str_2[5] = ""; - sprintf_P(cmd, PSTR("G28OXY\nG28Z\nG0X%sY%sF5000\nG0Z0F300"), + sprintf_P(cmd, PSTR("G28Z\nG0X%sY%sF5000\nM420S0\nG0Z0F300"), #if ENABLED(MESH_BED_LEVELING) dtostrf(0, 1, 1, str_1), dtostrf(0, 1, 1, str_2) @@ -2413,7 +2414,7 @@ void LevBed(uint8_t point) { float xpos = 0, ypos = 0, zval = 0; float margin = PROBING_MARGIN; #else - #define fmt "M420 S0\nG28O\nG90\nG0 Z5 F300\nG0 X%i Y%i F5000\nG0 Z0 F300" + #define fmt "M420S0\nG28O\nG90\nG0Z5F300\nG0X%iY%iF5000\nG0Z0F300" int16_t xpos = 0, ypos = 0; int16_t margin = 30; #endif @@ -2469,7 +2470,7 @@ void LevBedC () { LevBed(4); } void ManualMeshStart(){ LCD_MESSAGE(MSG_UBL_BUILD_MESH_MENU); - gcode.process_subcommands_now(F("G28 XYO\nG28 Z\nM211 S0\nG29S1")); + gcode.process_subcommands_now(F("G28Z\nM211S0\nG29S1")); planner.synchronize(); #ifdef MANUAL_PROBE_START_Z const uint8_t line = CurrentMenu->line(MMeshMoveZItem->pos); @@ -2494,7 +2495,7 @@ void LevBedC () { LevBed(4); } void ManualMeshSave(){ LCD_MESSAGE(MSG_UBL_STORAGE_MESH_MENU); - queue.inject(F("M211 S1\nM500")); + queue.inject(F("M211S1\nM500")); } #endif // MESH_BED_LEVELING @@ -2810,7 +2811,7 @@ void onDrawSteps(MenuItemClass* menuitem, int8_t line) { #if ENABLED(MESH_BED_LEVELING) void onDrawMMeshMoveZ(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) menuitem->SetFrame(1, 160, 118, 209, 132); - onDrawPFloatMenu(menuitem, line); + onDrawPFloat2Menu(menuitem, line); } #endif @@ -3096,11 +3097,11 @@ void HMI_SetIntNoDraw() { // Set an integer pointer variable using the encoder void HMI_SetPInt() { int8_t val = HMI_GetInt(HMI_value.MinValue, HMI_value.MaxValue); - if (!val) return; - else if (val == 2) { // Apply - *HMI_value.P_Int = HMI_value.Value; - if (HMI_value.Apply != nullptr) HMI_value.Apply(); - } else if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); + switch (val) { + case 0: return; + case 1: if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); break; + case 2: *HMI_value.P_Int = HMI_value.Value; if (HMI_value.Apply != nullptr) HMI_value.Apply(); break; + } } // Get a scaled float value using the encoder @@ -3140,17 +3141,16 @@ void HMI_SetFloat() { // Set a scaled float pointer variable using the encoder void HMI_SetPFloat() { const int8_t val = HMI_GetFloat(HMI_value.dp, HMI_value.MinValue, HMI_value.MaxValue); - if (!val) return; - if (val == 2) { // Apply - *HMI_value.P_Float = HMI_value.Value / POW(10, HMI_value.dp); - if (HMI_value.Apply != nullptr) HMI_value.Apply(); + switch (val) { + case 0: return; + case 1: if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); break; + case 2: *HMI_value.P_Float = HMI_value.Value / POW(10, HMI_value.dp); if (HMI_value.Apply != nullptr) HMI_value.Apply(); break; } - else if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); } // Menu Creation and Drawing functions ====================================================== -void SetMenuTitle(frame_rect_t cn, frame_rect_t en, const __FlashStringHelper* fstr) { +void SetMenuTitle(frame_rect_t cn, const __FlashStringHelper* fstr) { if (HMI_IsChinese() && (cn.w != 0)) CurrentMenu->MenuTitle.SetFrame(cn.x, cn.y, cn.w, cn.h); else @@ -3162,7 +3162,7 @@ void Draw_Prepare_Menu() { if (PrepareMenu == nullptr) PrepareMenu = new MenuClass(); if (CurrentMenu != PrepareMenu) { CurrentMenu = PrepareMenu; - SetMenuTitle({133, 1, 28, 13}, {179, 0, 48, 14}, GET_TEXT_F(MSG_PREPARE)); + SetMenuTitle({133, 1, 28, 13}, GET_TEXT_F(MSG_PREPARE)); DWINUI::MenuItemsPrepare(13); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -3203,7 +3203,7 @@ void Draw_LevBedCorners_Menu() { if (LevBedMenu == nullptr) LevBedMenu = new MenuClass(); if (CurrentMenu != LevBedMenu) { CurrentMenu = LevBedMenu; - SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_BED_TRAMMING)); // TODO: Chinese, English "Bed Tramming" JPG + SetMenuTitle({0}, GET_TEXT_F(MSG_BED_TRAMMING)); // TODO: Chinese, English "Bed Tramming" JPG DWINUI::MenuItemsPrepare(6); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FL), onDrawMenuItem, LevBedFL); @@ -3220,7 +3220,7 @@ void Draw_Control_Menu() { if (ControlMenu == nullptr) ControlMenu = new MenuClass(); if (CurrentMenu != ControlMenu) { CurrentMenu = ControlMenu; - SetMenuTitle({103, 1, 28, 14}, {128, 2, 49, 11}, GET_TEXT_F(MSG_CONTROL)); + SetMenuTitle({103, 1, 28, 14}, GET_TEXT_F(MSG_CONTROL)); DWINUI::MenuItemsPrepare(9); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); ADDMENUITEM(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawTempSubMenu, Draw_Temperature_Menu); @@ -3242,8 +3242,8 @@ void Draw_AdvancedSettings_Menu() { if (AdvancedSettings == nullptr) AdvancedSettings = new MenuClass(); if (CurrentMenu != AdvancedSettings) { CurrentMenu = AdvancedSettings; - SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_ADVANCED_SETTINGS)); // TODO: Chinese, English "Advanced Settings" JPG - DWINUI::MenuItemsPrepare(11); + SetMenuTitle({0}, GET_TEXT_F(MSG_ADVANCED_SETTINGS)); // TODO: Chinese, English "Advanced Settings" JPG + DWINUI::MenuItemsPrepare(12); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); #if HAS_HOME_OFFSET ADDMENUITEM(ICON_HomeOffset, GET_TEXT_F(MSG_SET_HOME_OFFSETS), onDrawSubMenu, Draw_HomeOffset_Menu); @@ -3283,7 +3283,7 @@ void Draw_Move_Menu() { if (MoveMenu == nullptr) MoveMenu = new MenuClass(); if (CurrentMenu != MoveMenu) { CurrentMenu = MoveMenu; - SetMenuTitle({192, 1, 42, 14}, {231, 2, 35, 11}, GET_TEXT_F(MSG_MOVE_AXIS)); + SetMenuTitle({192, 1, 42, 14}, GET_TEXT_F(MSG_MOVE_AXIS)); DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); ADDMENUITEM_P(ICON_MoveX, GET_TEXT_F(MSG_MOVE_X), onDrawMoveX, SetMoveX, ¤t_position.x); @@ -3303,7 +3303,7 @@ void Draw_Move_Menu() { if (HomeOffMenu == nullptr) HomeOffMenu = new MenuClass(); if (CurrentMenu != HomeOffMenu) { CurrentMenu = HomeOffMenu; - SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); // TODO: Chinese, English "Set Home Offsets" JPG + SetMenuTitle({0}, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); // TODO: Chinese, English "Set Home Offsets" JPG DWINUI::MenuItemsPrepare(4); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); ADDMENUITEM_P(ICON_HomeOffsetX, GET_TEXT_F(MSG_HOME_OFFSET_X), onDrawPFloatMenu, SetHomeOffsetX, &home_offset[X_AXIS]); @@ -3320,7 +3320,7 @@ void Draw_Move_Menu() { if (ProbeSetMenu == nullptr) ProbeSetMenu = new MenuClass(); if (CurrentMenu != ProbeSetMenu) { CurrentMenu = ProbeSetMenu; - SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_ZPROBE_SETTINGS)); // TODO: Chinese, English "Probe Settings" JPG + SetMenuTitle({0}, GET_TEXT_F(MSG_ZPROBE_SETTINGS)); // TODO: Chinese, English "Probe Settings" JPG DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); ADDMENUITEM_P(ICON_ProbeOffsetX, GET_TEXT_F(MSG_ZPROBE_XOFFSET), onDrawPFloatMenu, SetProbeOffsetX, &probe.offset.x); @@ -3364,7 +3364,7 @@ void Draw_SelectColors_Menu() { if (SelectColorMenu == nullptr) SelectColorMenu = new MenuClass(); if (CurrentMenu != SelectColorMenu) { CurrentMenu = SelectColorMenu; - SetMenuTitle({0}, {0}, F("Select Colors")); // TODO: Chinese, English "Select Color" JPG + SetMenuTitle({0}, F("Select Colors")); // TODO: Chinese, English "Select Color" JPG DWINUI::MenuItemsPrepare(20); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); ADDMENUITEM(ICON_StockConfiguration, GET_TEXT_F(MSG_RESTORE_DEFAULTS), onDrawMenuItem, RestoreDefaultsColors); @@ -3395,7 +3395,7 @@ void Draw_GetColor_Menu() { if (GetColorMenu == nullptr) GetColorMenu = new MenuClass(); if (CurrentMenu != GetColorMenu) { CurrentMenu = GetColorMenu; - SetMenuTitle({0}, {0}, F("Get Color")); // TODO: Chinese, English "Get Color" JPG + SetMenuTitle({0}, F("Get Color")); // TODO: Chinese, English "Get Color" JPG DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, DWIN_ApplyColor); ADDMENUITEM(ICON_Cancel, GET_TEXT_F(MSG_BUTTON_CANCEL), onDrawMenuItem, Draw_SelectColors_Menu); @@ -3412,7 +3412,7 @@ void Draw_Tune_Menu() { if (TuneMenu == nullptr) TuneMenu = new MenuClass(); if (CurrentMenu != TuneMenu) { CurrentMenu = TuneMenu; - SetMenuTitle({73, 2, 28, 12}, {94, 2, 33, 11}, GET_TEXT_F(MSG_TUNE)); // TODO: Chinese, English "Tune" JPG + SetMenuTitle({73, 2, 28, 12}, GET_TEXT_F(MSG_TUNE)); // TODO: Chinese, English "Tune" JPG DWINUI::MenuItemsPrepare(10); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_PrintProcess); ADDMENUITEM_P(ICON_Speed, GET_TEXT_F(MSG_SPEED), onDrawSpeedItem, SetSpeed, &feedrate_percentage); @@ -3445,7 +3445,7 @@ void Draw_Motion_Menu() { if (MotionMenu == nullptr) MotionMenu = new MenuClass(); if (CurrentMenu != MotionMenu) { CurrentMenu = MotionMenu; - SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_MOTION)); // TODO: Chinese, English "Motion" JPG + SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_MOTION)); // TODO: Chinese, English "Motion" JPG DWINUI::MenuItemsPrepare(6); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); ADDMENUITEM(ICON_MaxSpeed, GET_TEXT_F(MSG_SPEED), onDrawSpeed, Draw_MaxSpeed_Menu); @@ -3465,7 +3465,7 @@ void Draw_Motion_Menu() { if (FilamentMenu == nullptr) FilamentMenu = new MenuClass(); if (CurrentMenu != FilamentMenu) { CurrentMenu = FilamentMenu; - SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_FILAMENT_MAN)); // TODO: Chinese, English "Filament Management" JPG + SetMenuTitle({0}, GET_TEXT_F(MSG_FILAMENT_MAN)); // TODO: Chinese, English "Filament Management" JPG DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); ADDMENUITEM(ICON_Park, GET_TEXT_F(MSG_FILAMENT_PARK_ENABLED), onDrawMenuItem, ParkHead); @@ -3485,8 +3485,8 @@ void Draw_Motion_Menu() { if (ManualMesh == nullptr) ManualMesh = new MenuClass(); if (CurrentMenu != ManualMesh) { CurrentMenu = ManualMesh; - SetMenuTitle({0}, {0}, GET_TEXT_F(MSG_MANUAL_MESH)); // TODO: Chinese, English "Manual Mesh Leveling" JPG - DWINUI::MenuItemsPrepare(5); + SetMenuTitle({0}, GET_TEXT_F(MSG_MANUAL_MESH)); // TODO: Chinese, English "Manual Mesh Leveling" JPG + DWINUI::MenuItemsPrepare(6); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); ADDMENUITEM(ICON_ManualMesh, GET_TEXT_F(MSG_LEVEL_BED), onDrawMenuItem, ManualMeshStart); MMeshMoveZItem = ADDMENUITEM_P(ICON_Zoffset, GET_TEXT_F(MSG_MOVE_Z), onDrawMMeshMoveZ, SetMMeshMoveZ, ¤t_position.z); @@ -3500,11 +3500,11 @@ void Draw_Motion_Menu() { #if HAS_PREHEAT - void Draw_Preheat_Menu(frame_rect_t cn, frame_rect_t en, const __FlashStringHelper* fstr) { + void Draw_Preheat_Menu(frame_rect_t cn, const __FlashStringHelper* fstr) { checkkey = Menu; if (CurrentMenu != PreheatMenu) { CurrentMenu = PreheatMenu; - SetMenuTitle(cn, en, fstr); + SetMenuTitle(cn, fstr); DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Temperature_Menu); #if HAS_HOTEND @@ -3526,13 +3526,13 @@ void Draw_Motion_Menu() { void Draw_Preheat1_Menu() { HMI_value.Preheat = 0; if (PreheatMenu == nullptr) PreheatMenu = new MenuClass(); - Draw_Preheat_Menu({59, 16, 81, 14}, {56, 15, 85, 14}, F(PREHEAT_1_LABEL " Preheat Settings")); // TODO: English "PLA Settings" JPG + Draw_Preheat_Menu({59, 16, 81, 14}, F(PREHEAT_1_LABEL " Preheat Settings")); // TODO: English "PLA Settings" JPG } void Draw_Preheat2_Menu() { HMI_value.Preheat = 1; if (PreheatMenu == nullptr) PreheatMenu = new MenuClass(); - Draw_Preheat_Menu({142, 16, 82, 14}, {56, 15, 85, 14}, F(PREHEAT_2_LABEL " Preheat Settings")); // TODO: English "ABS Settings" JPG + Draw_Preheat_Menu({142, 16, 82, 14}, F(PREHEAT_2_LABEL " Preheat Settings")); // TODO: English "ABS Settings" JPG } #ifdef PREHEAT_3_LABEL @@ -3540,7 +3540,7 @@ void Draw_Motion_Menu() { HMI_value.Preheat = 2; if (PreheatMenu == nullptr) PreheatMenu = new MenuClass(); #define PREHEAT_3_TITLE PREHEAT_3_LABEL " Preheat Set." - Draw_Preheat_Menu({0}, {0}, F(PREHEAT_3_TITLE)); // TODO: Chinese, English "Custom Preheat Settings" JPG + Draw_Preheat_Menu({0}, F(PREHEAT_3_TITLE)); // TODO: Chinese, English "Custom Preheat Settings" JPG } #endif @@ -3551,7 +3551,7 @@ void Draw_Temperature_Menu() { if (TemperatureMenu == nullptr) TemperatureMenu = new MenuClass(); if (CurrentMenu != TemperatureMenu) { CurrentMenu = TemperatureMenu; - SetMenuTitle({236, 2, 28, 12}, {56, 15, 85, 14}, GET_TEXT_F(MSG_TEMPERATURE)); + SetMenuTitle({236, 2, 28, 12}, GET_TEXT_F(MSG_TEMPERATURE)); DWINUI::MenuItemsPrepare(7); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); #if HAS_HOTEND @@ -3579,7 +3579,7 @@ void Draw_MaxSpeed_Menu() { if (MaxSpeedMenu == nullptr) MaxSpeedMenu = new MenuClass(); if (CurrentMenu != MaxSpeedMenu) { CurrentMenu = MaxSpeedMenu; - SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_MAXSPEED)); + SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_MAXSPEED)); DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); ADDMENUITEM_P(ICON_MaxSpeedX, GET_TEXT_F(MSG_MAXSPEED_X), onDrawMaxSpeedX, SetMaxSpeedX, &planner.settings.max_feedrate_mm_s[X_AXIS]); @@ -3597,7 +3597,7 @@ void Draw_MaxAccel_Menu() { if (MaxAccelMenu == nullptr) MaxAccelMenu = new MenuClass(); if (CurrentMenu != MaxAccelMenu) { CurrentMenu = MaxAccelMenu; - SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_ACCELERATION)); + SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_ACCELERATION)); DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); ADDMENUITEM_P(ICON_MaxAccX, GET_TEXT_F(MSG_AMAX_A), onDrawMaxAccelX, SetMaxAccelX, &planner.settings.max_acceleration_mm_per_s2[X_AXIS]); @@ -3616,7 +3616,7 @@ void Draw_MaxAccel_Menu() { if (MaxJerkMenu == nullptr) MaxJerkMenu = new MenuClass(); if (CurrentMenu != MaxJerkMenu) { CurrentMenu = MaxJerkMenu; - SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_JERK)); + SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_JERK)); DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); ADDMENUITEM_P(ICON_MaxSpeedJerkX, GET_TEXT_F(MSG_VA_JERK), onDrawMaxJerkX, SetMaxJerkX, &planner.max_jerk[X_AXIS]); @@ -3635,7 +3635,7 @@ void Draw_Steps_Menu() { if (StepsMenu == nullptr) StepsMenu = new MenuClass(); if (CurrentMenu != StepsMenu) { CurrentMenu = StepsMenu; - SetMenuTitle({1, 16, 28, 13}, {144, 16, 46, 11}, GET_TEXT_F(MSG_STEPS_PER_MM)); + SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_STEPS_PER_MM)); DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); ADDMENUITEM_P(ICON_StepX, GET_TEXT_F(MSG_A_STEPS), onDrawStepsX, SetStepsX, &planner.settings.axis_steps_per_mm[X_AXIS]); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.h b/Marlin/src/lcd/e3v2/enhanced/dwin.h index 90b7ceacfa443..05b81c1019923 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.h @@ -24,8 +24,8 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.6.3 - * Date: 2021/09/08 + * Version: 3.7.1 + * Date: 2021/11/09 */ #include "../../../inc/MarlinConfigPre.h" @@ -154,6 +154,7 @@ void HMI_SDCardUpdate(); // Other void Goto_PrintProcess(); void Goto_Main_Menu(); +void Goto_InfoMenu(); void Draw_Select_Highlight(const bool sel); void Draw_Status_Area(const bool with_update); // Status Area void Draw_Main_Area(); // Redraw main area; diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp index 93477be0b8714..681b318a15e0b 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp @@ -23,8 +23,8 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.6.3 - * Date: 2021/09/08 + * Version: 3.7.1 + * Date: 2021/11/09 */ #include "../../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h index c49f23af45dba..43cb098b91389 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h @@ -24,8 +24,8 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.6.3 - * Date: 2021/09/08 + * Version: 3.7.1 + * Date: 2021/11/09 */ #include "../common/dwin_api.h" @@ -48,13 +48,6 @@ inline void DWIN_Draw_QR(uint8_t QR_Pixel, uint16_t x, uint16_t y, FSTR_P title) // x/y: Screen paste point void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); -// Copy area from virtual display area to current screen -// cacheID: virtual area number -// xStart/yStart: Upper-left of virtual area -// xEnd/yEnd: Lower-right of virtual area -// x/y: Screen paste point -void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); - // Copy area from current virtual display area to current screen // xStart/yStart: Upper-left of virtual area // xEnd/yEnd: Lower-right of virtual area diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp index 6c46eb31f1051..824aca07f8661 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp @@ -23,8 +23,8 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.6.3 - * Date: 2021/09/08 + * Version: 3.7.1 + * Date: 2021/11/09 */ #include "../../../inc/MarlinConfigPre.h" @@ -38,8 +38,8 @@ //#define DEBUG_OUT 1 #include "../../../core/debug_out.h" -uint8_t MenuItemTotal = 0; -uint8_t MenuItemCount = 0; +int8_t MenuItemTotal = 0; +int8_t MenuItemCount = 0; MenuItemClass** MenuItems = nullptr; MenuClass *CurrentMenu = nullptr; MenuClass *PreviousMenu = nullptr; @@ -50,8 +50,8 @@ uint16_t DWINUI::textcolor = Def_Text_Color; uint16_t DWINUI::backcolor = Def_Background_Color; uint8_t DWINUI::font = font8x16; -void (*DWINUI::onCursorErase)(uint8_t line)=nullptr; -void (*DWINUI::onCursorDraw)(uint8_t line)=nullptr; +void (*DWINUI::onCursorErase)(const int8_t line)=nullptr; +void (*DWINUI::onCursorDraw)(const int8_t line)=nullptr; void (*DWINUI::onTitleDraw)(TitleClass* title)=nullptr; void (*DWINUI::onMenuDraw)(MenuClass* menu)=nullptr; @@ -304,14 +304,14 @@ void DWINUI::ClearMenuArea() { void DWINUI::MenuItemsClear() { if (MenuItems == nullptr) return; - for (uint8_t i = 0; i < MenuItemCount; i++) delete MenuItems[i]; + for (int8_t i = 0; i < MenuItemCount; i++) delete MenuItems[i]; delete[] MenuItems; MenuItems = nullptr; MenuItemCount = 0; MenuItemTotal = 0; } -void DWINUI::MenuItemsPrepare(uint8_t totalitems) { +void DWINUI::MenuItemsPrepare(int8_t totalitems) { MenuItemsClear(); MenuItemTotal = totalitems; MenuItems = new MenuItemClass*[totalitems]; @@ -379,7 +379,7 @@ MenuClass::MenuClass() { void MenuClass::draw() { MenuTitle.draw(); if (DWINUI::onMenuDraw != nullptr) (*DWINUI::onMenuDraw)(this); - for (uint8_t i = 0; i < MenuItemCount; i++) + for (int8_t i = 0; i < MenuItemCount; i++) MenuItems[i]->draw(i - topline); if (DWINUI::onCursorDraw != nullptr) DWINUI::onCursorDraw(line()); DWIN_UpdateLCD(); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.h b/Marlin/src/lcd/e3v2/enhanced/dwinui.h index 8cbb66fdf0416..078b3cc58bf4a 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.h @@ -24,11 +24,10 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.6.3 - * Date: 2021/09/08 + * Version: 3.7.1 + * Date: 2021/11/09 */ -#include "../../../core/types.h" #include "dwin_lcd.h" #include "../common/dwin_set.h" #include "../common/dwin_font.h" @@ -138,7 +137,7 @@ extern TitleClass Title; class MenuItemClass { protected: public: - uint8_t pos = 0; + int8_t pos = 0; uint8_t icon = 0; char caption[32] = ""; uint8_t frameid = 0; @@ -185,8 +184,8 @@ namespace DWINUI { extern uint16_t backcolor; extern uint8_t font; - extern void (*onCursorErase)(uint8_t line); - extern void (*onCursorDraw)(uint8_t line); + extern void (*onCursorErase)(const int8_t line); + extern void (*onCursorDraw)(const int8_t line); extern void (*onTitleDraw)(TitleClass* title); extern void (*onMenuDraw)(MenuClass* menu); @@ -342,6 +341,12 @@ namespace DWINUI { // rlimit: For draw less chars than string length use rlimit void Draw_String(const char * const string, uint16_t rlimit = 0xFFFF); void Draw_String(uint16_t color, const char * const string, uint16_t rlimit = 0xFFFF); + inline void Draw_String(FSTR_P string, uint16_t rlimit = 0xFFFF) { + Draw_String(FTOP(string), rlimit); + } + inline void Draw_String(uint16_t color, FSTR_P string, uint16_t rlimit = 0xFFFF) { + Draw_String(color, FTOP(string), rlimit); + } // Draw a string // size: Font size @@ -353,25 +358,25 @@ namespace DWINUI { DWIN_Draw_String(false, font, textcolor, backcolor, x, y, string); } inline void Draw_String(uint16_t x, uint16_t y, FSTR_P title) { - DWIN_Draw_String(false, font, textcolor, backcolor, x, y, (char *)title); + DWIN_Draw_String(false, font, textcolor, backcolor, x, y, FTOP(title)); } inline void Draw_String(uint16_t color, uint16_t x, uint16_t y, const char * const string) { DWIN_Draw_String(false, font, color, backcolor, x, y, string); } inline void Draw_String(uint16_t color, uint16_t x, uint16_t y, FSTR_P title) { - DWIN_Draw_String(false, font, color, backcolor, x, y, (char *)title); + DWIN_Draw_String(false, font, color, backcolor, x, y, title); } inline void Draw_String(uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, const char * const string) { DWIN_Draw_String(true, font, color, bgcolor, x, y, string); } inline void Draw_String(uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, FSTR_P title) { - DWIN_Draw_String(true, font, color, bgcolor, x, y, (char *)title); + DWIN_Draw_String(true, font, color, bgcolor, x, y, title); } inline void Draw_String(uint8_t size, uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, const char * const string) { DWIN_Draw_String(true, size, color, bgcolor, x, y, string); } inline void Draw_String(uint8_t size, uint16_t color, uint16_t bgcolor, uint16_t x, uint16_t y, FSTR_P title) { - DWIN_Draw_String(true, size, color, bgcolor, x, y, (char *)title); + DWIN_Draw_String(true, size, color, bgcolor, x, y, title); } // Draw a centered string using DWIN_WIDTH @@ -382,8 +387,8 @@ namespace DWINUI { // y: Upper coordinate of the string // *string: The string void Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, const char * const string); - inline void Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, FSTR_P title) { - Draw_CenteredString(bShow, size, color, bColor, y, (char *)title); + inline void Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, FSTR_P string) { + Draw_CenteredString(bShow, size, color, bColor, y, FTOP(string)); } inline void Draw_CenteredString(uint16_t color, uint16_t bcolor, uint16_t y, const char * const string) { Draw_CenteredString(true, font, color, bcolor, y, string); @@ -392,19 +397,19 @@ namespace DWINUI { Draw_CenteredString(false, size, color, backcolor, y, string); } inline void Draw_CenteredString(uint8_t size, uint16_t color, uint16_t y, FSTR_P title) { - Draw_CenteredString(false, size, color, backcolor, y, (char *)title); + Draw_CenteredString(false, size, color, backcolor, y, title); } inline void Draw_CenteredString(uint16_t color, uint16_t y, const char * const string) { Draw_CenteredString(false, font, color, backcolor, y, string); } inline void Draw_CenteredString(uint16_t color, uint16_t y, FSTR_P title) { - Draw_CenteredString(false, font, color, backcolor, y, (char *)title); + Draw_CenteredString(false, font, color, backcolor, y, title); } inline void Draw_CenteredString(uint16_t y, const char * const string) { Draw_CenteredString(false, font, textcolor, backcolor, y, string); } inline void Draw_CenteredString(uint16_t y, FSTR_P title) { - Draw_CenteredString(false, font, textcolor, backcolor, y, (char *)title); + Draw_CenteredString(false, font, textcolor, backcolor, y, title); } // Draw a circle @@ -477,7 +482,7 @@ namespace DWINUI { void MenuItemsClear(); // Prepare MenuItems array - void MenuItemsPrepare(uint8_t totalitems); + void MenuItemsPrepare(int8_t totalitems); // Add elements to the MenuItems array MenuItemClass* MenuItemsAdd(MenuItemClass* menuitem); diff --git a/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp b/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp index 8d6b5fa2c084b..3824d63b2b48d 100644 --- a/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp @@ -1,8 +1,8 @@ /** * DWIN Mesh Viewer * Author: Miguel A. Risco-Castillo - * version: 2.5 - * Date: 2021/09/27 + * version: 3.8.1 + * Date: 2021/11/06 * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU Lesser General Public License as @@ -35,13 +35,15 @@ MeshViewerClass MeshViewer; void MeshViewerClass::Draw() { - const int8_t mx = 30, my = 30; // Margins + const int8_t mx = 25, my = 25; // Margins const int16_t stx = (DWIN_WIDTH - 2 * mx) / (GRID_MAX_POINTS_X - 1), // Steps sty = (DWIN_WIDTH - 2 * my) / (GRID_MAX_POINTS_Y - 1); - int8_t zmesh[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y], maxz =-127, minz = 127; + const int8_t rmax = _MIN(mx - 2, stx / 2); + const int8_t rmin = 7; + int16_t zmesh[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y], maxz =-32000, minz = 32000; #define px(xp) (mx + (xp) * stx) #define py(yp) (30 + DWIN_WIDTH - my - (yp) * sty) - #define rm(z) ((((z) - minz) * 10 / _MAX(1, (maxz - minz))) + 10) + #define rm(z) ((z - minz) * (rmax - rmin) / _MAX(1, (maxz - minz)) + rmin) #define DrawMeshValue(xp, yp, zv) DWINUI::Draw_Signed_Float(font6x12, 1, 2, px(xp) - 12, py(yp) - 6, zv) #define DrawMeshHLine(yp) DWIN_Draw_HLine(HMI_data.SplitLine_Color, px(0), py(yp), DWIN_WIDTH - 2 * mx) #define DrawMeshVLine(xp) DWIN_Draw_VLine(HMI_data.SplitLine_Color, px(xp), py(GRID_MAX_POINTS_Y - 1), DWIN_WIDTH - 2 * my) @@ -61,8 +63,33 @@ void MeshViewerClass::Draw() { watchdog_refresh(); LOOP_L_N(x, GRID_MAX_POINTS_X) { uint16_t color = DWINUI::RainbowInt(zmesh[x][y], _MIN(-5, minz), _MAX(5, maxz)); - DWINUI::Draw_FillCircle(color, px(x), py(y), rm(zmesh[x][y])); - DrawMeshValue(x, y, Z_VALUES(x,y)); + uint8_t radius = rm(zmesh[x][y]); + DWINUI::Draw_FillCircle(color, px(x), py(y), radius); + if (GRID_MAX_POINTS_X < 9) + DWINUI::Draw_Signed_Float(font6x12, 1, 2, px(x) - 12, py(y) - 6, Z_VALUES(x,y)); + else { + char str_1[9]; + str_1[0] = 0; + switch (zmesh[x][y]) { + case -999 ... -100: + DWINUI::Draw_Signed_Float(font6x12, 1, 1, px(x) - 12, py(y) - 6, Z_VALUES(x,y)); + break; + case -99 ... -1: + sprintf_P(str_1, PSTR("-.%02i"), -zmesh[x][y]); + break; + case 0: + DWIN_Draw_String(false, font6x12, DWINUI::textcolor, DWINUI::backcolor, px(x) - 4, py(y) - 6, "0");; + break; + case 1 ... 99: + sprintf_P(str_1, PSTR(".%02i"), zmesh[x][y]); + break; + case 100 ... 999: + DWINUI::Draw_Signed_Float(font6x12, 1, 1, px(x) - 12, py(y) - 6, Z_VALUES(x,y)); + break; + } + if (str_1[0]) + DWIN_Draw_String(false, font6x12, DWINUI::textcolor, DWINUI::backcolor, px(x) - 12, py(y) - 6, str_1); + } } } char str_1[6], str_2[6] = ""; diff --git a/Marlin/src/lcd/e3v2/enhanced/meshviewer.h b/Marlin/src/lcd/e3v2/enhanced/meshviewer.h index 4f7a6ae1d25fe..0ba6ae2d7d158 100644 --- a/Marlin/src/lcd/e3v2/enhanced/meshviewer.h +++ b/Marlin/src/lcd/e3v2/enhanced/meshviewer.h @@ -1,8 +1,8 @@ /** * DWIN Mesh Viewer * Author: Miguel A. Risco-Castillo - * version: 2.5 - * Date: 2021/09/27 + * Version: 3.8.1 + * Date: 2021/11/06 * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU Lesser General Public License as diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index f4eba776b608c..0cb29f29e0f16 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -3044,8 +3044,6 @@ void MarlinSettings::reset() { postprocess(); DEBUG_ECHO_MSG("Hardcoded Default Settings Loaded"); - - TERN_(EXTENSIBLE_UI, ExtUI::onFactoryReset()); } #if DISABLED(DISABLE_M503) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index cef348c5f9856..48941532c8a0c 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -3731,8 +3731,9 @@ void Temperature::isr() { HMI_flag.heat_flag = 0; duration_t elapsed = print_job_timer.duration(); // print timer dwin_heat_time = elapsed.value; + #else + ui.reset_status(); #endif - ui.reset_status(); TERN_(PRINTER_EVENT_LEDS, printerEventLEDs.onHeatingDone()); return true; } From ecd4cdb2983e6eb0d2f6a112f1706b0e7c158ec2 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 11 Nov 2021 01:01:59 +0000 Subject: [PATCH 045/273] [cron] Bump distribution date (2021-11-11) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 0f2136cbddbcb..6d97693cd1732 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 "2021-11-10" +//#define STRING_DISTRIBUTION_DATE "2021-11-11" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e61948958d9ba..3b5f97d1c4e69 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 "2021-11-10" + #define STRING_DISTRIBUTION_DATE "2021-11-11" #endif /** From 72de764488b96a28d44668e0f246fa86cbadcb0a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 12 Nov 2021 01:02:28 +0000 Subject: [PATCH 046/273] [cron] Bump distribution date (2021-11-12) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 6d97693cd1732..1643741f49775 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 "2021-11-11" +//#define STRING_DISTRIBUTION_DATE "2021-11-12" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3b5f97d1c4e69..badb7231e0bd2 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 "2021-11-11" + #define STRING_DISTRIBUTION_DATE "2021-11-12" #endif /** From 4a840e15e160038b139131ec559b220e0ac4318e Mon Sep 17 00:00:00 2001 From: Skruppy Date: Fri, 12 Nov 2021 15:57:24 +0100 Subject: [PATCH 047/273] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20RGB=20case=20light?= =?UTF-8?q?=20compile=20(#23108)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/caselight.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index 7c4755d0b585b..59832fd6edd7c 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -39,7 +39,6 @@ CaseLight caselight; bool CaseLight::on = CASE_LIGHT_DEFAULT_ON; #if CASE_LIGHT_IS_COLOR_LED - #include "leds/leds.h" constexpr uint8_t init_case_light[] = CASE_LIGHT_DEFAULT_COLOR; LEDColor CaseLight::color = { init_case_light[0], init_case_light[1], init_case_light[2] OPTARG(HAS_WHITE_LED, init_case_light[3]) }; #endif @@ -65,7 +64,7 @@ void CaseLight::update(const bool sflag) { #endif #if CASE_LIGHT_IS_COLOR_LED - leds.set_color(LEDColor(color.r, color.g, color.b OPTARG(HAS_WHITE_LED, color.w), n10ct)); + leds.set_color(LEDColor(color.r, color.g, color.b OPTARG(HAS_WHITE_LED, color.w) OPTARG(NEOPIXEL_LED, n10ct))); #else // !CASE_LIGHT_IS_COLOR_LED #if CASELIGHT_USES_BRIGHTNESS From 649c7685bf3c06b7faf39400538831b76e24d392 Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Fri, 12 Nov 2021 12:14:28 -0600 Subject: [PATCH 048/273] =?UTF-8?q?=F0=9F=90=9B=20[LCP1768]=20Init=20PWM?= =?UTF-8?q?=20in=20set=5Fpwm=5Fduty=20(#23110)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/fast_pwm.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp index 70fc0e333d115..197abb33101b3 100644 --- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp +++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp @@ -25,7 +25,9 @@ #include void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { - LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size); + if (!LPC176x::pin_is_valid(pin)) return; + if (LPC176x::pwm_attach_pin(pin)) + LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size); // map 1-254 onto PWM range } #if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM From 4aa2c6628f05ad60001e66a87e3f52e26c0998c9 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Fri, 12 Nov 2021 21:26:19 +0100 Subject: [PATCH 049/273] =?UTF-8?q?=F0=9F=8E=A8=20MPX=20ARM=20Mini=20pins?= =?UTF-8?q?=20cleanup=20(#23113)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h | 32 ++++++------------- 1 file changed, 10 insertions(+), 22 deletions(-) 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 3fed0adac336d..87526bac87977 100644 --- a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h @@ -22,16 +22,16 @@ #pragma once /** - * MKS Robin mini (STM32F103VET6) board pin assignments + * MPX ARM MINI (STM32F103ZET6) board pin assignments */ #if NOT_TARGET(STM32F1, STM32F1xx) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#elif HOTENDS > 2 || E_STEPPERS > 2 - #error "MKS Robin supports up to 2 hotends / E-steppers. Comment out this line to continue." +#elif HOTENDS > 1 || E_STEPPERS > 1 + #error "MPX ARM Mini only supports one hotend / E-stepper. Comment out this line to continue." #endif -#define BOARD_INFO_NAME "Mingda MPX_ARM_MINI" +#define BOARD_INFO_NAME "Mingda MPX ARM Mini" #define BOARD_NO_NATIVE_USB #define DISABLE_DEBUG @@ -64,9 +64,9 @@ // Limit Switches // #define X_MIN_PIN PD6 -#define X_MAX_PIN PG15 +#define X_MAX_PIN PG15 // To double check #define Y_MIN_PIN PG9 -#define Y_MAX_PIN PG14 +#define Y_MAX_PIN PG14 // To double check #define Z_MIN_PIN PG10 #define Z_MAX_PIN PG13 @@ -137,18 +137,6 @@ // TFT with FSMC interface // #if HAS_FSMC_TFT - /** - * Note: MKS Robin TFT screens use various TFT controllers - * Supported screens are based on the ILI9341, ST7789V and ILI9328 (320x240) - * ILI9488 is not supported - * Define init sequences for other screens in u8g_dev_tft_320x240_upscale_from_128x64.cpp - * - * If the screen stays white, disable 'TFT_RESET_PIN' - * to let the bootloader init the screen. - * - * Setting an 'TFT_RESET_PIN' may cause a flicker when entering the LCD menu - * because Marlin uses the reset as a failsafe to revive a glitchy LCD. - */ #define TFT_RESET_PIN PF15 #define TFT_BACKLIGHT_PIN PF11 @@ -166,8 +154,8 @@ #endif #if NEED_TOUCH_PINS - #define TOUCH_CS_PIN PA4 // SPI2_NSS - #define TOUCH_SCK_PIN PA5 // SPI2_SCK - #define TOUCH_MISO_PIN PA6 // SPI2_MISO - #define TOUCH_MOSI_PIN PA7 // SPI2_MOSI + #define TOUCH_CS_PIN PA4 // SPI1_NSS + #define TOUCH_SCK_PIN PA5 // SPI1_SCK + #define TOUCH_MISO_PIN PA6 // SPI1_MISO + #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI #endif From d89f472a4f5bc58d083698955a8cdcc1c6d7f956 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 13 Nov 2021 00:59:50 +0000 Subject: [PATCH 050/273] [cron] Bump distribution date (2021-11-13) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 1643741f49775..f4cb9e1600fe2 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 "2021-11-12" +//#define STRING_DISTRIBUTION_DATE "2021-11-13" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index badb7231e0bd2..be48e253ba536 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 "2021-11-12" + #define STRING_DISTRIBUTION_DATE "2021-11-13" #endif /** From 5fa4631e375968dddbca5b584eabeb917a679464 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 14 Nov 2021 01:03:14 +0000 Subject: [PATCH 051/273] [cron] Bump distribution date (2021-11-14) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index f4cb9e1600fe2..b2150960b9ed9 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 "2021-11-13" +//#define STRING_DISTRIBUTION_DATE "2021-11-14" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index be48e253ba536..ed67ecef8427c 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 "2021-11-13" + #define STRING_DISTRIBUTION_DATE "2021-11-14" #endif /** From 8ee368b718ea7086522f9d64dc97e45a273d6832 Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Sun, 14 Nov 2021 05:55:31 -0600 Subject: [PATCH 052/273] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Controller=20Fan?= =?UTF-8?q?=20software=20PWM=20(etc.)=20(#23102)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/HAL/AVR/fast_pwm.cpp | 42 ++++----------------- Marlin/src/HAL/AVR/fastio.h | 30 ++++++--------- Marlin/src/HAL/AVR/inc/SanityCheck.h | 2 +- Marlin/src/HAL/AVR/pinsDebug.h | 43 +++++++++++----------- Marlin/src/feature/controllerfan.cpp | 12 ++++-- Marlin/src/lcd/menu/menu_configuration.cpp | 4 +- Marlin/src/module/temperature.cpp | 19 ++++++++++ Marlin/src/module/temperature.h | 4 ++ 8 files changed, 76 insertions(+), 80 deletions(-) diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index 2556fa0441212..cbe4fed94a05f 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -54,8 +54,8 @@ Timer get_pwm_timer(const pin_t pin) { case TIMER1A: case TIMER1B: #endif break; - #if defined(TCCR2) || defined(TCCR2A) - #ifdef TCCR2 + #if HAS_TCCR2 || defined(TCCR2A) + #if HAS_TCCR2 case TIMER2: { Timer timer = { /*TCCRnQ*/ { &TCCR2, nullptr, nullptr }, @@ -200,16 +200,7 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { res = res_temp_fast; j = i; // Set the Wave Generation Mode to FAST PWM - if (timer.n == 2) { - wgm = ( - #if ENABLED(USE_OCR2A_AS_TOP) - WGM2_FAST_PWM_OCR2A - #else - WGM2_FAST_PWM - #endif - ); - } - else wgm = WGM_FAST_PWM_ICRn; + wgm = timer.n == 2 ? TERN(USE_OCR2A_AS_TOP, WGM2_FAST_PWM_OCR2A, WGM2_FAST_PWM) : WGM_FAST_PWM_ICRn; } // If PHASE CORRECT values are closes to desired f else if (f_phase_diff < f_diff) { @@ -217,16 +208,7 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { res = res_temp_phase_correct; j = i; // Set the Wave Generation Mode to PWM PHASE CORRECT - if (timer.n == 2) { - wgm = ( - #if ENABLED(USE_OCR2A_AS_TOP) - WGM2_PWM_PC_OCR2A - #else - WGM2_PWM_PC - #endif - ); - } - else wgm = WGM_PWM_PC_ICRn; + wgm = timer.n == 2 ? TERN(USE_OCR2A_AS_TOP, WGM2_PWM_PC_OCR2A, WGM2_PWM_PC) : WGM_PWM_PC_ICRn; } } } @@ -234,9 +216,7 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { _SET_CSn(timer.TCCRnQ, j); if (timer.n == 2) { - #if ENABLED(USE_OCR2A_AS_TOP) - _SET_OCRnQ(timer.OCRnQ, 0, res); // Set OCR2A value (TOP) = res - #endif + TERN_(USE_OCR2A_AS_TOP, _SET_OCRnQ(timer.OCRnQ, 0, res)); // Set OCR2A value (TOP) = res } else _SET_ICRn(timer.ICRn, res); // Set ICRn value (TOP) = res @@ -257,15 +237,9 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 Timer timer = get_pwm_timer(pin); if (timer.n == 0) return; // Don't proceed if protected timer or not recognized // Set compare output mode to CLEAR -> SET or SET -> CLEAR (if inverted) - _SET_COMnQ(timer.TCCRnQ, (timer.q - #ifdef TCCR2 - + (timer.q == 2) // COM20 is on bit 4 of TCCR2, thus requires q + 1 in the macro - #endif - ), COM_CLEAR_SET + invert - ); - - uint16_t top = (timer.n == 2) ? TERN(USE_OCR2A_AS_TOP, *timer.OCRnQ[0], 255) : *timer.ICRn; - _SET_OCRnQ(timer.OCRnQ, timer.q, (v * top + v_size / 2) / v_size); // Scale 8/16-bit v to top value + _SET_COMnQ(timer.TCCRnQ, timer.q TERN_(HAS_TCCR2, + (timer.q == 2)), COM_CLEAR_SET + invert); // COM20 is on bit 4 of TCCR2, so +1 for q==2 + const uint16_t top = timer.n == 2 ? TERN(USE_OCR2A_AS_TOP, *timer.OCRnQ[0], 255) : *timer.ICRn; + _SET_OCRnQ(timer.OCRnQ, timer.q, uint16_t(uint32_t(v) * top / v_size)); // Scale 8/16-bit v to top value } #else diff --git a/Marlin/src/HAL/AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h index f77d4f666c7db..db6e598b86705 100644 --- a/Marlin/src/HAL/AVR/fastio.h +++ b/Marlin/src/HAL/AVR/fastio.h @@ -211,32 +211,32 @@ enum ClockSource2 : char { // Set Clock Select bits // Ex: SET_CS3(PRESCALER_64); +#ifdef TCCR2 + #define HAS_TCCR2 1 +#endif #define _SET_CS(T,V) (TCCR##T##B = (TCCR##T##B & ~(0x7 << CS##T##0)) | ((int(V) & 0x7) << CS##T##0)) #define _SET_CS0(V) _SET_CS(0,V) #define _SET_CS1(V) _SET_CS(1,V) -#ifdef TCCR2 - #define _SET_CS2(V) (TCCR2 = (TCCR2 & ~(0x7 << CS20)) | (int(V) << CS20)) -#else - #define _SET_CS2(V) _SET_CS(2,V) -#endif #define _SET_CS3(V) _SET_CS(3,V) #define _SET_CS4(V) _SET_CS(4,V) #define _SET_CS5(V) _SET_CS(5,V) #define SET_CS0(V) _SET_CS0(CS_##V) #define SET_CS1(V) _SET_CS1(CS_##V) -#ifdef TCCR2 + +#if HAS_TCCR2 + #define _SET_CS2(V) (TCCR2 = (TCCR2 & ~(0x7 << CS20)) | (int(V) << CS20)) #define SET_CS2(V) _SET_CS2(CS2_##V) #else + #define _SET_CS2(V) _SET_CS(2,V) #define SET_CS2(V) _SET_CS2(CS_##V) #endif + #define SET_CS3(V) _SET_CS3(CS_##V) #define SET_CS4(V) _SET_CS4(CS_##V) #define SET_CS5(V) _SET_CS5(CS_##V) #define SET_CS(T,V) SET_CS##T(V) // Runtime (see set_pwm_frequency) -#define _SET_CSn(TCCRnQ, V) do{ \ - (*(TCCRnQ)[1] = (*(TCCRnQ[1]) & ~(0x7 << 0)) | ((int(V) & 0x7) << 0)); \ - }while(0) +#define _SET_CSn(TCCRnQ, V) (*(TCCRnQ)[1] = (*(TCCRnQ[1]) & ~(0x7 << 0)) | ((int(V) & 0x7) << 0)) // Set Compare Mode bits // Ex: SET_COMS(4,CLEAR_SET,CLEAR_SET,CLEAR_SET); @@ -247,21 +247,15 @@ enum ClockSource2 : char { #define SET_COMC(T,V) SET_COM(T,C,V) #define SET_COMS(T,V1,V2,V3) do{ SET_COMA(T,V1); SET_COMB(T,V2); SET_COMC(T,V3); }while(0) // Runtime (see set_pwm_duty) -#define _SET_COMnQ(TCCRnQ, Q, V) do{ \ - (*(TCCRnQ)[0] = (*(TCCRnQ)[0] & ~(0x3 << (6-2*(Q)))) | (int(V) << (6-2*(Q)))); \ - }while(0) +#define _SET_COMnQ(TCCRnQ, Q, V) (*(TCCRnQ)[0] = (*(TCCRnQ)[0] & ~(0x3 << (6-2*(Q)))) | (int(V) << (6-2*(Q)))) // Set OCRnQ register // Runtime (see set_pwm_duty): -#define _SET_OCRnQ(OCRnQ, Q, V) do{ \ - (*(OCRnQ)[(Q)] = (0x0000) | (int(V) & 0xFFFF)); \ - }while(0) +#define _SET_OCRnQ(OCRnQ, Q, V) (*(OCRnQ)[Q] = int(V) & 0xFFFF) // Set ICRn register (one per timer) // Runtime (see set_pwm_frequency) -#define _SET_ICRn(ICRn, V) do{ \ - (*(ICRn) = (0x0000) | (int(V) & 0xFFFF)); \ - }while(0) +#define _SET_ICRn(ICRn, V) (*(ICRn) = int(V) & 0xFFFF) // Set Noise Canceler bit // Ex: SET_ICNC(2,1) diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h index 79809b8f618d1..2f80d1fee165c 100644 --- a/Marlin/src/HAL/AVR/inc/SanityCheck.h +++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h @@ -28,7 +28,7 @@ /** * Checks for FAST PWM */ -#if ENABLED(FAST_PWM_FAN) && (ENABLED(USE_OCR2A_AS_TOP) && defined(TCCR2)) +#if ALL(FAST_PWM_FAN, USE_OCR2A_AS_TOP, HAS_TCCR2) #error "USE_OCR2A_AS_TOP does not apply to devices with a single output TIMER2" #endif diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index fcbb7af3e17e3..0f564df987f39 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -102,7 +102,7 @@ void PRINT_ARRAY_NAME(uint8_t x) { return true; \ } else return false - +#define ABTEST(N) defined(TCCR##N##A) && defined(COM##N##A1) /** * Print a pin's PWM status. @@ -113,7 +113,7 @@ static bool pwm_status(uint8_t pin) { switch (digitalPinToTimer_DEBUG(pin)) { - #if defined(TCCR0A) && defined(COM0A1) + #if ABTEST(0) #ifdef TIMER0A #if !AVR_AT90USB1286_FAMILY // not available in Teensyduino type IDEs PWM_CASE(0, A); @@ -122,20 +122,20 @@ static bool pwm_status(uint8_t pin) { PWM_CASE(0, B); #endif - #if defined(TCCR1A) && defined(COM1A1) + #if ABTEST(1) PWM_CASE(1, A); PWM_CASE(1, B); - #if defined(COM1C1) && defined(TIMER1C) - PWM_CASE(1, C); - #endif + #if defined(COM1C1) && defined(TIMER1C) + PWM_CASE(1, C); + #endif #endif - #if defined(TCCR2A) && defined(COM2A1) + #if ABTEST(2) PWM_CASE(2, A); PWM_CASE(2, B); #endif - #if defined(TCCR3A) && defined(COM3A1) + #if ABTEST(3) PWM_CASE(3, A); PWM_CASE(3, B); #ifdef COM3C1 @@ -149,7 +149,7 @@ static bool pwm_status(uint8_t pin) { PWM_CASE(4, C); #endif - #if defined(TCCR5A) && defined(COM5A1) + #if ABTEST(5) PWM_CASE(5, A); PWM_CASE(5, B); PWM_CASE(5, C); @@ -166,16 +166,16 @@ static bool pwm_status(uint8_t pin) { const volatile uint8_t* const PWM_other[][3] PROGMEM = { { &TCCR0A, &TCCR0B, &TIMSK0 }, { &TCCR1A, &TCCR1B, &TIMSK1 }, - #if defined(TCCR2A) && defined(COM2A1) + #if ABTEST(2) { &TCCR2A, &TCCR2B, &TIMSK2 }, #endif - #if defined(TCCR3A) && defined(COM3A1) + #if ABTEST(3) { &TCCR3A, &TCCR3B, &TIMSK3 }, #endif #ifdef TCCR4A { &TCCR4A, &TCCR4B, &TIMSK4 }, #endif - #if defined(TCCR5A) && defined(COM5A1) + #if ABTEST(5) { &TCCR5A, &TCCR5B, &TIMSK5 }, #endif }; @@ -195,11 +195,11 @@ const volatile uint8_t* const PWM_OCR[][3] PROGMEM = { { (const uint8_t*)&OCR1A, (const uint8_t*)&OCR1B, 0 }, #endif - #if defined(TCCR2A) && defined(COM2A1) + #if ABTEST(2) { &OCR2A, &OCR2B, 0 }, #endif - #if defined(TCCR3A) && defined(COM3A1) + #if ABTEST(3) #ifdef COM3C1 { (const uint8_t*)&OCR3A, (const uint8_t*)&OCR3B, (const uint8_t*)&OCR3C }, #else @@ -211,7 +211,7 @@ const volatile uint8_t* const PWM_OCR[][3] PROGMEM = { { (const uint8_t*)&OCR4A, (const uint8_t*)&OCR4B, (const uint8_t*)&OCR4C }, #endif - #if defined(TCCR5A) && defined(COM5A1) + #if ABTEST(5) { (const uint8_t*)&OCR5A, (const uint8_t*)&OCR5B, (const uint8_t*)&OCR5C }, #endif }; @@ -281,7 +281,7 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - static void pwm_details(uint8_t pin) { switch (digitalPinToTimer_DEBUG(pin)) { - #if defined(TCCR0A) && defined(COM0A1) + #if ABTEST(0) #ifdef TIMER0A #if !AVR_AT90USB1286_FAMILY // not available in Teensyduino type IDEs case TIMER0A: timer_prefix(0, 'A', 3); break; @@ -290,7 +290,7 @@ static void pwm_details(uint8_t pin) { case TIMER0B: timer_prefix(0, 'B', 3); break; #endif - #if defined(TCCR1A) && defined(COM1A1) + #if ABTEST(1) case TIMER1A: timer_prefix(1, 'A', 4); break; case TIMER1B: timer_prefix(1, 'B', 4); break; #if defined(COM1C1) && defined(TIMER1C) @@ -298,12 +298,12 @@ static void pwm_details(uint8_t pin) { #endif #endif - #if defined(TCCR2A) && defined(COM2A1) + #if ABTEST(2) case TIMER2A: timer_prefix(2, 'A', 3); break; case TIMER2B: timer_prefix(2, 'B', 3); break; #endif - #if defined(TCCR3A) && defined(COM3A1) + #if ABTEST(3) case TIMER3A: timer_prefix(3, 'A', 4); break; case TIMER3B: timer_prefix(3, 'B', 4); break; #ifdef COM3C1 @@ -317,7 +317,7 @@ static void pwm_details(uint8_t pin) { case TIMER4C: timer_prefix(4, 'C', 4); break; #endif - #if defined(TCCR5A) && defined(COM5A1) + #if ABTEST(5) case TIMER5A: timer_prefix(5, 'A', 4); break; case TIMER5B: timer_prefix(5, 'B', 4); break; case TIMER5C: timer_prefix(5, 'C', 4); break; @@ -351,7 +351,6 @@ static void pwm_details(uint8_t pin) { #endif } // pwm_details - #ifndef digitalRead_mod // Use Teensyduino's version of digitalRead - it doesn't disable the PWMs int digitalRead_mod(const int8_t pin) { // same as digitalRead except the PWM stop section has been removed const uint8_t port = digitalPinToPort_DEBUG(pin); @@ -397,3 +396,5 @@ static void pwm_details(uint8_t pin) { #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) + +#undef ABTEST diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index 330f3914f6c0c..59ba665e11144 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -72,10 +72,14 @@ void ControllerFan::update() { ? settings.active_speed : settings.idle_speed ); - if (PWM_PIN(CONTROLLER_FAN_PIN)) - set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); - else - WRITE(CONTROLLER_FAN_PIN, speed); + #if ENABLED(FAN_SOFT_PWM) + thermalManager.soft_pwm_controller_speed = speed; + #else + if (PWM_PIN(CONTROLLER_FAN_PIN)) + set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); + else + WRITE(CONTROLLER_FAN_PIN, speed > 0); + #endif } } diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 6d6b0228fb406..b976224b8c534 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -266,10 +266,10 @@ void menu_advanced_settings(); void menu_controller_fan() { START_MENU(); BACK_ITEM(MSG_CONFIGURATION); - EDIT_ITEM_FAST(percent, MSG_CONTROLLER_FAN_IDLE_SPEED, &controllerFan.settings.idle_speed, _MAX(1, CONTROLLERFAN_SPEED_MIN) - 1, 255); + EDIT_ITEM_FAST(percent, MSG_CONTROLLER_FAN_IDLE_SPEED, &controllerFan.settings.idle_speed, CONTROLLERFAN_SPEED_MIN, 255); EDIT_ITEM(bool, MSG_CONTROLLER_FAN_AUTO_ON, &controllerFan.settings.auto_mode); if (controllerFan.settings.auto_mode) { - EDIT_ITEM_FAST(percent, MSG_CONTROLLER_FAN_SPEED, &controllerFan.settings.active_speed, _MAX(1, CONTROLLERFAN_SPEED_MIN) - 1, 255); + EDIT_ITEM_FAST(percent, MSG_CONTROLLER_FAN_SPEED, &controllerFan.settings.active_speed, CONTROLLERFAN_SPEED_MIN, 255); EDIT_ITEM(uint16_4, MSG_CONTROLLER_FAN_DURATION, &controllerFan.settings.duration, 0, 4800); } END_MENU(); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 48941532c8a0c..ede8aa73acb7a 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -41,6 +41,10 @@ #include "../feature/spindle_laser.h" #endif +#if ENABLED(USE_CONTROLLER_FAN) + #include "../feature/controllerfan.h" +#endif + #if ENABLED(EMERGENCY_PARSER) #include "motion.h" #endif @@ -302,6 +306,10 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); uint8_t Temperature::coolerfan_speed; // = 0 #endif +#if BOTH(FAN_SOFT_PWM, USE_CONTROLLER_FAN) + uint8_t Temperature::soft_pwm_controller_speed; +#endif + // Init fans according to whether they're native PWM or Software PWM #ifdef BOARD_OPENDRAIN_MOSFETS #define _INIT_SOFT_FAN(P) OUT_WRITE_OD(P, FAN_INVERTING ? LOW : HIGH) @@ -3021,6 +3029,10 @@ void Temperature::isr() { static SoftPWM soft_pwm_cooler; #endif + #if BOTH(FAN_SOFT_PWM, USE_CONTROLLER_FAN) + static SoftPWM soft_pwm_controller; + #endif + #define WRITE_FAN(n, v) WRITE(FAN##n##_PIN, (v) ^ FAN_INVERTING) #if DISABLED(SLOW_PWM_HEATERS) @@ -3056,6 +3068,10 @@ void Temperature::isr() { _PWM_MOD(COOLER, soft_pwm_cooler, temp_cooler); #endif + #if BOTH(USE_CONTROLLER_FAN, FAN_SOFT_PWM) + WRITE(CONTROLLER_FAN_PIN, soft_pwm_controller.add(pwm_mask, soft_pwm_controller_speed)); + #endif + #if ENABLED(FAN_SOFT_PWM) #define _FAN_PWM(N) do{ \ uint8_t &spcf = soft_pwm_count_fan[N]; \ @@ -3132,6 +3148,9 @@ void Temperature::isr() { #if HAS_FAN7 if (soft_pwm_count_fan[7] <= pwm_count_tmp) WRITE_FAN(7, LOW); #endif + #if ENABLED(USE_CONTROLLER_FAN) + if (soft_pwm_controller.count <= pwm_count_tmp) WRITE(CONTROLLER_FAN_PIN, LOW); + #endif #endif } diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 0e66f2311012e..050b3379e9198 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -387,6 +387,10 @@ class Temperature { soft_pwm_count_fan[FAN_COUNT]; #endif + #if BOTH(FAN_SOFT_PWM, USE_CONTROLLER_FAN) + static uint8_t soft_pwm_controller_speed; + #endif + #if ENABLED(PREVENT_COLD_EXTRUSION) static bool allow_cold_extrude; static celsius_t extrude_min_temp; From 8b952d9d11e3415d1aa42559c54c42c489860a5f Mon Sep 17 00:00:00 2001 From: EvilGremlin <22657714+EvilGremlin@users.noreply.github.com> Date: Mon, 15 Nov 2021 00:15:07 +0300 Subject: [PATCH 053/273] =?UTF-8?q?=F0=9F=9A=B8=20Simplify=20touchscreen?= =?UTF-8?q?=20calibration=20for=20SimUI=20(#23124)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 4 +- Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 53 +++++++++++++++++++----- 2 files changed, 44 insertions(+), 13 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index fbdda2c127585..866b86ef6bf9f 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3652,8 +3652,8 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); /** * Touch Screen Calibration */ -#if ENABLED(TFT_TOUCH_DEVICE_XPT2046) && DISABLED(TOUCH_SCREEN_CALIBRATION) \ - && (!defined(TOUCH_CALIBRATION_X) || !defined(TOUCH_CALIBRATION_Y) || !defined(TOUCH_OFFSET_X) || !defined(TOUCH_OFFSET_Y)) +#if !MB(LINUX_RAMPS) && ENABLED(TFT_TOUCH_DEVICE_XPT2046) && DISABLED(TOUCH_SCREEN_CALIBRATION) \ + && !(defined(TOUCH_CALIBRATION_X) && defined(TOUCH_CALIBRATION_Y) && defined(TOUCH_OFFSET_X) && defined(TOUCH_OFFSET_Y)) #error "TOUCH_CALIBRATION_[XY] and TOUCH_OFFSET_[XY] are required for resistive touch screens with TOUCH_SCREEN_CALIBRATION disabled." #endif diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 20bd5ef8cca7e..acf2d31cf604c 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -391,6 +391,7 @@ #define BEEPER_PIN 42 #define TOUCH_CS_PIN 33 + #define SD_DETECT_PIN 41 #define HAS_SPI_FLASH 1 @@ -407,17 +408,47 @@ #ifndef TFT_DRIVER #define TFT_DRIVER ST7796 #endif - #ifndef XPT2046_X_CALIBRATION - #define XPT2046_X_CALIBRATION 63934 - #endif - #ifndef XPT2046_Y_CALIBRATION - #define XPT2046_Y_CALIBRATION 63598 - #endif - #ifndef XPT2046_X_OFFSET - #define XPT2046_X_OFFSET -1 - #endif - #ifndef XPT2046_Y_OFFSET - #define XPT2046_Y_OFFSET -20 + #ifndef TOUCH_SCREEN_CALIBRATION + #if ENABLED(TFT_RES_320x240) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X 20525 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 15335 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X -1 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y 0 + #endif + #elif ENABLED(TFT_RES_480x272) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X 30715 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 17415 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 0 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -1 + #endif + #elif ENABLED(TFT_RES_480x320) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X 30595 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 20415 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 2 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y 1 + #endif + #endif #endif #define BTN_BACK 70 From 33c89d1f3fa603e49f5a9b346d089331f0f0efbf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 14 Nov 2021 17:19:57 -0600 Subject: [PATCH 054/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20SENSORLESS=5FHOMIN?= =?UTF-8?q?G=20for=206-axis?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/calibrate/G28.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 95f2a9b17614f..28df536c51ef6 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -83,9 +83,7 @@ #if ENABLED(SENSORLESS_HOMING) sensorless_t stealth_states { - tmc_enable_stallguard(stepperX) - , tmc_enable_stallguard(stepperY) - , false + LINEAR_AXIS_LIST(tmc_enable_stallguard(stepperX), tmc_enable_stallguard(stepperY), false, false, false, false) , false #if AXIS_HAS_STALLGUARD(X2) || tmc_enable_stallguard(stepperX2) From 125310dca00383d60632f13fcf185f59bc51bdf6 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 15 Nov 2021 01:01:02 +0000 Subject: [PATCH 055/273] [cron] Bump distribution date (2021-11-15) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index b2150960b9ed9..d1e68f6ca620d 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 "2021-11-14" +//#define STRING_DISTRIBUTION_DATE "2021-11-15" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ed67ecef8427c..9c201fd66d946 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 "2021-11-14" + #define STRING_DISTRIBUTION_DATE "2021-11-15" #endif /** From 36b2650f65e036ce1b02da568364230201a22b80 Mon Sep 17 00:00:00 2001 From: Mikhail Basov Date: Mon, 15 Nov 2021 07:46:34 +0300 Subject: [PATCH 056/273] =?UTF-8?q?=F0=9F=9A=B8=20LCD=5FSHOW=5FE=5FTOTAL?= =?UTF-8?q?=20for=20TFT=5FCOLOR=5FUI=20(#23127)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../lcd/dogm/status_screen_lite_ST7920.cpp | 16 ++++---- Marlin/src/lcd/tft/ui_1024x600.cpp | 38 +++++++++++------- Marlin/src/lcd/tft/ui_320x240.cpp | 39 ++++++++++++------- Marlin/src/lcd/tft/ui_480x320.cpp | 38 +++++++++++------- 4 files changed, 81 insertions(+), 50 deletions(-) diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index 2e6d697488ca2..492a79a311088 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -672,14 +672,7 @@ void ST7920_Lite_Status_Screen::draw_position(const xyze_pos_t &pos, const bool // If position is unknown, flash the labels. const unsigned char alt_label = position_trusted ? 0 : (ui.get_blink() ? ' ' : 0); - if (TERN1(LCD_SHOW_E_TOTAL, !printingIsActive())) { - write_byte(alt_label ? alt_label : 'X'); - write_str(dtostrf(pos.x, -4, 0, str), 4); - - write_byte(alt_label ? alt_label : 'Y'); - write_str(dtostrf(pos.y, -4, 0, str), 4); - } - else { + if (TERN0(LCD_SHOW_E_TOTAL, printingIsActive())) { #if ENABLED(LCD_SHOW_E_TOTAL) char tmp[15]; const uint8_t escale = e_move_accumulator >= 100000.0f ? 10 : 1; // After 100m switch to cm @@ -687,6 +680,13 @@ void ST7920_Lite_Status_Screen::draw_position(const xyze_pos_t &pos, const bool write_str(tmp); #endif } + else { + write_byte(alt_label ? alt_label : 'X'); + write_str(dtostrf(pos.x, -4, 0, str), 4); + + write_byte(alt_label ? alt_label : 'Y'); + write_str(dtostrf(pos.y, -4, 0, str), 4); + } write_byte(alt_label ? alt_label : 'Z'); write_str(dtostrf(pos.z, -5, 1, str), 5); diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index 3f0c70ab4ce2e..160f8c29f396b 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -258,21 +258,31 @@ void MarlinUI::draw_status_screen() { tft.set_background(COLOR_BACKGROUND); tft.add_rectangle(0, 0, TFT_WIDTH - 8, FONT_LINE_HEIGHT, COLOR_AXIS_HOMED); - tft.add_text(200, 3, COLOR_AXIS_HOMED , "X"); - tft.add_text(500, 3, COLOR_AXIS_HOMED , "Y"); + if (TERN0(LCD_SHOW_E_TOTAL, printingIsActive())) { + #if ENABLED(LCD_SHOW_E_TOTAL) + tft.add_text(200, 3, COLOR_AXIS_HOMED , "E"); + const uint8_t escale = e_move_accumulator >= 100000.0f ? 10 : 1; // After 100m switch to cm + tft_string.set(ftostr4sign(e_move_accumulator / escale)); + tft_string.add(escale == 10 ? 'c' : 'm'); + tft_string.add('m'); + tft.add_text(500 - tft_string.width(), 3, COLOR_AXIS_HOMED, tft_string); + #endif + } + else { + tft.add_text(200, 3, COLOR_AXIS_HOMED , "X"); + const bool nhx = axis_should_home(X_AXIS); + tft_string.set(blink && nhx ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); + tft.add_text(300 - tft_string.width(), 3, nhx ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + + tft.add_text(500, 3, COLOR_AXIS_HOMED , "Y"); + const bool nhy = axis_should_home(Y_AXIS); + tft_string.set(blink && nhy ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); + tft.add_text(600 - tft_string.width(), 3, nhy ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + } tft.add_text(800, 3, COLOR_AXIS_HOMED , "Z"); - - bool not_homed = axis_should_home(X_AXIS); - tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); - tft.add_text(300 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - - not_homed = axis_should_home(Y_AXIS); - tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); - tft.add_text(600 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - uint16_t offset = 32; - not_homed = axis_should_home(Z_AXIS); - if (blink && not_homed) + const bool nhz = axis_should_home(Z_AXIS); + if (blink && nhz) tft_string.set("?"); else { const float z = LOGICAL_Z_POSITION(current_position.z); @@ -283,7 +293,7 @@ void MarlinUI::draw_status_screen() { tft_string.set(ftostr52sp(z)); offset -= tft_string.width(); } - tft.add_text(900 - tft_string.width() - offset, 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + tft.add_text(900 - tft_string.width() - offset, 3, nhz ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); TERN_(TOUCH_SCREEN, touch.add_control(MOVE_AXIS, 4, y, TFT_WIDTH - 8, FONT_LINE_HEIGHT)); y += 100; diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index 1ef4c5881c249..d85a917983c06 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -256,21 +256,32 @@ void MarlinUI::draw_status_screen() { tft.set_background(COLOR_BACKGROUND); tft.add_rectangle(0, 0, 312, 24, COLOR_AXIS_HOMED); - tft.add_text( 10, 3, COLOR_AXIS_HOMED , "X"); - tft.add_text(127, 3, COLOR_AXIS_HOMED , "Y"); - tft.add_text(219, 3, COLOR_AXIS_HOMED , "Z"); - - bool not_homed = axis_should_home(X_AXIS); - tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); - tft.add_text( 68 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - - not_homed = axis_should_home(Y_AXIS); - tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); - tft.add_text(185 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + if (TERN0(LCD_SHOW_E_TOTAL, printingIsActive())) { + #if ENABLED(LCD_SHOW_E_TOTAL) + tft.add_text( 10, 3, COLOR_AXIS_HOMED , "E"); + const uint8_t escale = e_move_accumulator >= 100000.0f ? 10 : 1; // After 100m switch to cm + tft_string.set(ftostr4sign(e_move_accumulator / escale)); + tft_string.add(escale == 10 ? 'c' : 'm'); + tft_string.add('m'); + tft.add_text(127 - tft_string.width(), 3, COLOR_AXIS_HOMED, tft_string); + #endif + } + else { + tft.add_text( 10, 3, COLOR_AXIS_HOMED , "X"); + const bool nhx = axis_should_home(X_AXIS); + tft_string.set(blink && nhx ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); + tft.add_text( 68 - tft_string.width(), 3, nhx ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + + tft.add_text(127, 3, COLOR_AXIS_HOMED , "Y"); + const bool nhy = axis_should_home(Y_AXIS); + tft_string.set(blink && nhy ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); + tft.add_text(185 - tft_string.width(), 3, nhy ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + } - not_homed = axis_should_home(Z_AXIS); + tft.add_text(219, 3, COLOR_AXIS_HOMED , "Z"); + const bool nhz = axis_should_home(Z_AXIS); uint16_t offset = 25; - if (blink && not_homed) + if (blink && nhz) tft_string.set("?"); else { const float z = LOGICAL_Z_POSITION(current_position.z); @@ -281,7 +292,7 @@ void MarlinUI::draw_status_screen() { tft_string.set(ftostr52sp(z)); offset -= tft_string.width(); } - tft.add_text(301 - tft_string.width() - offset, 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + tft.add_text(301 - tft_string.width() - offset, 3, nhz ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); TERN_(TOUCH_SCREEN, touch.add_control(MOVE_AXIS, 0, 103, 312, 24)); // feed rate diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index f6591d682dc1d..ff14a9d588ed4 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -258,21 +258,31 @@ void MarlinUI::draw_status_screen() { tft.set_background(COLOR_BACKGROUND); tft.add_rectangle(0, 0, TFT_WIDTH - 8, FONT_LINE_HEIGHT, COLOR_AXIS_HOMED); - tft.add_text( 16, 3, COLOR_AXIS_HOMED , "X"); - tft.add_text(192, 3, COLOR_AXIS_HOMED , "Y"); + if (TERN0(LCD_SHOW_E_TOTAL, printingIsActive())) { + #if ENABLED(LCD_SHOW_E_TOTAL) + tft.add_text( 16, 3, COLOR_AXIS_HOMED , "E"); + const uint8_t escale = e_move_accumulator >= 100000.0f ? 10 : 1; // After 100m switch to cm + tft_string.set(ftostr4sign(e_move_accumulator / escale)); + tft_string.add(escale == 10 ? 'c' : 'm'); + tft_string.add('m'); + tft.add_text(192 - tft_string.width(), 3, COLOR_AXIS_HOMED, tft_string); + #endif + } + else { + tft.add_text( 16, 3, COLOR_AXIS_HOMED , "X"); + const bool nhx = axis_should_home(X_AXIS); + tft_string.set(blink && nhx ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); + tft.add_text(102 - tft_string.width(), 3, nhx ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + + tft.add_text(192, 3, COLOR_AXIS_HOMED , "Y"); + const bool nhy = axis_should_home(Y_AXIS); + tft_string.set(blink && nhy ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); + tft.add_text(280 - tft_string.width(), 3, nhy ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + } tft.add_text(330, 3, COLOR_AXIS_HOMED , "Z"); - - bool not_homed = axis_should_home(X_AXIS); - tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); - tft.add_text(102 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - - not_homed = axis_should_home(Y_AXIS); - tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); - tft.add_text(280 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - uint16_t offset = 32; - not_homed = axis_should_home(Z_AXIS); - if (blink && not_homed) + const bool nhz = axis_should_home(Z_AXIS); + if (blink && nhz) tft_string.set("?"); else { const float z = LOGICAL_Z_POSITION(current_position.z); @@ -283,7 +293,7 @@ void MarlinUI::draw_status_screen() { tft_string.set(ftostr52sp(z)); offset -= tft_string.width(); } - tft.add_text(455 - tft_string.width() - offset, 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); + tft.add_text(455 - tft_string.width() - offset, 3, nhz ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); TERN_(TOUCH_SCREEN, touch.add_control(MOVE_AXIS, 4, y, TFT_WIDTH - 8, FONT_LINE_HEIGHT)); y += TERN(HAS_UI_480x272, 38, 48); From f0b1ce8749b5b988d6fc640be1c64652fff160d5 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 16 Nov 2021 01:01:41 +0000 Subject: [PATCH 057/273] [cron] Bump distribution date (2021-11-16) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index d1e68f6ca620d..78a19bc06ecd8 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 "2021-11-15" +//#define STRING_DISTRIBUTION_DATE "2021-11-16" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9c201fd66d946..80420626f04b9 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 "2021-11-15" + #define STRING_DISTRIBUTION_DATE "2021-11-16" #endif /** From 2aa36af55739c3e2685cd3698186748835cd57da Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 16 Nov 2021 08:54:30 -0600 Subject: [PATCH 058/273] =?UTF-8?q?=F0=9F=94=A7=20SOUND=5FMENU=5FITEM=20fo?= =?UTF-8?q?r=20E3V2?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index fc9688edb76e8..c4feba569210e 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1246,9 +1246,6 @@ // BACK menu items keep the highlight at the top //#define TURBO_BACK_MENU_ITEM - // Add a mute option to the LCD menu - //#define SOUND_MENU_ITEM - /** * LED Control Menu * Add LED Control to the LCD menu @@ -1280,6 +1277,10 @@ #endif // HAS_LCD_MENU +#if ANY(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI) + //#define SOUND_MENU_ITEM // Add a mute option to the LCD menu +#endif + #if EITHER(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED) // The timeout (in ms) to return to the status screen from sub-menus //#define LCD_TIMEOUT_TO_STATUS 15000 From 629498f8d43be6675674671927456b8b6b4ac47b Mon Sep 17 00:00:00 2001 From: Luc Van Daele Date: Tue, 16 Nov 2021 16:24:53 +0100 Subject: [PATCH 059/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20G33,=20Delta=20rad?= =?UTF-8?q?ii,=20reachable=20(#22795)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/fast_pwm.cpp | 2 +- Marlin/src/gcode/calibrate/G33.cpp | 71 ++++++++++++----------------- Marlin/src/inc/SanityCheck.h | 2 +- Marlin/src/module/probe.cpp | 11 ++--- Marlin/src/module/probe.h | 46 ++++++++++++------- 5 files changed, 66 insertions(+), 66 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp index 197abb33101b3..eae0e36b0b0e3 100644 --- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp +++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp @@ -26,7 +26,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!LPC176x::pin_is_valid(pin)) return; - if (LPC176x::pwm_attach_pin(pin)) + if (LPC176x::pwm_attach_pin(pin)) LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size); // map 1-254 onto PWM range } diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 779ae99d0adf3..a4b9aec01b675 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -69,8 +69,6 @@ enum CalEnum : char { // the 7 main calibration points - float lcd_probe_pt(const xy_pos_t &xy); -float dcr; - void ac_home() { endstops.enable(true); TERN_(HAS_DELTA_SENSORLESS_PROBING, probe.set_homing_current(true)); @@ -177,7 +175,7 @@ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool */ static float calibration_probe(const xy_pos_t &xy, const bool stow, const bool probe_at_offset) { #if HAS_BED_PROBE - return probe.probe_at_point(xy, stow ? PROBE_PT_STOW : PROBE_PT_RAISE, 0, true, probe_at_offset); + return probe.probe_at_point(xy, stow ? PROBE_PT_STOW : PROBE_PT_RAISE, 0, probe_at_offset, false); #else UNUSED(stow); return lcd_probe_pt(xy); @@ -187,7 +185,7 @@ static float calibration_probe(const xy_pos_t &xy, const bool stow, const bool p /** * - Probe a grid */ -static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_points, const bool towers_set, const bool stow_after_each, const bool probe_at_offset) { +static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_points, const float dcr, const bool towers_set, const bool stow_after_each, const bool probe_at_offset) { const bool _0p_calibration = probe_points == 0, _1p_calibration = probe_points == 1 || probe_points == -1, _4p_calibration = probe_points == 2, @@ -271,7 +269,7 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi * - formulae for approximative forward kinematics in the end-stop displacement matrix * - definition of the matrix scaling parameters */ -static void reverse_kinematics_probe_points(float z_pt[NPP + 1], abc_float_t mm_at_pt_axis[NPP + 1]) { +static void reverse_kinematics_probe_points(float z_pt[NPP + 1], abc_float_t mm_at_pt_axis[NPP + 1], const float dcr) { xyz_pos_t pos{0}; LOOP_CAL_ALL(rad) { @@ -283,7 +281,7 @@ static void reverse_kinematics_probe_points(float z_pt[NPP + 1], abc_float_t mm_ } } -static void forward_kinematics_probe_points(abc_float_t mm_at_pt_axis[NPP + 1], float z_pt[NPP + 1]) { +static void forward_kinematics_probe_points(abc_float_t mm_at_pt_axis[NPP + 1], float z_pt[NPP + 1], const float dcr) { const float r_quot = dcr / delta_radius; #define ZPP(N,I,A) (((1.0f + r_quot * (N)) / 3.0f) * mm_at_pt_axis[I].A) @@ -302,19 +300,19 @@ static void forward_kinematics_probe_points(abc_float_t mm_at_pt_axis[NPP + 1], z_pt[_AB] = Zp1(_AB, a) + Zp1(_AB, b) + Zm2(_AB, c); } -static void calc_kinematics_diff_probe_points(float z_pt[NPP + 1], abc_float_t delta_e, const float delta_r, abc_float_t delta_t) { +static void calc_kinematics_diff_probe_points(float z_pt[NPP + 1], const float dcr, abc_float_t delta_e, const float delta_r, abc_float_t delta_t) { const float z_center = z_pt[CEN]; abc_float_t diff_mm_at_pt_axis[NPP + 1], new_mm_at_pt_axis[NPP + 1]; - reverse_kinematics_probe_points(z_pt, diff_mm_at_pt_axis); + reverse_kinematics_probe_points(z_pt, diff_mm_at_pt_axis, dcr); delta_radius += delta_r; delta_tower_angle_trim += delta_t; recalc_delta_settings(); - reverse_kinematics_probe_points(z_pt, new_mm_at_pt_axis); + reverse_kinematics_probe_points(z_pt, new_mm_at_pt_axis, dcr); LOOP_CAL_ALL(rad) diff_mm_at_pt_axis[rad] -= new_mm_at_pt_axis[rad] + delta_e; - forward_kinematics_probe_points(diff_mm_at_pt_axis, z_pt); + forward_kinematics_probe_points(diff_mm_at_pt_axis, z_pt, dcr); LOOP_CAL_RAD(rad) z_pt[rad] -= z_pt[CEN] - z_center; z_pt[CEN] = z_center; @@ -324,23 +322,23 @@ static void calc_kinematics_diff_probe_points(float z_pt[NPP + 1], abc_float_t d recalc_delta_settings(); } -static float auto_tune_h() { +static float auto_tune_h(const float dcr) { const float r_quot = dcr / delta_radius; return RECIPROCAL(r_quot / (2.0f / 3.0f)); // (2/3)/CR } -static float auto_tune_r() { +static float auto_tune_r(const float dcr) { constexpr float diff = 0.01f, delta_r = diff; float r_fac = 0.0f, z_pt[NPP + 1] = { 0.0f }; abc_float_t delta_e = { 0.0f }, delta_t = { 0.0f }; - calc_kinematics_diff_probe_points(z_pt, delta_e, delta_r, delta_t); + calc_kinematics_diff_probe_points(z_pt, dcr, delta_e, delta_r, delta_t); r_fac = -(z_pt[__A] + z_pt[__B] + z_pt[__C] + z_pt[_BC] + z_pt[_CA] + z_pt[_AB]) / 6.0f; r_fac = diff / r_fac / 3.0f; // 1/(3*delta_Z) return r_fac; } -static float auto_tune_a() { +static float auto_tune_a(const float dcr) { constexpr float diff = 0.01f, delta_r = 0.0f; float a_fac = 0.0f, z_pt[NPP + 1] = { 0.0f }; abc_float_t delta_e = { 0.0f }, delta_t = { 0.0f }; @@ -348,7 +346,7 @@ static float auto_tune_a() { delta_t.reset(); LOOP_LINEAR_AXES(axis) { delta_t[axis] = diff; - calc_kinematics_diff_probe_points(z_pt, delta_e, delta_r, delta_t); + calc_kinematics_diff_probe_points(z_pt, dcr, delta_e, delta_r, delta_t); delta_t[axis] = 0; a_fac += z_pt[uint8_t((axis * _4P_STEP) - _7P_STEP + NPP) % NPP + 1] / 6.0f; a_fac -= z_pt[uint8_t((axis * _4P_STEP) + 1 + _7P_STEP)] / 6.0f; @@ -370,7 +368,7 @@ static float auto_tune_a() { * P3 Probe all positions: center, towers and opposite towers. Calibrate all. * P4-P10 Probe all positions at different intermediate locations and average them. * - * Rn.nn override default calibration Radius + * Rn.nn Temporary reduce the probe grid by the specified amount (mm) * * T Don't calibrate tower angle corrections * @@ -386,7 +384,7 @@ static float auto_tune_a() { * * E Engage the probe for each point * - * O Probe at offset points (this is wrong but it seems to work) + * O Probe at offsetted probe positions (this is wrong but it seems to work) * * With SENSORLESS_PROBING: * Use these flags to calibrate stall sensitivity: (e.g., `G33 P1 Y Z` to calibrate X only.) @@ -404,27 +402,17 @@ void GcodeSuite::G33() { return; } - const bool probe_at_offset = TERN0(HAS_PROBE_XY_OFFSET, parser.boolval('O')), + const bool probe_at_offset = TERN0(HAS_PROBE_XY_OFFSET, parser.seen_test('O')), towers_set = !parser.seen_test('T'); - float max_dcr = dcr = DELTA_PRINTABLE_RADIUS; + // The calibration radius is set to a calculated value + float dcr = probe_at_offset ? DELTA_PRINTABLE_RADIUS : DELTA_PRINTABLE_RADIUS - PROBING_MARGIN; #if HAS_PROBE_XY_OFFSET - // For offset probes the calibration radius is set to a safe but non-optimal value - dcr -= HYPOT(probe.offset_xy.x, probe.offset_xy.y); - if (probe_at_offset) { - // With probe positions both probe and nozzle need to be within the printable area - max_dcr = dcr; - } - // else with nozzle positions there is a risk of the probe being outside the bed - // but as long the nozzle stays within the printable area there is no risk of - // the effector crashing into the towers. + const float total_offset = HYPOT(probe.offset_xy.x, probe.offset_xy.y); + dcr -= probe_at_offset ? _MAX(total_offset, PROBING_MARGIN) : total_offset; #endif - - if (parser.seenval('R')) dcr = parser.value_float(); - if (!WITHIN(dcr, 0, max_dcr)) { - SERIAL_ECHOLNPGM("?calibration (R)adius implausible."); - return; - } + NOMORE(dcr, DELTA_PRINTABLE_RADIUS); + if (parser.seenval('R')) dcr -= _MAX(parser.value_float(),0); const float calibration_precision = parser.floatval('C', 0.0f); if (calibration_precision < 0) { @@ -475,8 +463,9 @@ void GcodeSuite::G33() { SERIAL_ECHOLNPGM("G33 Auto Calibrate"); // Report settings - FSTR_P const checkingac = F("Checking... AC"); - SERIAL_ECHOF(checkingac); + PGM_P const checkingac = PSTR("Checking... AC"); + SERIAL_ECHOPGM_P(checkingac); + SERIAL_ECHOPGM(" at radius:", dcr); if (verbose_level == 0) SERIAL_ECHOPGM(" (DRY-RUN)"); SERIAL_EOL(); ui.set_status(checkingac); @@ -496,7 +485,7 @@ void GcodeSuite::G33() { // Probe the points zero_std_dev_old = zero_std_dev; - if (!probe_calibration_points(z_at_pt, probe_points, towers_set, stow_after_each, probe_at_offset)) { + if (!probe_calibration_points(z_at_pt, probe_points, dcr, towers_set, stow_after_each, probe_at_offset)) { SERIAL_ECHOLNPGM("Correct delta settings with M665 and M666"); return ac_cleanup(TERN_(HAS_MULTI_HOTEND, old_tool_index)); } @@ -536,10 +525,10 @@ void GcodeSuite::G33() { // calculate factors if (_7p_9_center) dcr *= 0.9f; - h_factor = auto_tune_h(); - r_factor = auto_tune_r(); - a_factor = auto_tune_a(); - dcr /= 0.9f; + h_factor = auto_tune_h(dcr); + r_factor = auto_tune_r(dcr); + a_factor = auto_tune_a(dcr); + if (_7p_9_center) dcr /= 0.9f; switch (probe_points) { case 0: diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 866b86ef6bf9f..4186e994677d7 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1635,7 +1635,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if ENABLED(NOZZLE_AS_PROBE) static_assert(sanity_nozzle_to_probe_offset.x == 0 && sanity_nozzle_to_probe_offset.y == 0, "NOZZLE_AS_PROBE requires the XY offsets in NOZZLE_TO_PROBE_OFFSET to both be 0."); - #else + #elif !IS_KINEMATIC static_assert(PROBING_MARGIN >= 0, "PROBING_MARGIN must be >= 0."); static_assert(PROBING_MARGIN_BACK >= 0, "PROBING_MARGIN_BACK must be >= 0."); static_assert(PROBING_MARGIN_FRONT >= 0, "PROBING_MARGIN_FRONT must be >= 0."); diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 984a3aabb505c..89a043d0f508e 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -768,14 +768,11 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai // On delta keep Z below clip height or do_blocking_move_to will abort xyz_pos_t npos = { rx, ry, TERN(DELTA, _MIN(delta_clip_start_height, current_position.z), current_position.z) }; - if (probe_relative) { // The given position is in terms of the probe - if (!can_reach(npos)) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Position Not Reachable"); - return NAN; - } - npos -= offset_xy; // Get the nozzle position + if (!can_reach(npos, probe_relative)) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Position Not Reachable"); + return NAN; } - else if (!position_is_reachable(npos)) return NAN; // The given position is in terms of the nozzle + if (probe_relative) npos -= offset_xy; // Get the nozzle position // Move the probe to the starting XYZ do_blocking_move_to(npos, feedRate_t(XY_PROBE_FEEDRATE_MM_S)); diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index f9275ba9fdc48..3c97afcb899c4 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -77,13 +77,20 @@ class Probe { #if HAS_PROBE_XY_OFFSET // Return true if the both nozzle and the probe can reach the given point. // Note: This won't work on SCARA since the probe offset rotates with the arm. - static bool can_reach(const_float_t rx, const_float_t ry) { - return position_is_reachable(rx - offset_xy.x, ry - offset_xy.y) // The nozzle can go where it needs to go? - && position_is_reachable(rx, ry, ABS(PROBING_MARGIN)); // Can the nozzle also go near there? + static bool can_reach(const_float_t rx, const_float_t ry, const bool probe_relative=true) { + if (probe_relative) { + return position_is_reachable(rx - offset_xy.x, ry - offset_xy.y) // The nozzle can go where it needs to go? + && position_is_reachable(rx, ry, PROBING_MARGIN); // Can the probe also go near there? + } + else { + return position_is_reachable(rx, ry) + && position_is_reachable(rx + offset_xy.x, ry + offset_xy.y, PROBING_MARGIN); + } } #else - static bool can_reach(const_float_t rx, const_float_t ry) { - return position_is_reachable(rx, ry, PROBING_MARGIN); + static bool can_reach(const_float_t rx, const_float_t ry, const bool=true) { + return position_is_reachable(rx, ry) + && position_is_reachable(rx, ry, PROBING_MARGIN); } #endif @@ -96,10 +103,17 @@ class Probe { * Example: For a probe offset of -10,+10, then for the probe to reach 0,0 the * nozzle must be be able to reach +10,-10. */ - static bool can_reach(const_float_t rx, const_float_t ry) { - return position_is_reachable(rx - offset_xy.x, ry - offset_xy.y) - && COORDINATE_OKAY(rx, min_x() - fslop, max_x() + fslop) - && COORDINATE_OKAY(ry, min_y() - fslop, max_y() + fslop); + static bool can_reach(const_float_t rx, const_float_t ry, const bool probe_relative=true) { + if (probe_relative) { + return position_is_reachable(rx - offset_xy.x, ry - offset_xy.y) + && COORDINATE_OKAY(rx, min_x() - fslop, max_x() + fslop) + && COORDINATE_OKAY(ry, min_y() - fslop, max_y() + fslop); + } + else { + return position_is_reachable(rx, ry) + && COORDINATE_OKAY(rx + offset_xy.x, min_x() - fslop, max_x() + fslop) + && COORDINATE_OKAY(ry + offset_xy.y, min_y() - fslop, max_y() + fslop); + } } #endif @@ -120,7 +134,7 @@ class Probe { static bool set_deployed(const bool) { return false; } - static bool can_reach(const_float_t rx, const_float_t ry) { return position_is_reachable(rx, ry); } + static bool can_reach(const_float_t rx, const_float_t ry, const bool=true) { return position_is_reachable(rx, ry); } #endif @@ -132,7 +146,7 @@ class Probe { #endif } - static bool can_reach(const xy_pos_t &pos) { return can_reach(pos.x, pos.y); } + static bool can_reach(const xy_pos_t &pos, const bool probe_relative=true) { return can_reach(pos.x, pos.y, probe_relative); } static bool good_bounds(const xy_pos_t &lf, const xy_pos_t &rb) { return ( @@ -161,30 +175,30 @@ class Probe { TERN_(DELTA, DELTA_PRINTABLE_RADIUS) TERN_(IS_SCARA, SCARA_PRINTABLE_RADIUS) ); - static constexpr float probe_radius(const xy_pos_t &probe_offset_xy = offset_xy) { + static constexpr float probe_radius(const xy_pos_t &probe_offset_xy=offset_xy) { return printable_radius - _MAX(PROBING_MARGIN, HYPOT(probe_offset_xy.x, probe_offset_xy.y)); } #endif - static constexpr float _min_x(const xy_pos_t &probe_offset_xy = offset_xy) { + static constexpr float _min_x(const xy_pos_t &probe_offset_xy=offset_xy) { return TERN(IS_KINEMATIC, (X_CENTER) - probe_radius(probe_offset_xy), _MAX((X_MIN_BED) + (PROBING_MARGIN_LEFT), (X_MIN_POS) + probe_offset_xy.x) ); } - static constexpr float _max_x(const xy_pos_t &probe_offset_xy = offset_xy) { + static constexpr float _max_x(const xy_pos_t &probe_offset_xy=offset_xy) { return TERN(IS_KINEMATIC, (X_CENTER) + probe_radius(probe_offset_xy), _MIN((X_MAX_BED) - (PROBING_MARGIN_RIGHT), (X_MAX_POS) + probe_offset_xy.x) ); } - static constexpr float _min_y(const xy_pos_t &probe_offset_xy = offset_xy) { + static constexpr float _min_y(const xy_pos_t &probe_offset_xy=offset_xy) { return TERN(IS_KINEMATIC, (Y_CENTER) - probe_radius(probe_offset_xy), _MAX((Y_MIN_BED) + (PROBING_MARGIN_FRONT), (Y_MIN_POS) + probe_offset_xy.y) ); } - static constexpr float _max_y(const xy_pos_t &probe_offset_xy = offset_xy) { + static constexpr float _max_y(const xy_pos_t &probe_offset_xy=offset_xy) { return TERN(IS_KINEMATIC, (Y_CENTER) + probe_radius(probe_offset_xy), _MIN((Y_MAX_BED) - (PROBING_MARGIN_BACK), (Y_MAX_POS) + probe_offset_xy.y) From eb8392edd4a1ccedd235c7463f15e583f47f233a Mon Sep 17 00:00:00 2001 From: EvilGremlin <22657714+EvilGremlin@users.noreply.github.com> Date: Tue, 16 Nov 2021 19:32:43 +0300 Subject: [PATCH 060/273] =?UTF-8?q?=F0=9F=94=A8=20Ignore=20sim=20flashdriv?= =?UTF-8?q?e=20file=20(#23129)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index a83bfa4265a6a..fabe5445631f6 100755 --- a/.gitignore +++ b/.gitignore @@ -146,6 +146,7 @@ vc-fileutils.settings #Simulation imgui.ini eeprom.dat +spi_flash.bin #cmake CMakeLists.txt From 89fe5f6d74ba6d45290e3e268619c8f9b32ba8ba Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 16 Nov 2021 12:49:25 -0600 Subject: [PATCH 061/273] =?UTF-8?q?=F0=9F=94=A8=20Bring=20Makefile=20up=20?= =?UTF-8?q?to=20date?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Makefile | 165 ++++++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 158 insertions(+), 7 deletions(-) diff --git a/Marlin/Makefile b/Marlin/Makefile index d09e5828f5b2f..eee1403b537ce 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -191,6 +191,134 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1034) # RAMPS Derivatives - ATmega1280, ATmega2560 # +# 3Drag Controller +else ifeq ($(HARDWARE_MOTHERBOARD),1100) +# Velleman K8200 Controller (derived from 3Drag Controller) +else ifeq ($(HARDWARE_MOTHERBOARD),1101) +# Velleman K8400 Controller (derived from 3Drag Controller) +else ifeq ($(HARDWARE_MOTHERBOARD),1102) +# Velleman K8600 Controller (Vertex Nano) +else ifeq ($(HARDWARE_MOTHERBOARD),1103) +# Velleman K8800 Controller (Vertex Delta) +else ifeq ($(HARDWARE_MOTHERBOARD),1104) +# 2PrintBeta BAM&DICE with STK drivers +else ifeq ($(HARDWARE_MOTHERBOARD),1105) +# 2PrintBeta BAM&DICE Due with STK drivers +else ifeq ($(HARDWARE_MOTHERBOARD),1106) +# MKS BASE v1.0 +else ifeq ($(HARDWARE_MOTHERBOARD),1107) +# MKS BASE v1.4 with Allegro A4982 stepper drivers +else ifeq ($(HARDWARE_MOTHERBOARD),1108) +# MKS BASE v1.5 with Allegro A4982 stepper drivers +else ifeq ($(HARDWARE_MOTHERBOARD),1109) +# MKS BASE v1.6 with Allegro A4982 stepper drivers +else ifeq ($(HARDWARE_MOTHERBOARD),1110) +# MKS BASE 1.0 with Heroic HR4982 stepper drivers +else ifeq ($(HARDWARE_MOTHERBOARD),1111) +# MKS GEN v1.3 or 1.4 +else ifeq ($(HARDWARE_MOTHERBOARD),1112) +# MKS GEN L +else ifeq ($(HARDWARE_MOTHERBOARD),1113) +# BigTreeTech or BIQU KFB2.0 +else ifeq ($(HARDWARE_MOTHERBOARD),1114) +# zrib V2.0 (Chinese RAMPS replica) +else ifeq ($(HARDWARE_MOTHERBOARD),1115) +# zrib V5.2 (Chinese RAMPS replica) +else ifeq ($(HARDWARE_MOTHERBOARD),1116) +# Felix 2.0+ Electronics Board (RAMPS like) +else ifeq ($(HARDWARE_MOTHERBOARD),1117) +# Invent-A-Part RigidBoard +else ifeq ($(HARDWARE_MOTHERBOARD),1118) +# Invent-A-Part RigidBoard V2 +else ifeq ($(HARDWARE_MOTHERBOARD),1119) +# Sainsmart 2-in-1 board +else ifeq ($(HARDWARE_MOTHERBOARD),1120) +# Ultimaker +else ifeq ($(HARDWARE_MOTHERBOARD),1121) +# Ultimaker (Older electronics. Pre 1.5.4. This is rare) +else ifeq ($(HARDWARE_MOTHERBOARD),1122) + MCU ?= atmega1280 + PROG_MCU ?= m1280 +# Azteeg X3 +else ifeq ($(HARDWARE_MOTHERBOARD),1123) +# Azteeg X3 Pro +else ifeq ($(HARDWARE_MOTHERBOARD),1124) +# Ultimainboard 2.x (Uses TEMP_SENSOR 20) +else ifeq ($(HARDWARE_MOTHERBOARD),1125) +# Rumba +else ifeq ($(HARDWARE_MOTHERBOARD),1126) +# Raise3D N series Rumba derivative +else ifeq ($(HARDWARE_MOTHERBOARD),1127) +# Rapide Lite 200 (v1, low-cost RUMBA clone with drv) +else ifeq ($(HARDWARE_MOTHERBOARD),1128) +# Formbot T-Rex 2 Plus +else ifeq ($(HARDWARE_MOTHERBOARD),1129) +# Formbot T-Rex 3 +else ifeq ($(HARDWARE_MOTHERBOARD),1130) +# Formbot Raptor +else ifeq ($(HARDWARE_MOTHERBOARD),1131) +# Formbot Raptor 2 +else ifeq ($(HARDWARE_MOTHERBOARD),1132) +# bq ZUM Mega 3D +else ifeq ($(HARDWARE_MOTHERBOARD),1133) +# MakeBoard Mini v2.1.2 by MicroMake +else ifeq ($(HARDWARE_MOTHERBOARD),1134) +# TriGorilla Anycubic version 1.3-based on RAMPS EFB +else ifeq ($(HARDWARE_MOTHERBOARD),1135) +# ... Ver 1.4 +else ifeq ($(HARDWARE_MOTHERBOARD),1136) +# ... Rev 1.1 (new servo pin order) +else ifeq ($(HARDWARE_MOTHERBOARD),1137) +# Creality: Ender-4, CR-8 +else ifeq ($(HARDWARE_MOTHERBOARD),1138) +# Creality: CR10S, CR20, CR-X +else ifeq ($(HARDWARE_MOTHERBOARD),1139) +# Dagoma F5 +else ifeq ($(HARDWARE_MOTHERBOARD),1140) +# FYSETC F6 1.3 +else ifeq ($(HARDWARE_MOTHERBOARD),1141) +# FYSETC F6 1.4 +else ifeq ($(HARDWARE_MOTHERBOARD),1142) +# Wanhao Duplicator i3 Plus +else ifeq ($(HARDWARE_MOTHERBOARD),1143) +# VORON Design +else ifeq ($(HARDWARE_MOTHERBOARD),1144) +# Tronxy TRONXY-V3-1.0 +else ifeq ($(HARDWARE_MOTHERBOARD),1145) +# Z-Bolt X Series +else ifeq ($(HARDWARE_MOTHERBOARD),1146) +# TT OSCAR +else ifeq ($(HARDWARE_MOTHERBOARD),1147) +# Overlord/Overlord Pro +else ifeq ($(HARDWARE_MOTHERBOARD),1148) +# ADIMLab Gantry v1 +else ifeq ($(HARDWARE_MOTHERBOARD),1149) +# ADIMLab Gantry v2 +else ifeq ($(HARDWARE_MOTHERBOARD),1150) +# BIQU Tango V1 +else ifeq ($(HARDWARE_MOTHERBOARD),1151) +# MKS GEN L V2 +else ifeq ($(HARDWARE_MOTHERBOARD),1152) +# MKS GEN L V2.1 +else ifeq ($(HARDWARE_MOTHERBOARD),1153) +# Copymaster 3D +else ifeq ($(HARDWARE_MOTHERBOARD),1154) +# Ortur 4 +else ifeq ($(HARDWARE_MOTHERBOARD),1155) +# Tenlog D3 Hero IDEX printer +else ifeq ($(HARDWARE_MOTHERBOARD),1156) +# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Fan, Bed) +else ifeq ($(HARDWARE_MOTHERBOARD),1157) +# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Hotend2, Bed) +else ifeq ($(HARDWARE_MOTHERBOARD),1158) +# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend, Fan0, Fan1, Bed) +else ifeq ($(HARDWARE_MOTHERBOARD),1159) +# Longer LK1 PRO / Alfawise U20 Pro (PRO version) +else ifeq ($(HARDWARE_MOTHERBOARD),1160) +# Longer LKx PRO / Alfawise Uxx Pro (PRO version) +else ifeq ($(HARDWARE_MOTHERBOARD),1161) + + # 3Drag Controller else ifeq ($(HARDWARE_MOTHERBOARD),1100) # Velleman K8200 Controller (derived from 3Drag Controller) @@ -358,20 +486,38 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1311) else ifeq ($(HARDWARE_MOTHERBOARD),1312) # Mega controller else ifeq ($(HARDWARE_MOTHERBOARD),1313) -# Geeetech GT2560 Rev B for Mecreator2 +# Geeetech GT2560 Rev A else ifeq ($(HARDWARE_MOTHERBOARD),1314) -# Geeetech GT2560 Rev. A +# Geeetech GT2560 Rev A+ (with auto level probe) else ifeq ($(HARDWARE_MOTHERBOARD),1315) -# Geeetech GT2560 Rev. A+ (with auto level probe) +# Geeetech GT2560 Rev B else ifeq ($(HARDWARE_MOTHERBOARD),1316) -# Geeetech GT2560 Rev B for A10(M/D) +# Geeetech GT2560 Rev B for A10(M/T/D) else ifeq ($(HARDWARE_MOTHERBOARD),1317) -# Geeetech GT2560 Rev B for A20(M/D) +# Geeetech GT2560 Rev B for A10(M/T/D) else ifeq ($(HARDWARE_MOTHERBOARD),1318) -# Einstart retrofit +# Geeetech GT2560 Rev B for Mecreator2 else ifeq ($(HARDWARE_MOTHERBOARD),1319) -# Wanhao 0ne+ i3 Mini +# Geeetech GT2560 Rev B for A20(M/T/D) else ifeq ($(HARDWARE_MOTHERBOARD),1320) +# Einstart retrofit +else ifeq ($(HARDWARE_MOTHERBOARD),1321) +# Wanhao 0ne+ i3 Mini +else ifeq ($(HARDWARE_MOTHERBOARD),1322) +# Leapfrog Xeed 2015 +else ifeq ($(HARDWARE_MOTHERBOARD),1323) +# PICA Shield (original version) +else ifeq ($(HARDWARE_MOTHERBOARD),1324) +# PICA Shield (rev C or later) +else ifeq ($(HARDWARE_MOTHERBOARD),1325) +# Intamsys 4.0 (Funmat HT) +else ifeq ($(HARDWARE_MOTHERBOARD),1326) +# Malyan M180 Mainboard Version 2 (no display function, direct gcode only) +else ifeq ($(HARDWARE_MOTHERBOARD),1327) +# Geeetech GT2560 Rev B for A20(M/T/D) +else ifeq ($(HARDWARE_MOTHERBOARD),1328) +# Mega controller & Protoneer CNC Shield V3.00 +else ifeq ($(HARDWARE_MOTHERBOARD),1329) # # ATmega1281, ATmega2561 @@ -445,6 +591,11 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1510) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p PROG_MCU ?= m1284p +# ZoneStar ZMIB V2 +else ifeq ($(HARDWARE_MOTHERBOARD),1511) + HARDWARE_VARIANT ?= Sanguino + MCU ?= atmega1284p + PROG_MCU ?= m1284p # # Other ATmega644P, ATmega644, ATmega1284P From 36173fb2593489a0be1ad1f2a90553de3a452700 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 16 Nov 2021 14:06:36 -0600 Subject: [PATCH 062/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20fast=20PWM=20WGM?= =?UTF-8?q?=20code?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #23102 --- Marlin/src/HAL/AVR/fast_pwm.cpp | 10 ++++++++-- Marlin/src/feature/spindle_laser.cpp | 2 +- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index cbe4fed94a05f..804e5fad30709 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -200,7 +200,10 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { res = res_temp_fast; j = i; // Set the Wave Generation Mode to FAST PWM - wgm = timer.n == 2 ? TERN(USE_OCR2A_AS_TOP, WGM2_FAST_PWM_OCR2A, WGM2_FAST_PWM) : WGM_FAST_PWM_ICRn; + if (timer.n == 2) + wgm = TERN(USE_OCR2A_AS_TOP, WGM2_FAST_PWM_OCR2A, WGM2_FAST_PWM); + else + wgm = WGM_FAST_PWM_ICRn; } // If PHASE CORRECT values are closes to desired f else if (f_phase_diff < f_diff) { @@ -208,7 +211,10 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { res = res_temp_phase_correct; j = i; // Set the Wave Generation Mode to PWM PHASE CORRECT - wgm = timer.n == 2 ? TERN(USE_OCR2A_AS_TOP, WGM2_PWM_PC_OCR2A, WGM2_PWM_PC) : WGM_PWM_PC_ICRn; + if (timer.n == 2) + wgm = TERN(USE_OCR2A_AS_TOP, WGM2_PWM_PC_OCR2A, WGM2_FAST_PWM); + else + wgm = WGM_PWM_PC_ICRn; } } } diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 9297e9b95c8a8..cde2b47d90aad 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -62,7 +62,7 @@ void SpindleLaser::init() { OUT_WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); // Init spindle to off #endif #if ENABLED(SPINDLE_CHANGE_DIR) - OUT_WRITE(SPINDLE_DIR_PIN, SPINDLE_INVERT_DIR ? 255 : 0); // Init rotation to clockwise (M3) + OUT_WRITE(SPINDLE_DIR_PIN, SPINDLE_INVERT_DIR); // Init rotation to clockwise (M3) #endif #if ENABLED(SPINDLE_LASER_USE_PWM) SET_PWM(SPINDLE_LASER_PWM_PIN); From 3e14f06f8009e1d02a6b92f2caa6ed027ed078b0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 17 Nov 2021 01:01:01 +0000 Subject: [PATCH 063/273] [cron] Bump distribution date (2021-11-17) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 78a19bc06ecd8..eb5d6934bb63f 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 "2021-11-16" +//#define STRING_DISTRIBUTION_DATE "2021-11-17" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 80420626f04b9..b2fa8bac0c391 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 "2021-11-16" + #define STRING_DISTRIBUTION_DATE "2021-11-17" #endif /** From 44d8c2f5bf970e5f701e8bf8e2eff4e17b9266bc Mon Sep 17 00:00:00 2001 From: espr14 Date: Wed, 17 Nov 2021 18:07:11 +0100 Subject: [PATCH 064/273] =?UTF-8?q?=F0=9F=8F=97=EF=B8=8F=20Planner::busy()?= =?UTF-8?q?=20(#23145)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/planner.cpp | 12 ++---------- Marlin/src/module/planner.h | 11 +++++++++++ 2 files changed, 13 insertions(+), 10 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 11460fa67a24b..e19684a7b55a9 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -91,10 +91,6 @@ #include "../feature/power.h" #endif -#if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) - #include "../feature/closedloop.h" -#endif - #if ENABLED(BACKLASH_COMPENSATION) #include "../feature/backlash.h" #endif @@ -1763,13 +1759,9 @@ float Planner::get_axis_position_mm(const AxisEnum axis) { } /** - * Block until all buffered steps are executed / cleaned + * Block until the planner is finished processing */ -void Planner::synchronize() { - while (has_blocks_queued() || cleaning_buffer_counter - || TERN0(EXTERNAL_CLOSED_LOOP_CONTROLLER, CLOSED_LOOP_WAITING()) - ) idle(); -} +void Planner::synchronize() { while (busy()) idle(); } /** * Planner::_buffer_steps diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 16d136be454f5..60574b65f0582 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -75,6 +75,10 @@ #define IS_PAGE(B) false #endif +#if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) + #include "../feature/closedloop.h" +#endif + // Feedrate for manual moves #ifdef MANUAL_FEEDRATE constexpr xyze_feedrate_t _mf = MANUAL_FEEDRATE, @@ -865,6 +869,13 @@ class Planner { // Triggered position of an axis in mm (not core-savvy) static float triggered_position_mm(const AxisEnum axis); + // Blocks are queued, or we're running out moves, or the closed loop controller is waiting + static inline bool busy() { + return (has_blocks_queued() || cleaning_buffer_counter + || TERN0(EXTERNAL_CLOSED_LOOP_CONTROLLER, CLOSED_LOOP_WAITING()) + ); + } + // Block until all buffered steps are executed / cleaned static void synchronize(); From b7be62ad36d9d2e8bc4d0718b8cba94321267077 Mon Sep 17 00:00:00 2001 From: luzpaz Date: Wed, 17 Nov 2021 12:09:01 -0500 Subject: [PATCH 065/273] =?UTF-8?q?=F0=9F=8E=A8=20Fix=20misspelling=20(#23?= =?UTF-8?q?137)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32F1/onboard_sd.cpp | 2 +- Marlin/src/lcd/e3v2/enhanced/dwinui.cpp | 6 +++--- Marlin/src/lcd/e3v2/enhanced/dwinui.h | 6 +++--- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 2 +- Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h | 2 +- Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h | 2 +- 6 files changed, 10 insertions(+), 10 deletions(-) diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/onboard_sd.cpp index df98c2c057af9..582ee3853d00e 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.cpp +++ b/Marlin/src/HAL/STM32F1/onboard_sd.cpp @@ -278,7 +278,7 @@ DSTATUS disk_initialize ( if (drv) return STA_NOINIT; // Supports only drive 0 sd_power_on(); // Initialize SPI - if (Stat & STA_NODISK) return Stat; // Is a card existing in the soket? + if (Stat & STA_NODISK) return Stat; // Is a card existing in the socket? FCLK_SLOW(); for (n = 10; n; n--) xchg_spi(0xFF); // Send 80 dummy clocks diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp index 824aca07f8661..52b7c3b5213f9 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp @@ -93,7 +93,7 @@ uint8_t DWINUI::fontWidth(uint8_t cfont) { } } -// Get font character heigh +// Get font character height uint8_t DWINUI::fontHeight(uint8_t cfont) { switch (cfont) { case font6x12 : return 12; @@ -110,12 +110,12 @@ uint8_t DWINUI::fontHeight(uint8_t cfont) { } } -// Get screen x coodinates from text column +// Get screen x coordinates from text column uint16_t DWINUI::ColToX(uint8_t col) { return col * fontWidth(font); } -// Get screen y coodinates from text row +// Get screen y coordinates from text row uint16_t DWINUI::RowToY(uint8_t row) { return row * fontHeight(font); } diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.h b/Marlin/src/lcd/e3v2/enhanced/dwinui.h index 078b3cc58bf4a..9a717da80d7e2 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.h @@ -198,13 +198,13 @@ namespace DWINUI { // Get font character width uint8_t fontWidth(uint8_t cfont); - // Get font character heigh + // Get font character height uint8_t fontHeight(uint8_t cfont); - // Get screen x coodinates from text column + // Get screen x coordinates from text column uint16_t ColToX(uint8_t col); - // Get screen y coodinates from text row + // Get screen y coordinates from text row uint16_t RowToY(uint8_t row); // Set text/number color diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 4c838a2e21432..eea464dcfd171 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -4135,7 +4135,7 @@ void CrealityDWINClass::Popup_Handler(PopupID popupid, bool option/*=false*/) { switch (popupid) { case Pause: Draw_Popup(F("Pause Print"), F(""), F(""), Popup); break; case Stop: Draw_Popup(F("Stop Print"), F(""), F(""), Popup); break; - case Resume: Draw_Popup(F("Resume Print?"), F("Looks Like the last"), F("print was interupted."), Popup); break; + case Resume: Draw_Popup(F("Resume Print?"), F("Looks Like the last"), F("print was interrupted."), Popup); break; case ConfFilChange: Draw_Popup(F("Confirm Filament Change"), F(""), F(""), Popup); break; case PurgeMore: Draw_Popup(F("Purge more filament?"), F("(Cancel to finish process)"), F(""), Popup); break; case SaveLevel: Draw_Popup(F("Leveling Complete"), F("Save to EEPROM?"), F(""), Popup); break; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h index 1869f79404503..265e2fe584bdd 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h @@ -96,7 +96,7 @@ class DGUSDisplay { static size_t GetFreeTxBuffer(); static void FlushTx(); - // Checks two things: Can we confirm the presence of the display and has we initiliazed it. + // 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 inline bool IsInitialized() { return initialized; diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h index 04dcc432cae15..f2fc53379be15 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h @@ -22,7 +22,7 @@ #pragma once /** - * No offical schematics have been found. + * No official schematics have been found. * But these differences where noted in https://github.com/bigtreetech/Rumba32/issues/1 */ From e3d777cf8fcdeafe11df73d88fd6c374148b6f47 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 17 Nov 2021 09:33:42 -0800 Subject: [PATCH 066/273] =?UTF-8?q?=F0=9F=93=8C=20Overridable=20probe-rela?= =?UTF-8?q?ted=20pins=20(#23107)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h | 9 +++++++-- Marlin/src/pins/stm32f1/pins_CREALITY_V452.h | 4 +++- Marlin/src/pins/stm32f1/pins_CREALITY_V453.h | 4 +++- Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h | 4 +++- Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 4 +++- 5 files changed, 19 insertions(+), 6 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h index 8368fd03cd9c2..570d102c47583 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -70,9 +70,14 @@ // // Probe // -#define PROBE_TARE_PIN PA1 +#ifndef PROBE_TARE_PIN + #define PROBE_TARE_PIN PA1 +#endif + #if ENABLED(PROBE_ACTIVATION_SWITCH) - #define PROBE_ACTIVATION_SWITCH_PIN PC2 // Optoswitch to Enable Z Probe + #ifndef PROBE_ACTIVATION_SWITCH_PIN + #define PROBE_ACTIVATION_SWITCH_PIN PC2 // Optoswitch to Enable Z Probe + #endif #endif // diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h index 7d3140056a0dd..9b6862d99bd43 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h @@ -36,7 +36,9 @@ #define FAN_PIN PA0 // FAN #if ENABLED(PROBE_ACTIVATION_SWITCH) - #define PROBE_ACTIVATION_SWITCH_PIN PC6 // Optoswitch to Enable Z Probe + #ifndef PROBE_ACTIVATION_SWITCH_PIN + #define PROBE_ACTIVATION_SWITCH_PIN PC6 // Optoswitch to Enable Z Probe + #endif #endif #include "pins_CREALITY_V45x.h" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h index b669887d1eaf0..fd3ea93c32d3e 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h @@ -36,7 +36,9 @@ #define FAN_PIN PB15 // FAN #if ENABLED(PROBE_ACTIVATION_SWITCH) - #define PROBE_ACTIVATION_SWITCH_PIN PB2 // Optoswitch to Enable Z Probe + #ifndef PROBE_ACTIVATION_SWITCH_PIN + #define PROBE_ACTIVATION_SWITCH_PIN PB2 // Optoswitch to Enable Z Probe + #endif #endif #include "pins_CREALITY_V45x.h" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h index 39dccf1271afb..023fca21ce981 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h @@ -64,7 +64,9 @@ // // Probe // -#define PROBE_TARE_PIN PA5 +#ifndef PROBE_TARE_PIN + #define PROBE_TARE_PIN PA5 +#endif // // Steppers 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 762e355626630..0a80c99878a2b 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 @@ -136,7 +136,9 @@ // Probe enable // #if ENABLED(PROBE_ENABLE_DISABLE) - #define PROBE_ENABLE_PIN SERVO0_PIN + #ifndef PROBE_ENABLE_PIN + #define PROBE_ENABLE_PIN SERVO0_PIN + #endif #endif // From 2edda4c58200db4a20af852c30e0ae4accfb5640 Mon Sep 17 00:00:00 2001 From: BigTreeTech <38851044+bigtreetech@users.noreply.github.com> Date: Thu, 18 Nov 2021 01:35:28 +0800 Subject: [PATCH 067/273] =?UTF-8?q?=F0=9F=90=9B=20Init=20PROBE=5FENABLE=5F?= =?UTF-8?q?PIN=20(#23133)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index f2031cdfb9f65..04ee8eb52076e 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1353,6 +1353,9 @@ void setup() { #endif #if HAS_BED_PROBE + #if PIN_EXISTS(PROBE_ENABLE) + OUT_WRITE(PROBE_ENABLE_PIN, LOW); // Disable + #endif SETUP_RUN(endstops.enable_z_probe(false)); #endif From f1af475253941e4ee4cc2bdf05989c623c27a663 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 17 Nov 2021 13:01:44 -0600 Subject: [PATCH 068/273] =?UTF-8?q?=F0=9F=8E=A8=20Misc=20formatting?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp | 5 ++++- Marlin/src/lcd/extui/mks_ui/draw_about.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_advance_settings.h | 2 +- .../src/lcd/extui/mks_ui/draw_auto_level_offset_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_change_speed.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h | 4 ++-- Marlin/src/lcd/extui/mks_ui/draw_dialog.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_error_message.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_extrusion.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_fan.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_filament_change.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_filament_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_gcode.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_home.h | 2 +- .../src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_keyboard.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_language.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_level_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_machine_para.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_machine_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_media_select.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_more.h | 4 ++-- Marlin/src/lcd/extui/mks_ui/draw_motor_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_move_motor.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_number_key.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_operation.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_pause_message.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_pause_position.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_preHeat.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_print_file.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_printing.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_ready_print.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_set.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_step_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_tool.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_ui.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_wifi.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.h | 2 +- Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h | 2 +- Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/pic_manager.h | 2 +- Marlin/src/lcd/extui/mks_ui/printer_operation.h | 2 +- Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h | 2 +- Marlin/src/lcd/extui/mks_ui/wifi_module.h | 2 +- Marlin/src/lcd/extui/mks_ui/wifi_upload.h | 2 +- 57 files changed, 62 insertions(+), 59 deletions(-) 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 7fd335d62eba7..7be84580b1331 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 @@ -208,8 +208,11 @@ uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt } #endif -#elif !ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI, HAS_MARLINUI_HD44780) && HAS_MARLINUI_U8GLIB +#elif NONE(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI, HAS_MARLINUI_HD44780) && HAS_MARLINUI_U8GLIB + #include uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {return 0;} + #endif // HAS_MARLINUI_U8GLIB && !IS_U8GLIB_ST7920 + #endif // __PLAT_NATIVE_SIM__ diff --git a/Marlin/src/lcd/extui/mks_ui/draw_about.h b/Marlin/src/lcd/extui/mks_ui/draw_about.h index 4e7b318eda548..fdb76c5c41457 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_about.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_about.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_about(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.h index e333e0ae51184..0147945edbde8 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_acceleration_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.h index 8848c34451bc3..39c976413662f 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_advance_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_advance_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.h index 38314f6bc2dfa..11c4f0502bbce 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_auto_level_offset_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.h b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.h index f8efeabc40933..f525273887c9b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_baby_stepping.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_baby_stepping(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_change_speed.h b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.h index 66662d8811a16..326e5d33a1204 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_change_speed.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif #define MIN_EXT_SPEED_PERCENT 10 diff --git a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h index ff60f121a1061..1414637ab7c0b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_cloud_bind(); @@ -33,5 +33,5 @@ void display_qrcode(uint8_t *qrcode_data); void cloud_unbind(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.h b/Marlin/src/lcd/extui/mks_ui/draw_dialog.h index 7e98a80c0a2bc..ad26ec639fe11 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_dialog.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif enum { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.h index 575ebbc6a2e67..f71886c855be3 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_eeprom_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_eeprom_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.h index bbf0c34858774..0f57e444362ad 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_encoder_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_encoder_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_error_message.h b/Marlin/src/lcd/extui/mks_ui/draw_error_message.h index 8963e7f477eb0..5a4d75575f964 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_error_message.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_error_message.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif #ifndef PGM_P diff --git a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.h b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.h index 0252767767845..27961bd6a9165 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_extrusion(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_fan.h b/Marlin/src/lcd/extui/mks_ui/draw_fan.h index 0db87eb4f64ea..739d628446425 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_fan.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_fan.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_fan(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_filament_change.h b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.h index d3536a380ad10..8b09708445d49 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_filament_change.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_change.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_filament_change(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.h index 3d190e99c731d..92b4091b6b70a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_filament_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_filament_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_gcode.h b/Marlin/src/lcd/extui/mks_ui/draw_gcode.h index 4e1610431ef9b..df752e7cc9016 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_gcode.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_gcode.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_gcode(bool clear = false); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_home.h b/Marlin/src/lcd/extui/mks_ui/draw_home.h index 7375dc7aa8cb0..ae7ce5f6c2bd4 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_home.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_home.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_home(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.h index e08639137341b..11f0b2f403b59 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_homing_sensitivity_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_homing_sensitivity_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.h index 7f5ffc3ac50de..5b990e1344e50 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_jerk_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_keyboard.h b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.h index d89806c272d4a..0db13cf88eab7 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_keyboard.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_keyboard(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_language.h b/Marlin/src/lcd/extui/mks_ui/draw_language.h index 4f51856f4f554..4f0ceefff22a6 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_language.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_language.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_language(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_level_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_level_settings.h index 06283d20955b3..9b5056753e82b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_level_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_level_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_level_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_machine_para.h b/Marlin/src/lcd/extui/mks_ui/draw_machine_para.h index f495e8b35e5e4..3853e7d9d8216 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_machine_para.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_machine_para.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_machine_para(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.h index f113f65fc1b04..ce12415a5288b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_machine_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_machine_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.h b/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.h index 29c8fa144ed31..4a234a85e7a68 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_manuaLevel.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_manualLevel(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.h index 45c3fd29db22f..802693356fa64 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_max_feedrate_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_max_feedrate_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_media_select.h b/Marlin/src/lcd/extui/mks_ui/draw_media_select.h index a698714a9dce1..2274539277eb5 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_media_select.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_media_select.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif extern void lv_draw_media_select(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_more.h b/Marlin/src/lcd/extui/mks_ui/draw_more.h index 86ee6f895fabc..8e36e9d16ad73 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_more.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_more.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_more(); void lv_clear_more(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.h index 5d26a402d0347..309829aeda324 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_motor_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_motor_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_move_motor.h b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.h index 133a0444c1570..60f55dc1d9a03 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_move_motor.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_move_motor.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_move_motor(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_number_key.h b/Marlin/src/lcd/extui/mks_ui/draw_number_key.h index fcff280d3b52f..62f4e501b333d 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_number_key.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_number_key.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_number_key(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_operation.h b/Marlin/src/lcd/extui/mks_ui/draw_operation.h index d58b3307b8f61..3d89f1dc25a93 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_operation.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_operation.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_operation(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_pause_message.h b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.h index c3df8118a42d2..97ce3988976e2 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_pause_message.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_pause_message(const PauseMessage msg); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_pause_position.h b/Marlin/src/lcd/extui/mks_ui/draw_pause_position.h index fd5459c647674..7dc4c1fbc2f66 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_pause_position.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_position.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_pause_position(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.h b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.h index 023f1228b33a4..ddb488eaa765b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_preHeat(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_print_file.h b/Marlin/src/lcd/extui/mks_ui/draw_print_file.h index 85eadc0a6bcc8..01b0db83fbd1b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_print_file.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_print_file.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif typedef struct { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.h b/Marlin/src/lcd/extui/mks_ui/draw_printing.h index b2a02a62da54a..8055a0746a4ec 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_printing.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif enum { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.h b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.h index 873be528ed1d8..d5582936ce5bf 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_ready_print(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_set.h b/Marlin/src/lcd/extui/mks_ui/draw_set.h index a270308e074e0..11a38ea32f747 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_set.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_set.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_set(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_step_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_step_settings.h index 4f32f0a6c2b05..0678aaa7fe869 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_step_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_step_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_step_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.h index 99589a3a17c78..b3ab95dc69558 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_tmc_current_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.h index aa42d9b87dba2..0f58bb56ad068 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_tmc_step_mode_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tool.h b/Marlin/src/lcd/extui/mks_ui/draw_tool.h index 0dc86b703072c..db65ae5763f0c 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tool.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_tool.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_tool(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.h b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.h index 567256a792e1d..17ec9fc96c262 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_touch_calibration_screen(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.h index 863ff6fc7e845..15c783c362d08 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_tramming_pos_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_tramming_pos_settings(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.h b/Marlin/src/lcd/extui/mks_ui/draw_ui.h index 55ea6220e0765..950386f878e53 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.h @@ -178,7 +178,7 @@ #endif // ifdef TFT35 #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif extern char public_buf_m[100]; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi.h index 4fa642b39c1ed..a89bbd67d8c23 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h index 8dbedf832e78a..81c3a00d4a571 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_list.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif void lv_draw_wifi_list(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.h index ff27397049539..81400856fdd8c 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_settings.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif #define WIFI_AP_TEXT "AP" diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h index 4ffe6c1312a38..ad1523893243e 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif diff --git a/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp b/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp index f3c87c03c4b5d..aca1db0039ba0 100644 --- a/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp +++ b/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp @@ -39,7 +39,7 @@ #include "../../../inc/MarlinConfig.h" #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif #define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.h b/Marlin/src/lcd/extui/mks_ui/pic_manager.h index 95405af1cf24a..320cb20b0b8d5 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.h +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.h @@ -131,7 +131,7 @@ #define OTHERS_COMMAND_ADDR_4 OTHERS_COMMAND_ADDR_3 + 100 #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif union union32 { diff --git a/Marlin/src/lcd/extui/mks_ui/printer_operation.h b/Marlin/src/lcd/extui/mks_ui/printer_operation.h index 499799c6c78be..d9c0b741f23e7 100644 --- a/Marlin/src/lcd/extui/mks_ui/printer_operation.h +++ b/Marlin/src/lcd/extui/mks_ui/printer_operation.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif #define MIN_FILE_PRINTED 100 //5000 diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h index e2786fd452cf2..0790d8323c5d3 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h @@ -27,7 +27,7 @@ */ #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif #include diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.h b/Marlin/src/lcd/extui/mks_ui/wifi_module.h index 15b90ab367c52..36998899b4836 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.h +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif #include "../../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.h b/Marlin/src/lcd/extui/mks_ui/wifi_upload.h index ff98173b9555f..2daa505d9088f 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_upload.h +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ + extern "C" { #endif #define ESP_FIRMWARE_FILE "MksWifi.bin" From e34ca749b1b4a060549c42480d170f6d7440538d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 18 Nov 2021 01:01:47 +0000 Subject: [PATCH 069/273] [cron] Bump distribution date (2021-11-18) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index eb5d6934bb63f..708c628a95337 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 "2021-11-17" +//#define STRING_DISTRIBUTION_DATE "2021-11-18" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b2fa8bac0c391..7f7818ea6e8b4 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 "2021-11-17" + #define STRING_DISTRIBUTION_DATE "2021-11-18" #endif /** From 8e7f2f4483e83edc9ee6f38d632ed2a5f7ad0465 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 19 Nov 2021 01:01:40 +0000 Subject: [PATCH 070/273] [cron] Bump distribution date (2021-11-19) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 708c628a95337..ae7f2d01259df 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 "2021-11-18" +//#define STRING_DISTRIBUTION_DATE "2021-11-19" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7f7818ea6e8b4..2cd02b1ab6588 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 "2021-11-18" + #define STRING_DISTRIBUTION_DATE "2021-11-19" #endif /** From 0293a8340872296dc085394f75a6e68337087d18 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 20 Nov 2021 01:00:26 +0000 Subject: [PATCH 071/273] [cron] Bump distribution date (2021-11-20) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ae7f2d01259df..21e6af29f0179 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 "2021-11-19" +//#define STRING_DISTRIBUTION_DATE "2021-11-20" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2cd02b1ab6588..0f6a8c011cb05 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 "2021-11-19" + #define STRING_DISTRIBUTION_DATE "2021-11-20" #endif /** From 1c31366bf37fcebe91e8e6011af354904dd58ad4 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Sat, 20 Nov 2021 02:44:53 +0100 Subject: [PATCH 072/273] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Reduce=20calls=20t?= =?UTF-8?q?o=20set=20fan=20PWM=20(#23149)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/planner.cpp | 21 +++++++++++++++++---- 1 file changed, 17 insertions(+), 4 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index e19684a7b55a9..28364d4be0b1f 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1311,7 +1311,8 @@ void Planner::check_axes_activity() { #endif #if HAS_TAIL_FAN_SPEED - uint8_t tail_fan_speed[FAN_COUNT]; + static uint8_t tail_fan_speed[FAN_COUNT]; + bool fans_need_update = false; #endif #if ENABLED(BARICUDA) @@ -1330,7 +1331,13 @@ void Planner::check_axes_activity() { #endif #if HAS_TAIL_FAN_SPEED - FANS_LOOP(i) tail_fan_speed[i] = thermalManager.scaledFanSpeed(i, block->fan_speed[i]); + FANS_LOOP(i) { + const uint8_t spd = thermalManager.scaledFanSpeed(i, block->fan_speed[i]); + if (tail_fan_speed[i] != spd) { + fans_need_update = true; + tail_fan_speed[i] = spd; + } + } #endif #if ENABLED(BARICUDA) @@ -1358,7 +1365,13 @@ void Planner::check_axes_activity() { TERN_(HAS_CUTTER, cutter.refresh()); #if HAS_TAIL_FAN_SPEED - FANS_LOOP(i) tail_fan_speed[i] = thermalManager.scaledFanSpeed(i); + FANS_LOOP(i) { + const uint8_t spd = thermalManager.scaledFanSpeed(i); + if (tail_fan_speed[i] != spd) { + fans_need_update = true; + tail_fan_speed[i] = spd; + } + } #endif #if ENABLED(BARICUDA) @@ -1384,7 +1397,7 @@ void Planner::check_axes_activity() { // Update Fan speeds // Only if synchronous M106/M107 is disabled // - TERN_(HAS_TAIL_FAN_SPEED, sync_fan_speeds(tail_fan_speed)); + TERN_(HAS_TAIL_FAN_SPEED, if (fans_need_update) sync_fan_speeds(tail_fan_speed)); TERN_(AUTOTEMP, autotemp_task()); From 2955061b056dba156dc846385285cd6c8633e274 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 21 Nov 2021 01:04:01 +0000 Subject: [PATCH 073/273] [cron] Bump distribution date (2021-11-21) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 21e6af29f0179..0afcc71151d15 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 "2021-11-20" +//#define STRING_DISTRIBUTION_DATE "2021-11-21" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 0f6a8c011cb05..d08ffda113310 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 "2021-11-20" + #define STRING_DISTRIBUTION_DATE "2021-11-21" #endif /** From f33396c2c34be960d81a6a7be1086af90946f262 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Sun, 21 Nov 2021 20:13:01 +0100 Subject: [PATCH 074/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20TFT=20backlight=20?= =?UTF-8?q?sleep/wake=20(#23153)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/tft/touch.cpp | 8 +++++--- Marlin/src/lcd/touch/touch_buttons.cpp | 8 +++++--- 2 files changed, 10 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index dc1f2ecb6c139..a04715a2952d2 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -287,15 +287,17 @@ bool Touch::get_point(int16_t *x, int16_t *y) { #if HAS_TOUCH_SLEEP void Touch::sleepTimeout() { - #if PIN_EXISTS(TFT_BACKLIGHT) - OUT_WRITE(TFT_BACKLIGHT_PIN, LOW); + #if HAS_LCD_BRIGHTNESS + ui.set_brightness(0); + #elif PIN_EXISTS(TFT_BACKLIGHT) + WRITE(TFT_BACKLIGHT_PIN, LOW); #endif next_sleep_ms = TSLP_SLEEPING; } void Touch::wakeUp() { if (isSleeping()) { #if HAS_LCD_BRIGHTNESS - ui._set_brightness(); + ui.set_brightness(ui.brightness); #elif PIN_EXISTS(TFT_BACKLIGHT) WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index feaba8483b279..c15bb08281f22 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -115,15 +115,17 @@ uint8_t TouchButtons::read_buttons() { #if HAS_TOUCH_SLEEP void TouchButtons::sleepTimeout() { - #if PIN_EXISTS(TFT_BACKLIGHT) - OUT_WRITE(TFT_BACKLIGHT_PIN, LOW); + #if HAS_LCD_BRIGHTNESS + ui.set_brightness(0); + #elif PIN_EXISTS(TFT_BACKLIGHT) + WRITE(TFT_BACKLIGHT_PIN, LOW); #endif next_sleep_ms = TSLP_SLEEPING; } void TouchButtons::wakeUp() { if (isSleeping()) { #if HAS_LCD_BRIGHTNESS - ui._set_brightness(); + ui.set_brightness(ui.brightness); #elif PIN_EXISTS(TFT_BACKLIGHT) WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif From 6ac0d4727cd4abe70002c32faf3d87c7e24bfad3 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Sun, 21 Nov 2021 11:25:06 -0800 Subject: [PATCH 075/273] =?UTF-8?q?=E2=9C=A8=20BigTreeTech=20Mini=2012864?= =?UTF-8?q?=20V1.0=20(#23130)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 5 +++++ Marlin/src/HAL/STM32F1/inc/SanityCheck.h | 2 +- Marlin/src/inc/Conditionals_LCD.h | 4 ++-- Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/inc/SanityCheck.h | 4 +++- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 2 +- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 2 +- Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h | 2 +- 10 files changed, 17 insertions(+), 10 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 2c53498d0272c..28040bf1c71f2 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2458,6 +2458,11 @@ //#define FYSETC_MINI_12864_2_1 // Type A/B. NeoPixel RGB Backlight //#define FYSETC_GENERIC_12864_1_1 // Larger display with basic ON/OFF backlight. +// +// BigTreeTech Mini 12864 V1.0 is an alias for FYSETC_MINI_12864_2_1. Type A/B. NeoPixel RGB Backlight. +// +//#define BTT_MINI_12864_V1 + // // Factory display for Creality CR-10 // https://www.aliexpress.com/item/32833148327.html diff --git a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h index 2846155c351d8..fe8f6e0ec24b4 100644 --- a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h @@ -39,7 +39,7 @@ #error "SERIAL_STATS_DROPPED_RX is not supported on the STM32F1 platform." #endif -#if ENABLED(NEOPIXEL_LED) && DISABLED(MKS_MINI_12864_V3) +#if ENABLED(NEOPIXEL_LED) && DISABLED(FYSETC_MINI_12864_2_1) #error "NEOPIXEL_LED (Adafruit NeoPixel) is not supported for HAL/STM32F1. Comment out this line to proceed at your own risk!" #endif diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 7b0c9928685c1..7d8b50f7be007 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -31,8 +31,8 @@ #define MKS_MINI_12864 #endif -// MKS_MINI_12864_V3 is simply identical to FYSETC_MINI_12864_2_1 -#if ENABLED(MKS_MINI_12864_V3) +// 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) #define FYSETC_MINI_12864_2_1 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 8008461547ce9..ae3a8a8bf29c1 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -373,7 +373,7 @@ #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 195 -#elif ENABLED(MKS_MINI_12864_V3) +#elif EITHER(MKS_MINI_12864_V3, BTT_MINI_12864_V1) #define _LCD_CONTRAST_MIN 255 #define _LCD_CONTRAST_INIT 255 #define _LCD_CONTRAST_MAX 255 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 4186e994677d7..959302ee73803 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2630,6 +2630,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS + (ENABLED(U8GLIB_SSD1306) && DISABLED(IS_U8GLIB_SSD1306)) \ + (ENABLED(MINIPANEL) && NONE(MKS_MINI_12864, ENDER2_STOCKDISPLAY)) \ + (ENABLED(MKS_MINI_12864) && NONE(MKS_LCD12864A, MKS_LCD12864B)) \ + + (ENABLED(FYSETC_MINI_12864_2_1) && NONE(MKS_MINI_12864_V3, BTT_MINI_12864_V1)) \ + + COUNT_ENABLED(MKS_MINI_12864_V3, BTT_MINI_12864_V1) \ + (ENABLED(EXTENSIBLE_UI) && DISABLED(IS_EXTUI)) \ + (DISABLED(IS_LEGACY_TFT) && ENABLED(TFT_GENERIC)) \ + (ENABLED(IS_LEGACY_TFT) && COUNT_ENABLED(TFT_320x240, TFT_320x240_SPI, TFT_480x320, TFT_480x320_SPI)) \ @@ -2637,7 +2639,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS, DGUS_LCD_UI_RELOADED) \ + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY) \ + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ - + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_GENERIC_12864_1_1) \ + + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_GENERIC_12864_1_1) \ + COUNT_ENABLED(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) \ + COUNT_ENABLED(MKS_12864OLED, MKS_12864OLED_SSD1306) \ + COUNT_ENABLED(MKS_TS35_V2_0, MKS_ROBIN_TFT24, MKS_ROBIN_TFT28, MKS_ROBIN_TFT32, MKS_ROBIN_TFT35, MKS_ROBIN_TFT43, MKS_ROBIN_TFT_V1_1R, ANET_ET4_TFT28, ANET_ET5_TFT35, BIQU_BX_TFT70, BTT_TFT35_SPI_V1_0) \ diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 06b9721403c1b..67072968974b9 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -314,7 +314,7 @@ #define BEEPER_PIN -1 #endif - #elif ENABLED(MKS_MINI_12864_V3) + #elif ENABLED(FYSETC_MINI_12864_2_1) #define DOGLCD_CS PD13 #define DOGLCD_A0 PC6 #define LCD_PINS_DC DOGLCD_A0 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 025c65a38b24f..c30bb0ac9e99f 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -201,7 +201,7 @@ #define DOGLCD_SCK EXP2_09_PIN #define DOGLCD_MOSI EXP2_05_PIN - #elif ENABLED(MKS_MINI_12864_V3) + #elif ENABLED(FYSETC_MINI_12864_2_1) #define DOGLCD_CS EXP1_08_PIN #define DOGLCD_A0 EXP1_07_PIN #define LCD_PINS_DC DOGLCD_A0 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 1cdee92b088d9..e8d567bc70cfd 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -338,7 +338,7 @@ #define BEEPER_PIN -1 #endif - #elif ENABLED(MKS_MINI_12864_V3) + #elif ENABLED(FYSETC_MINI_12864_2_1) #define DOGLCD_CS PD13 #define DOGLCD_A0 PC6 #define LCD_PINS_DC DOGLCD_A0 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index a7f853185e1dc..00dcade892fe7 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -346,7 +346,7 @@ //#define DOGLCD_SCK EXP2_09_PIN //#define DOGLCD_MOSI EXP2_05_PIN - #elif ENABLED(MKS_MINI_12864_V3) + #elif ENABLED(FYSETC_MINI_12864_2_1) #define DOGLCD_CS EXP1_08_PIN #define DOGLCD_A0 EXP1_07_PIN #define LCD_PINS_DC DOGLCD_A0 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 256439e654dc7..48d2ffef6ec85 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 @@ -335,7 +335,7 @@ //#define MKS_LCD12864B //#undef SHOW_BOOTSCREEN - #elif ENABLED(MKS_MINI_12864_V3) + #elif ENABLED(FYSETC_MINI_12864_2_1) #define DOGLCD_CS EXP1_08_PIN #define DOGLCD_A0 EXP1_07_PIN #define LCD_PINS_DC DOGLCD_A0 From 0fbecf4aaff595bb90b9e7d7556fba3dc40e406c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 22 Nov 2021 01:05:17 +0000 Subject: [PATCH 076/273] [cron] Bump distribution date (2021-11-22) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 0afcc71151d15..d5fa63a955a06 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 "2021-11-21" +//#define STRING_DISTRIBUTION_DATE "2021-11-22" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index d08ffda113310..c71818b136bfb 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 "2021-11-21" + #define STRING_DISTRIBUTION_DATE "2021-11-22" #endif /** From 430a4aec3453b671a531ea7fa2b7dc203ba8769a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 23 Nov 2021 01:01:29 +0000 Subject: [PATCH 077/273] [cron] Bump distribution date (2021-11-23) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index d5fa63a955a06..b025ee39a323c 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 "2021-11-22" +//#define STRING_DISTRIBUTION_DATE "2021-11-23" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c71818b136bfb..71086876afe1a 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 "2021-11-22" + #define STRING_DISTRIBUTION_DATE "2021-11-23" #endif /** From 7110d11c9d8933c8c412c2fabd3b065a5ab97b6e Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Tue, 23 Nov 2021 21:01:53 +0100 Subject: [PATCH 078/273] =?UTF-8?q?=E2=9C=A8=20Fan=20tachometer=20support?= =?UTF-8?q?=20(#23086)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 40 ++++ Marlin/src/MarlinCore.cpp | 7 + Marlin/src/core/language.h | 1 + Marlin/src/feature/fancheck.cpp | 207 ++++++++++++++++++ Marlin/src/feature/fancheck.h | 89 ++++++++ Marlin/src/gcode/control/M999.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 10 + Marlin/src/gcode/gcode.h | 5 + Marlin/src/gcode/temp/M123.cpp | 48 ++++ Marlin/src/inc/Conditionals_post.h | 34 ++- Marlin/src/inc/SanityCheck.h | 25 +++ Marlin/src/lcd/language/language_en.h | 2 + Marlin/src/lcd/language/language_it.h | 3 + Marlin/src/lcd/marlinui.cpp | 4 - Marlin/src/lcd/menu/menu_configuration.cpp | 8 + Marlin/src/module/settings.cpp | 31 +++ Marlin/src/module/temperature.cpp | 67 +++--- Marlin/src/module/temperature.h | 40 +++- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 8 + ini/features.ini | 3 +- platformio.ini | 2 + 21 files changed, 592 insertions(+), 44 deletions(-) create mode 100644 Marlin/src/feature/fancheck.cpp create mode 100644 Marlin/src/feature/fancheck.h create mode 100644 Marlin/src/gcode/temp/M123.cpp diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index c4feba569210e..a1366fc511144 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -603,6 +603,40 @@ #define COOLER_AUTO_FAN_TEMPERATURE 18 #define COOLER_AUTO_FAN_SPEED 255 +/** + * Hotend Cooling Fans tachometers + * + * Define one or more tachometer pins to enable fan speed + * monitoring, and reporting of fan speeds with M123. + * + * NOTE: Only works with fans up to 7000 RPM. + */ +//#define FOURWIRES_FANS // Needed with AUTO_FAN when 4-wire PWM fans are installed +//#define E0_FAN_TACHO_PIN -1 +//#define E0_FAN_TACHO_PULLUP +//#define E0_FAN_TACHO_PULLDOWN +//#define E1_FAN_TACHO_PIN -1 +//#define E1_FAN_TACHO_PULLUP +//#define E1_FAN_TACHO_PULLDOWN +//#define E2_FAN_TACHO_PIN -1 +//#define E2_FAN_TACHO_PULLUP +//#define E2_FAN_TACHO_PULLDOWN +//#define E3_FAN_TACHO_PIN -1 +//#define E3_FAN_TACHO_PULLUP +//#define E3_FAN_TACHO_PULLDOWN +//#define E4_FAN_TACHO_PIN -1 +//#define E4_FAN_TACHO_PULLUP +//#define E4_FAN_TACHO_PULLDOWN +//#define E5_FAN_TACHO_PIN -1 +//#define E5_FAN_TACHO_PULLUP +//#define E5_FAN_TACHO_PULLDOWN +//#define E6_FAN_TACHO_PIN -1 +//#define E6_FAN_TACHO_PULLUP +//#define E6_FAN_TACHO_PULLDOWN +//#define E7_FAN_TACHO_PIN -1 +//#define E7_FAN_TACHO_PULLUP +//#define E7_FAN_TACHO_PULLDOWN + /** * Part-Cooling Fan Multiplexer * @@ -3607,6 +3641,12 @@ */ //#define CNC_COORDINATE_SYSTEMS +/** + * Auto-report fan speed with M123 S + * Requires fans with tachometer pins + */ +//#define AUTO_REPORT_FANS + /** * Auto-report temperatures with M155 S */ diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 04ee8eb52076e..827d2af86466a 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -212,6 +212,10 @@ #include "module/tool_change.h" +#if HAS_FANCHECK + #include "feature/fancheck.h" +#endif + #if ENABLED(USE_CONTROLLER_FAN) #include "feature/controllerfan.h" #endif @@ -829,6 +833,7 @@ void idle(bool no_stepper_sleep/*=false*/) { #if HAS_AUTO_REPORTING if (!gcode.autoreport_paused) { TERN_(AUTO_REPORT_TEMPERATURES, thermalManager.auto_reporter.tick()); + TERN_(AUTO_REPORT_FANS, fan_check.auto_reporter.tick()); TERN_(AUTO_REPORT_SD_STATUS, card.auto_reporter.tick()); TERN_(AUTO_REPORT_POSITION, position_auto_reporter.tick()); TERN_(BUFFER_MONITORING, queue.auto_report_buffer_statistics()); @@ -1275,6 +1280,8 @@ void setup() { SETUP_RUN(controllerFan.setup()); #endif + TERN_(HAS_FANCHECK, fan_check.init()); + // UI must be initialized before EEPROM // (because EEPROM code calls the UI). diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 03bffb8bd9ad4..0a6870af26bf3 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -140,6 +140,7 @@ #define STR_RESEND "Resend: " #define STR_UNKNOWN_COMMAND "Unknown command: \"" #define STR_ACTIVE_EXTRUDER "Active Extruder: " +#define STR_ERR_FANSPEED "Fan speed E" #define STR_PROBE_OFFSET "Probe Offset" #define STR_SKEW_MIN "min_skew_factor: " diff --git a/Marlin/src/feature/fancheck.cpp b/Marlin/src/feature/fancheck.cpp new file mode 100644 index 0000000000000..1b47fadecc314 --- /dev/null +++ b/Marlin/src/feature/fancheck.cpp @@ -0,0 +1,207 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * fancheck.cpp - fan tachometer check + */ + +#include "../inc/MarlinConfig.h" + +#if HAS_FANCHECK + +#include "fancheck.h" +#include "../module/temperature.h" + +#if HAS_AUTO_FAN && EXTRUDER_AUTO_FAN_SPEED != 255 && DISABLED(FOURWIRES_FANS) + bool FanCheck::measuring = false; +#endif +bool FanCheck::tacho_state[TACHO_COUNT]; +uint16_t FanCheck::edge_counter[TACHO_COUNT]; +uint8_t FanCheck::rps[TACHO_COUNT]; +FanCheck::TachoError FanCheck::error = FanCheck::TachoError::NONE; +bool FanCheck::enabled; + +void FanCheck::init() { + #define _TACHINIT(N) TERN(E##N##_FAN_TACHO_PULLUP, SET_INPUT_PULLUP, TERN(E##N##_FAN_TACHO_PULLDOWN, SET_INPUT_PULLDOWN, SET_INPUT))(E##N##_FAN_TACHO_PIN) + #if HAS_E0_FAN_TACHO + _TACHINIT(0); + #endif + #if HAS_E1_FAN_TACHO + _TACHINIT(1); + #endif + #if HAS_E2_FAN_TACHO + _TACHINIT(2); + #endif + #if HAS_E3_FAN_TACHO + _TACHINIT(3); + #endif + #if HAS_E4_FAN_TACHO + _TACHINIT(4); + #endif + #if HAS_E5_FAN_TACHO + _TACHINIT(5); + #endif + #if HAS_E6_FAN_TACHO + _TACHINIT(6); + #endif + #if HAS_E7_FAN_TACHO + _TACHINIT(7); + #endif +} + +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) { + switch (f) { + #if HAS_E0_FAN_TACHO + _TACHO_CASE(0) + #endif + #if HAS_E1_FAN_TACHO + _TACHO_CASE(1) + #endif + #if HAS_E2_FAN_TACHO + _TACHO_CASE(2) + #endif + #if HAS_E3_FAN_TACHO + _TACHO_CASE(3) + #endif + #if HAS_E4_FAN_TACHO + _TACHO_CASE(4) + #endif + #if HAS_E5_FAN_TACHO + _TACHO_CASE(5) + #endif + #if HAS_E6_FAN_TACHO + _TACHO_CASE(6) + #endif + #if HAS_E7_FAN_TACHO + _TACHO_CASE(7) + #endif + default: continue; + } + + if (status != tacho_state[f]) { + if (measuring) ++edge_counter[f]; + tacho_state[f] = status; + } + } +} + +void FanCheck::compute_speed(uint16_t elapsedTime) { + static uint8_t errors_count[TACHO_COUNT]; + static uint8_t fan_reported_errors_msk = 0; + + uint8_t fan_error_msk = 0; + LOOP_L_N(f, TACHO_COUNT) { + switch (f) { + TERN_(HAS_E0_FAN_TACHO, case 0:) + TERN_(HAS_E1_FAN_TACHO, case 1:) + TERN_(HAS_E2_FAN_TACHO, case 2:) + TERN_(HAS_E3_FAN_TACHO, case 3:) + TERN_(HAS_E4_FAN_TACHO, case 4:) + TERN_(HAS_E5_FAN_TACHO, case 5:) + TERN_(HAS_E6_FAN_TACHO, case 6:) + TERN_(HAS_E7_FAN_TACHO, case 7:) + // Compute fan speed + rps[f] = edge_counter[f] * float(250) / elapsedTime; + edge_counter[f] = 0; + + // Check fan speed + constexpr int8_t max_extruder_fan_errors = TERN(HAS_PWMFANCHECK, 10000, 5000) / Temperature::fan_update_interval_ms; + + if (rps[f] >= 20 || TERN0(HAS_AUTO_FAN, thermalManager.autofan_speed[f] == 0)) + errors_count[f] = 0; + else if (errors_count[f] < max_extruder_fan_errors) + ++errors_count[f]; + else if (enabled) + SBI(fan_error_msk, f); + break; + } + } + + // Drop the error when all fans are ok + if (!fan_error_msk && error == TachoError::REPORTED) error = TachoError::FIXED; + + if (error == TachoError::FIXED && !printJobOngoing() && !printingIsPaused()) { + error = TachoError::NONE; // if the issue has been fixed while the printer is idle, reenable immediately + ui.reset_alert_level(); + } + + 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); + } + fan_reported_errors_msk = fan_error_msk; +} + +void FanCheck::report_speed_error(uint8_t fan) { + if (printJobOngoing()) { + if (error == TachoError::NONE) { + if (thermalManager.degTargetHotend(fan) != 0) { + kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT)); + error = TachoError::REPORTED; + } + else + error = TachoError::DETECTED; // Plans error for next processed command + } + } + else if (!printingIsPaused()) { + thermalManager.setTargetHotend(0, fan); // Always disable heating + if (error == TachoError::NONE) error = TachoError::REPORTED; + } + + SERIAL_ERROR_MSG(STR_ERR_FANSPEED, fan); + LCD_ALERTMESSAGE(MSG_FAN_SPEED_FAULT); +} + +void FanCheck::print_fan_states() { + LOOP_L_N(s, 2) { + LOOP_L_N(f, TACHO_COUNT) { + switch (f) { + TERN_(HAS_E0_FAN_TACHO, case 0:) + TERN_(HAS_E1_FAN_TACHO, case 1:) + TERN_(HAS_E2_FAN_TACHO, case 2:) + TERN_(HAS_E3_FAN_TACHO, case 3:) + TERN_(HAS_E4_FAN_TACHO, case 4:) + TERN_(HAS_E5_FAN_TACHO, case 5:) + TERN_(HAS_E6_FAN_TACHO, case 6:) + TERN_(HAS_E7_FAN_TACHO, case 7:) + SERIAL_ECHOPGM("E", f); + if (s == 0) + SERIAL_ECHOPGM(":", 60 * rps[f], " RPM "); + else + SERIAL_ECHOPGM("@:", TERN(HAS_AUTO_FAN, thermalManager.autofan_speed[f], 255), " "); + break; + } + } + } + SERIAL_EOL(); +} + +#if ENABLED(AUTO_REPORT_FANS) + AutoReporter FanCheck::auto_reporter; + void FanCheck::AutoReportFan::report() { print_fan_states(); } +#endif + +#endif // HAS_FANCHECK diff --git a/Marlin/src/feature/fancheck.h b/Marlin/src/feature/fancheck.h new file mode 100644 index 0000000000000..6e8038b498e7c --- /dev/null +++ b/Marlin/src/feature/fancheck.h @@ -0,0 +1,89 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../inc/MarlinConfig.h" + +#if HAS_FANCHECK + +#include "../MarlinCore.h" +#include "../lcd/marlinui.h" + +#if ENABLED(AUTO_REPORT_FANS) + #include "../libs/autoreport.h" +#endif + +#if ENABLED(PARK_HEAD_ON_PAUSE) + #include "../gcode/queue.h" +#endif + +/** + * fancheck.h + */ +#define TACHO_COUNT TERN(HAS_E7_FAN_TACHO, 8, TERN(HAS_E6_FAN_TACHO, 7, TERN(HAS_E5_FAN_TACHO, 6, TERN(HAS_E4_FAN_TACHO, 5, TERN(HAS_E3_FAN_TACHO, 4, TERN(HAS_E2_FAN_TACHO, 3, TERN(HAS_E1_FAN_TACHO, 2, 1))))))) + +class FanCheck { + private: + + enum class TachoError : uint8_t { NONE, DETECTED, REPORTED, FIXED }; + + #if HAS_PWMFANCHECK + static bool measuring; // For future use (3 wires PWM controlled fans) + #else + static constexpr bool measuring = true; + #endif + static bool tacho_state[TACHO_COUNT]; + static uint16_t edge_counter[TACHO_COUNT]; + static uint8_t rps[TACHO_COUNT]; + static TachoError error; + + static inline void report_speed_error(uint8_t fan); + + public: + + static bool enabled; + + static void init(); + static void update_tachometers(); + static void compute_speed(uint16_t elapsedTime); + static void print_fan_states(); + #if HAS_PWMFANCHECK + static inline void toggle_measuring() { measuring = !measuring; } + static inline bool is_measuring() { return measuring; } + #endif + + static inline void check_deferred_error() { + if (error == TachoError::DETECTED) { + error = TachoError::REPORTED; + TERN(PARK_HEAD_ON_PAUSE, queue.inject(F("M125")), kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT))); + } + } + + #if ENABLED(AUTO_REPORT_FANS) + struct AutoReportFan { static void report(); }; + static AutoReporter auto_reporter; + #endif +}; + +extern FanCheck fan_check; + +#endif // HAS_FANCHECK diff --git a/Marlin/src/gcode/control/M999.cpp b/Marlin/src/gcode/control/M999.cpp index b7219673a3d66..b7d6db9f23128 100644 --- a/Marlin/src/gcode/control/M999.cpp +++ b/Marlin/src/gcode/control/M999.cpp @@ -22,7 +22,7 @@ #include "../gcode.h" -#include "../../lcd/marlinui.h" // for lcd_reset_alert_level +#include "../../lcd/marlinui.h" // for ui.reset_alert_level #include "../../MarlinCore.h" // for marlin_state #include "../queue.h" // for flush_and_request_resend diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index b2cb26122fcfa..24eb9914d1f47 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -65,6 +65,10 @@ GcodeSuite gcode; #include "../feature/password/password.h" #endif +#if HAS_FANCHECK + #include "../feature/fancheck.h" +#endif + #include "../MarlinCore.h" // for idle, kill // Inactivity shutdown @@ -296,6 +300,8 @@ void GcodeSuite::dwell(millis_t time) { * Process the parsed command and dispatch it to its handler */ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { + TERN_(HAS_FANCHECK, fan_check.check_deferred_error()); + KEEPALIVE_STATE(IN_HANDLER); /** @@ -577,6 +583,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 113: M113(); break; // M113: Set Host Keepalive interval #endif + #if HAS_FANCHECK + case 123: M123(); break; // M123: Report fan states or set fans auto-report interval + #endif + #if HAS_HEATED_BED case 140: M140(); break; // M140: Set bed temperature case 190: M190(); break; // M190: Wait for bed temperature to reach target diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index d7bacaef32a80..6bfaf00c13921 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -156,6 +156,7 @@ * M121 - Disable endstops detection. * * M122 - Debug stepper (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660 or L6470) + * M123 - Report fan tachometers. (Requires En_FAN_TACHO_PIN) Optionally set auto-report interval. (Requires AUTO_REPORT_FANS) * M125 - Save current position and move to filament change position. (Requires PARK_HEAD_ON_PAUSE) * * M126 - Solenoid Air Valve Open. (Requires BARICUDA) @@ -736,6 +737,10 @@ class GcodeSuite { static void M120(); static void M121(); + #if HAS_FANCHECK + static void M123(); + #endif + #if ENABLED(PARK_HEAD_ON_PAUSE) static void M125(); #endif diff --git a/Marlin/src/gcode/temp/M123.cpp b/Marlin/src/gcode/temp/M123.cpp new file mode 100644 index 0000000000000..389656ef342b5 --- /dev/null +++ b/Marlin/src/gcode/temp/M123.cpp @@ -0,0 +1,48 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if HAS_FANCHECK + +#include "../gcode.h" +#include "../../feature/fancheck.h" + +/** + * M123: Report fan states -or- set interval for auto-report + * + * S : Set auto-report interval + */ +void GcodeSuite::M123() { + + #if ENABLED(AUTO_REPORT_FANS) + if (parser.seenval('S')) { + fan_check.auto_reporter.set_interval(parser.value_byte()); + return; + } + #endif + + fan_check.print_fan_states(); + +} + +#endif // HAS_FANCHECK diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index ae3a8a8bf29c1..d0b5aff5dda3d 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2510,10 +2510,42 @@ #define AUTO_CHAMBER_IS_E 1 #endif +// Fans check +#if HAS_HOTEND && PIN_EXISTS(E0_FAN_TACHO) + #define HAS_E0_FAN_TACHO 1 +#endif +#if HOTENDS > 1 && PIN_EXISTS(E1_FAN_TACHO) + #define HAS_E1_FAN_TACHO 1 +#endif +#if HOTENDS > 2 && PIN_EXISTS(E2_FAN_TACHO) + #define HAS_E2_FAN_TACHO 1 +#endif +#if HOTENDS > 3 && PIN_EXISTS(E3_FAN_TACHO) + #define HAS_E3_FAN_TACHO 1 +#endif +#if HOTENDS > 4 && PIN_EXISTS(E4_FAN_TACHO) + #define HAS_E4_FAN_TACHO 1 +#endif +#if HOTENDS > 5 && PIN_EXISTS(E5_FAN_TACHO) + #define HAS_E5_FAN_TACHO 1 +#endif +#if HOTENDS > 6 && PIN_EXISTS(E6_FAN_TACHO) + #define HAS_E6_FAN_TACHO 1 +#endif +#if HOTENDS > 7 && PIN_EXISTS(E7_FAN_TACHO) + #define HAS_E7_FAN_TACHO 1 +#endif +#if ANY(HAS_E0_FAN_TACHO, HAS_E1_FAN_TACHO, HAS_E2_FAN_TACHO, HAS_E3_FAN_TACHO, HAS_E4_FAN_TACHO, HAS_E5_FAN_TACHO, HAS_E6_FAN_TACHO, HAS_E7_FAN_TACHO) + #define HAS_FANCHECK 1 + #if HAS_AUTO_FAN && EXTRUDER_AUTO_FAN_SPEED != 255 && DISABLED(FOURWIRES_FANS) + #define HAS_PWMFANCHECK 1 + #endif +#endif + #if !HAS_TEMP_SENSOR #undef AUTO_REPORT_TEMPERATURES #endif -#if ANY(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS, AUTO_REPORT_POSITION) +#if ANY(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS, AUTO_REPORT_POSITION, AUTO_REPORT_FANS) #define HAS_AUTO_REPORTING 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 959302ee73803..193750ef2664d 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2583,6 +2583,31 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif +/** + * Fan check + */ +#if HAS_FANCHECK + #if BOTH(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) + #error "Enable only one of E1_FAN_TACHO_PULLUP or E1_FAN_TACHO_PULLDOWN." + #elif BOTH(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) + #error "Enable only one of E3_FAN_TACHO_PULLUP or E3_FAN_TACHO_PULLDOWN." + #elif BOTH(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) + #error "Enable only one of E5_FAN_TACHO_PULLUP or E5_FAN_TACHO_PULLDOWN." + #elif BOTH(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) + #error "Enable only one of E7_FAN_TACHO_PULLUP or E7_FAN_TACHO_PULLDOWN." + #endif +#elif ENABLED(AUTO_REPORT_FANS) + #error "AUTO_REPORT_FANS requires one or more fans with a tachometer pin." +#endif + /** * Make sure only one EEPROM type is enabled */ diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index ecd5ef56601a4..907faa143620e 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -570,6 +570,7 @@ namespace Language_en { LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Runaway Watch: OFF"); LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Runaway Watch: ON"); LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); + LSTR MSG_FAN_SPEED_FAULT = _UxGT("Fan speed fault"); LSTR MSG_CASE_LIGHT = _UxGT("Case Light"); LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Light Brightness"); @@ -613,6 +614,7 @@ namespace Language_en { LSTR MSG_RUNOUT_SENSOR = _UxGT("Runout Sensor"); LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout Dist mm"); LSTR MSG_RUNOUT_ENABLE = _UxGT("Enable Runout"); + LSTR MSG_FANCHECK = _UxGT("Fan Tacho Check"); LSTR MSG_KILL_HOMING_FAILED = _UxGT("Homing Failed"); LSTR MSG_LCD_PROBING_FAILED = _UxGT("Probing Failed"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 44ae49b519af4..1720c0a93ac80 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -556,6 +556,7 @@ namespace Language_it { LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Controllo fuga: OFF"); LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Controllo fuga: ON"); LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Timeout inatt.ugello"); + LSTR MSG_FAN_SPEED_FAULT = _UxGT("Err.vel.della ventola"); LSTR MSG_CASE_LIGHT = _UxGT("Luci Case"); LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Luminosità Luci"); @@ -597,6 +598,8 @@ namespace Language_it { LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Ugello: "); LSTR MSG_RUNOUT_SENSOR = _UxGT("Sens.filo termin."); // Max 17 characters LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm filo term."); + LSTR MSG_RUNOUT_ENABLE = _UxGT("Abil.filo termin."); + LSTR MSG_FANCHECK = _UxGT("Verif.tacho vent."); // Max 17 characters LSTR MSG_KILL_HOMING_FAILED = _UxGT("Home fallito"); LSTR MSG_LCD_PROBING_FAILED = _UxGT("Sondaggio fallito"); diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 57157d2c00ce8..5cf3e668260b4 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1566,10 +1566,6 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; TERN_(HAS_LCD_MENU, return_to_status()); } - #if ANY(PARK_HEAD_ON_PAUSE, SDSUPPORT) - #include "../gcode/queue.h" - #endif - void MarlinUI::pause_print() { #if HAS_LCD_MENU synchronize(GET_TEXT(MSG_PAUSING)); diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index b976224b8c534..cd8bad9c8ba4c 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -34,6 +34,10 @@ #include "../../feature/runout.h" #endif +#if HAS_FANCHECK + #include "../../feature/fancheck.h" +#endif + #if ENABLED(POWER_LOSS_RECOVERY) #include "../../feature/powerloss.h" #endif @@ -537,6 +541,10 @@ void menu_configuration() { EDIT_ITEM(bool, MSG_RUNOUT_SENSOR, &runout.enabled, runout.reset); #endif + #if HAS_FANCHECK + EDIT_ITEM(bool, MSG_FANCHECK, &fan_check.enabled); + #endif + #if ENABLED(POWER_LOSS_RECOVERY) EDIT_ITEM(bool, MSG_OUTAGE_RECOVERY, &recovery.enabled, recovery.changed); #endif diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 0cb29f29e0f16..4057d339dc7d2 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -154,6 +154,10 @@ #include "../libs/buzzer.h" #endif +#if HAS_FANCHECK + #include "../feature/fancheck.h" +#endif + #if ENABLED(DGUS_LCD_UI_MKS) #include "../lcd/extui/dgus/DGUSScreenHandler.h" #include "../lcd/extui/dgus/DGUSDisplayDef.h" @@ -491,6 +495,13 @@ typedef struct SettingsDataStruct { bool buzzer_enabled; #endif + // + // Fan tachometer check + // + #if HAS_FANCHECK + bool fan_check_enabled; + #endif + // // MKS UI controller // @@ -1433,6 +1444,13 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(ui.buzzer_enabled); #endif + // + // Fan tachometer check + // + #if HAS_FANCHECK + EEPROM_WRITE(fan_check.enabled); + #endif + // // MKS UI controller // @@ -2339,6 +2357,14 @@ void MarlinSettings::postprocess() { EEPROM_READ(ui.buzzer_enabled); #endif + // + // Fan tachometer check + // + #if HAS_FANCHECK + _FIELD_TEST(fan_check_enabled); + EEPROM_READ(fan_check.enabled); + #endif + // // MKS UI controller // @@ -3036,6 +3062,11 @@ void MarlinSettings::reset() { #endif #endif + // + // Fan tachometer check + // + TERN_(HAS_FANCHECK, fan_check.enabled = true); + // // MKS UI controller // diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index ede8aa73acb7a..7afec4408e386 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -294,7 +294,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); redundant_info_t Temperature::temp_redundant; #endif -#if ENABLED(AUTO_POWER_E_FANS) +#if EITHER(AUTO_POWER_E_FANS, HAS_FANCHECK) uint8_t Temperature::autofan_speed[HOTENDS]; // = { 0 } #endif @@ -526,8 +526,9 @@ volatile bool Temperature::raw_temps_ready = false; millis_t Temperature::preheat_end_time[HOTENDS] = { 0 }; #endif -#if HAS_AUTO_FAN - millis_t Temperature::next_auto_fan_check_ms = 0; +#if HAS_FAN_LOGIC + constexpr millis_t Temperature::fan_update_interval_ms; + millis_t Temperature::fan_update_ms = 0; #endif #if ENABLED(FAN_SOFT_PWM) @@ -614,7 +615,7 @@ volatile bool Temperature::raw_temps_ready = false; bool heated = false; #endif - TERN_(HAS_AUTO_FAN, next_auto_fan_check_ms = next_temp_ms + 2500UL); + TERN_(HAS_FAN_LOGIC, fan_update_ms = next_temp_ms + fan_update_interval_ms); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_STARTED)); TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(isbed ? PID_BED_START : PID_EXTR_START)); @@ -659,12 +660,7 @@ volatile bool Temperature::raw_temps_ready = false; ONHEATING(start_temp, current_temp, target); #endif - #if HAS_AUTO_FAN - if (ELAPSED(ms, next_auto_fan_check_ms)) { - checkExtruderAutoFans(); - next_auto_fan_check_ms = ms + 2500UL; - } - #endif + TERN_(HAS_FAN_LOGIC, manage_extruder_fans(ms)); if (heating && current_temp > target && ELAPSED(ms, t2 + 5000UL)) { heating = false; @@ -853,6 +849,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #define _EFANOVERLAP(A,B) _FANOVERLAP(E##A,B) #if HAS_AUTO_FAN + #if EXTRUDER_AUTO_FAN_SPEED != 255 #define INIT_E_AUTO_FAN_PIN(P) do{ if (P == FAN1_PIN || P == FAN2_PIN) { SET_PWM(P); SET_FAST_PWM_FREQ(P); } else SET_OUTPUT(P); }while(0) #else @@ -866,7 +863,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #define CHAMBER_FAN_INDEX HOTENDS - void Temperature::checkExtruderAutoFans() { + void Temperature::update_autofans() { #define _EFAN(B,A) _EFANOVERLAP(A,B) ? B : static const uint8_t fanBit[] PROGMEM = { 0 @@ -914,36 +911,43 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { break; #endif default: - #if ENABLED(AUTO_POWER_E_FANS) + #if EITHER(AUTO_POWER_E_FANS, HAS_FANCHECK) autofan_speed[realFan] = fan_on ? EXTRUDER_AUTO_FAN_SPEED : 0; #endif break; } + #if BOTH(HAS_FANCHECK, HAS_PWMFANCHECK) + #define _AUTOFAN_SPEED() fan_check.is_measuring() ? 255 : EXTRUDER_AUTO_FAN_SPEED + #else + #define _AUTOFAN_SPEED() 255 + #endif + #define _AUTOFAN_CASE(N) case N: _UPDATE_AUTO_FAN(E##N, fan_on, _AUTOFAN_SPEED()); break + switch (f) { #if HAS_AUTO_FAN_0 - case 0: _UPDATE_AUTO_FAN(E0, fan_on, EXTRUDER_AUTO_FAN_SPEED); break; + _AUTOFAN_CASE(0); #endif #if HAS_AUTO_FAN_1 - case 1: _UPDATE_AUTO_FAN(E1, fan_on, EXTRUDER_AUTO_FAN_SPEED); break; + _AUTOFAN_CASE(1); #endif #if HAS_AUTO_FAN_2 - case 2: _UPDATE_AUTO_FAN(E2, fan_on, EXTRUDER_AUTO_FAN_SPEED); break; + _AUTOFAN_CASE(2); #endif #if HAS_AUTO_FAN_3 - case 3: _UPDATE_AUTO_FAN(E3, fan_on, EXTRUDER_AUTO_FAN_SPEED); break; + _AUTOFAN_CASE(3); #endif #if HAS_AUTO_FAN_4 - case 4: _UPDATE_AUTO_FAN(E4, fan_on, EXTRUDER_AUTO_FAN_SPEED); break; + _AUTOFAN_CASE(4); #endif #if HAS_AUTO_FAN_5 - case 5: _UPDATE_AUTO_FAN(E5, fan_on, EXTRUDER_AUTO_FAN_SPEED); break; + _AUTOFAN_CASE(5); #endif #if HAS_AUTO_FAN_6 - case 6: _UPDATE_AUTO_FAN(E6, fan_on, EXTRUDER_AUTO_FAN_SPEED); break; + _AUTOFAN_CASE(6); #endif #if HAS_AUTO_FAN_7 - case 7: _UPDATE_AUTO_FAN(E7, fan_on, EXTRUDER_AUTO_FAN_SPEED); break; + _AUTOFAN_CASE(7); #endif #if HAS_AUTO_CHAMBER_FAN && !AUTO_CHAMBER_IS_E case CHAMBER_FAN_INDEX: _UPDATE_AUTO_FAN(CHAMBER, fan_on, CHAMBER_AUTO_FAN_SPEED); break; @@ -1367,20 +1371,14 @@ void Temperature::manage_heater() { _temp_error((heater_id_t)HEATER_ID(TEMP_SENSOR_REDUNDANT_TARGET), F(STR_REDUNDANCY), GET_TEXT_F(MSG_ERR_REDUNDANT_TEMP)); #endif - #if HAS_AUTO_FAN - if (ELAPSED(ms, next_auto_fan_check_ms)) { // only need to check fan state very infrequently - checkExtruderAutoFans(); - next_auto_fan_check_ms = ms + 2500UL; - } - #endif + // Manage extruder auto fans and/or read fan tachometers + TERN_(HAS_FAN_LOGIC, manage_extruder_fans(ms)); - #if ENABLED(FILAMENT_WIDTH_SENSOR) - /** - * Dynamically set the volumetric multiplier based - * on the delayed Filament Width measurement. - */ - filwidth.update_volumetric(); - #endif + /** + * Dynamically set the volumetric multiplier based + * on the delayed Filament Width measurement. + */ + TERN_(FILAMENT_WIDTH_SENSOR, filwidth.update_volumetric()); #if HAS_HEATED_BED @@ -3501,6 +3499,9 @@ void Temperature::isr() { babystep.task(); #endif + // Check fan tachometers + TERN_(HAS_FANCHECK, fan_check.update_tachometers()); + // Poll endstops state, if required endstops.poll(); diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 050b3379e9198..0e4302938eda6 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -37,6 +37,10 @@ #include "../libs/autoreport.h" #endif +#if HAS_FANCHECK + #include "../feature/fancheck.h" +#endif + #ifndef SOFT_PWM_SCALE #define SOFT_PWM_SCALE 0 #endif @@ -344,6 +348,10 @@ typedef struct { int16_t raw_min, raw_max; celsius_t mintemp, maxtemp; } temp_ra #endif +#if HAS_AUTO_FAN || HAS_FANCHECK + #define HAS_FAN_LOGIC 1 +#endif + class Temperature { public: @@ -372,7 +380,7 @@ class Temperature { static redundant_info_t temp_redundant; #endif - #if ENABLED(AUTO_POWER_E_FANS) + #if EITHER(AUTO_POWER_E_FANS, HAS_FANCHECK) static uint8_t autofan_speed[HOTENDS]; #endif #if ENABLED(AUTO_POWER_CHAMBER_FAN) @@ -459,6 +467,10 @@ class Temperature { static int16_t lpq_len; #endif + #if HAS_FAN_LOGIC + static constexpr millis_t fan_update_interval_ms = TERN(HAS_PWMFANCHECK, 5000, TERN(HAS_FANCHECK, 1000, 2500)); + #endif + private: #if ENABLED(WATCH_HOTENDS) @@ -510,8 +522,28 @@ class Temperature { static millis_t preheat_end_time[HOTENDS]; #endif - #if HAS_AUTO_FAN - static millis_t next_auto_fan_check_ms; + #if HAS_FAN_LOGIC + static millis_t fan_update_ms; + + static inline void manage_extruder_fans(millis_t ms) { + if (ELAPSED(ms, fan_update_ms)) { // only need to check fan state very infrequently + const millis_t next_ms = ms + fan_update_interval_ms; + #if HAS_PWMFANCHECK + #define FAN_CHECK_DURATION 100 + if (fan_check.is_measuring()) { + fan_check.compute_speed(ms + FAN_CHECK_DURATION - fan_update_ms); + fan_update_ms = next_ms; + } + else + fan_update_ms = ms + FAN_CHECK_DURATION; + fan_check.toggle_measuring(); + #else + TERN_(HAS_FANCHECK, fan_check.compute_speed(next_ms - fan_update_ms)); + fan_update_ms = next_ms; + #endif + TERN_(HAS_AUTO_FAN, update_autofans()); // Needed as last when HAS_PWMFANCHECK to properly force fan speed + } + } #endif #if ENABLED(PROBING_HEATERS_OFF) @@ -961,7 +993,7 @@ class Temperature { static int16_t read_max_tc(TERN_(HAS_MULTI_MAX_TC, const uint8_t hindex=0)); #endif - static void checkExtruderAutoFans(); + static void update_autofans(); #if HAS_HOTEND static float get_pid_output_hotend(const uint8_t e); 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 7b99352ef4952..602c8b05480fd 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -188,6 +188,14 @@ #endif #endif +#ifndef E0_FAN_TACHO_PIN + #ifdef MK3_FAN_PINS + #define E0_FAN_TACHO_PIN PE0 // Fan1 + #else + #define E0_FAN_TACHO_PIN PE1 // Fan0 + #endif +#endif + /** * -----------------------------------BTT002 V1.0---------------------------------------- * ------ ------ | diff --git a/ini/features.ini b/ini/features.ini index 4c146512989f7..606370e07a6a8 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -107,6 +107,7 @@ CANCEL_OBJECTS = src_filter=+ + EXTERNAL_CLOSED_LOOP_CONTROLLER = src_filter=+ + USE_CONTROLLER_FAN = src_filter=+ +HAS_COOLER|LASER_COOLANT_FLOW_METER = src_filter=+ HAS_MOTOR_CURRENT_DAC = src_filter=+ DIRECT_STEPPING = src_filter=+ + EMERGENCY_PARSER = src_filter=+ - @@ -114,6 +115,7 @@ I2C_POSITION_ENCODERS = src_filter=+ HAS_SPI_FLASH = src_filter=+ HAS_ETHERNET = src_filter=+ + +HAS_FANCHECK = src_filter=+ + HAS_FANMUX = src_filter=+ FILAMENT_WIDTH_SENSOR = src_filter=+ + FWRETRACT = src_filter=+ + @@ -211,7 +213,6 @@ GCODE_REPEAT_MARKERS = src_filter=+ +< HAS_EXTRUDERS = src_filter=+ + + HAS_TEMP_PROBE = src_filter=+ HAS_COOLER = src_filter=+ -HAS_COOLER|LASER_COOLANT_FLOW_METER = src_filter=+ AUTO_REPORT_TEMPERATURES = src_filter=+ INCH_MODE_SUPPORT = src_filter=+ TEMPERATURE_UNITS_SUPPORT = src_filter=+ diff --git a/platformio.ini b/platformio.ini index a364e8920f754..0be12fb6ae8f3 100644 --- a/platformio.ini +++ b/platformio.ini @@ -111,6 +111,7 @@ default_src_filter = + - - + - - - - + - - - - - - @@ -228,6 +229,7 @@ default_src_filter = + - - + - - - + - - - - From 5387ceba74862788d27b62f8624a2c697fe233ee Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Tue, 23 Nov 2021 14:05:50 -0600 Subject: [PATCH 079/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20STM32=20set=5Fpwm?= =?UTF-8?q?=5Fduty=20(#23125)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/MarlinSPI.cpp | 11 ++-- Marlin/src/HAL/STM32/fast_pwm.cpp | 72 +++++++++++++++------ Marlin/src/HAL/STM32/tft/tft_spi.cpp | 12 ++-- Marlin/src/HAL/STM32F1/HAL.h | 6 +- Marlin/src/HAL/STM32F1/fast_pwm.cpp | 50 +++++++------- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 2 +- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 1 - 7 files changed, 95 insertions(+), 59 deletions(-) diff --git a/Marlin/src/HAL/STM32/MarlinSPI.cpp b/Marlin/src/HAL/STM32/MarlinSPI.cpp index 7078d210dc4c0..f7c603d77e5cf 100644 --- a/Marlin/src/HAL/STM32/MarlinSPI.cpp +++ b/Marlin/src/HAL/STM32/MarlinSPI.cpp @@ -114,16 +114,19 @@ byte MarlinSPI::transfer(uint8_t _data) { return rxData; } +__STATIC_INLINE void LL_SPI_EnableDMAReq_RX(SPI_TypeDef *SPIx) { SET_BIT(SPIx->CR2, SPI_CR2_RXDMAEN); } +__STATIC_INLINE void LL_SPI_EnableDMAReq_TX(SPI_TypeDef *SPIx) { SET_BIT(SPIx->CR2, SPI_CR2_TXDMAEN); } + uint8_t MarlinSPI::dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16_t length) { const uint8_t ff = 0xFF; - //if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) //only enable if disabled + //if (!LL_SPI_IsEnabled(_spi.handle)) // only enable if disabled __HAL_SPI_ENABLE(&_spi.handle); if (receiveBuf) { setupDma(_spi.handle, _dmaRx, DMA_PERIPH_TO_MEMORY, true); HAL_DMA_Start(&_dmaRx, (uint32_t)&(_spi.handle.Instance->DR), (uint32_t)receiveBuf, length); - SET_BIT(_spi.handle.Instance->CR2, SPI_CR2_RXDMAEN); /* Enable Rx DMA Request */ + LL_SPI_EnableDMAReq_RX(_spi.handle.Instance); // Enable Rx DMA Request } // check for 2 lines transfer @@ -136,7 +139,7 @@ uint8_t MarlinSPI::dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16 if (transmitBuf) { setupDma(_spi.handle, _dmaTx, DMA_MEMORY_TO_PERIPH, mincTransmit); HAL_DMA_Start(&_dmaTx, (uint32_t)transmitBuf, (uint32_t)&(_spi.handle.Instance->DR), length); - SET_BIT(_spi.handle.Instance->CR2, SPI_CR2_TXDMAEN); /* Enable Tx DMA Request */ + LL_SPI_EnableDMAReq_TX(_spi.handle.Instance); // Enable Tx DMA Request } if (transmitBuf) { @@ -160,7 +163,7 @@ uint8_t MarlinSPI::dmaSend(const void * transmitBuf, uint16_t length, bool minc) setupDma(_spi.handle, _dmaTx, DMA_MEMORY_TO_PERIPH, minc); HAL_DMA_Start(&_dmaTx, (uint32_t)transmitBuf, (uint32_t)&(_spi.handle.Instance->DR), length); __HAL_SPI_ENABLE(&_spi.handle); - SET_BIT(_spi.handle.Instance->CR2, SPI_CR2_TXDMAEN); /* Enable Tx DMA Request */ + LL_SPI_EnableDMAReq_TX(_spi.handle.Instance); // Enable Tx DMA Request HAL_DMA_PollForTransfer(&_dmaTx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); HAL_DMA_Abort(&_dmaTx); // DeInit objects diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index 4d450374d32ba..4986e138a181d 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -27,37 +27,67 @@ #include "../../inc/MarlinConfig.h" #include "timers.h" -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { - if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer +// Array to support sticky frequency sets per timer +static uint16_t timer_freq[TIMER_NUM]; +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { + if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer + bool needs_freq; PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); + HardwareTimer *HT; + TimerModes_t previousMode; - uint16_t adj_val = Instance->ARR * v / v_size; - if (invert) adj_val = Instance->ARR - adj_val; - switch (get_pwm_channel(pin_name)) { - case TIM_CHANNEL_1: LL_TIM_OC_SetCompareCH1(Instance, adj_val); break; - case TIM_CHANNEL_2: LL_TIM_OC_SetCompareCH2(Instance, adj_val); break; - case TIM_CHANNEL_3: LL_TIM_OC_SetCompareCH3(Instance, adj_val); break; - case TIM_CHANNEL_4: LL_TIM_OC_SetCompareCH4(Instance, adj_val); break; - } -} + uint16_t value = v; + if (invert) value = v_size - value; -#if NEEDS_HARDWARE_PWM + uint32_t index = get_timer_index(Instance); - void set_pwm_frequency(const pin_t pin, int f_desired) { - if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer + if (HardwareTimer_Handle[index] == nullptr) { + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM)); + needs_freq = true; // The instance must be new set the default frequency of PWM_FREQUENCY + } - PinName pin_name = digitalPinToPinName(pin); - TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance + HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin_name, PinMap_PWM)); + previousMode = HT->getMode(channel); - LOOP_S_L_N(i, 0, NUM_HARDWARE_TIMERS) // Protect used timers - if (timer_instance[i] && timer_instance[i]->getHandle()->Instance == Instance) - return; + if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) + HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, pin); - pwm_start(pin_name, f_desired, 0, RESOLUTION_8B_COMPARE_FORMAT); + if (needs_freq) { + if (timer_freq[index] == 0 ) { // If the timer is unconfigured and no freq is set then default PWM_FREQUENCY. + timer_freq[index] = PWM_FREQUENCY; + set_pwm_frequency(pin_name, timer_freq[index]); // Set the frequency and save the value to the assigned index no. + } } + // Note the resolution is sticky here, the input can be upto 16 bits and that would require RESOLUTION_16B_COMPARE_FORMAT (16) + // If such a need were to manifest then we would need to calc the resolution based on the v_size parameter and add code for it. + HT->setCaptureCompare(channel, value, RESOLUTION_8B_COMPARE_FORMAT); // Sets the duty, the calc is done in the library :) + pinmap_pinout(pin_name, PinMap_PWM); // Make sure the pin output state is set. + if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume(); +} -#endif +void set_pwm_frequency(const pin_t pin, int f_desired) { + if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer + HardwareTimer *HT; + PinName pin_name = digitalPinToPinName(pin); + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance + + uint32_t index = get_timer_index(Instance); + + // Protect used timers + if (index == TEMP_TIMER_NUM || index == STEP_TIMER_NUM + #if PULSE_TIMER_NUM != STEP_TIMER_NUM + || index == PULSE_TIMER_NUM + #endif + ) return; + + if (HardwareTimer_Handle[index] == nullptr) // If frequency is set before duty we need to create a handle here. + HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM)); + HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + timer_freq[index] = f_desired; // Save the last frequency so duty will not set the default for this timer number. + HT->setOverflow(f_desired, HERTZ_FORMAT); +} #endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index 790513e7edd97..4ad35cee8ba30 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -161,11 +161,11 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { for (i = 0; i < 4; i++) { #if TFT_MISO_PIN != TFT_MOSI_PIN //if (hspi->Init.Direction == SPI_DIRECTION_2LINES) { - while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {} + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {} SPIx.Instance->DR = 0; //} #endif - while ((SPIx.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {} + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_RXNE)) {} Data = (Data << 8) | SPIx.Instance->DR; } @@ -195,8 +195,8 @@ bool TFT_SPI::isBusy() { void TFT_SPI::Abort() { // Wait for any running spi - while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {} - while ((SPIx.Instance->SR & SPI_FLAG_BSY) == SPI_FLAG_BSY) {} + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {} + while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) {} // First, abort any running dma HAL_DMA_Abort(&DMAtx); // DeInit objects @@ -214,8 +214,8 @@ void TFT_SPI::Transmit(uint16_t Data) { SPIx.Instance->DR = Data; - while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {} - while ((SPIx.Instance->SR & SPI_FLAG_BSY) == SPI_FLAG_BSY) {} + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {} + while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) {} if (TFT_MISO_PIN != TFT_MOSI_PIN) __HAL_SPI_CLEAR_OVRFLAG(&SPIx); // Clear overrun flag in 2 Lines communication mode because received is not read diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 3bdfb9703c643..026e83bc0d7b0 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -264,7 +264,10 @@ void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? #define PLATFORM_M997_SUPPORT void flashFirmware(const int16_t); -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment +#ifndef PWM_FREQUENCY + #define PWM_FREQUENCY 1000 // Default PWM Frequency +#endif +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment /** * set_pwm_frequency @@ -278,5 +281,6 @@ void set_pwm_frequency(const pin_t pin, int f_desired); * Set the PWM duty cycle of the provided pin to the provided value * Optionally allows inverting the duty cycle [default = false] * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] + * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. */ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp index 5171c11545f5b..b510a4c8a022b 100644 --- a/Marlin/src/HAL/STM32F1/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp @@ -30,40 +30,40 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!PWM_PIN(pin)) return; timer_dev *timer = PIN_MAP[pin].timer_device; + if (!(timer->regs.bas->SR & TIMER_CR1_CEN)) // Ensure the timer is enabled + set_pwm_frequency(pin, PWM_FREQUENCY); uint16_t max_val = timer->regs.bas->ARR * v / v_size; if (invert) max_val = v_size - max_val; pwmWrite(pin, max_val); -} -#if NEEDS_HARDWARE_PWM +} - void set_pwm_frequency(const pin_t pin, int f_desired) { - if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer +void set_pwm_frequency(const pin_t pin, int f_desired) { + if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer - timer_dev *timer = PIN_MAP[pin].timer_device; - uint8_t channel = PIN_MAP[pin].timer_channel; + timer_dev *timer = PIN_MAP[pin].timer_device; + uint8_t channel = PIN_MAP[pin].timer_channel; - // Protect used timers - if (timer == get_timer_dev(TEMP_TIMER_NUM)) return; - if (timer == get_timer_dev(STEP_TIMER_NUM)) return; - #if PULSE_TIMER_NUM != STEP_TIMER_NUM - if (timer == get_timer_dev(PULSE_TIMER_NUM)) return; - #endif + // Protect used timers + if (timer == get_timer_dev(TEMP_TIMER_NUM)) return; + if (timer == get_timer_dev(STEP_TIMER_NUM)) return; + #if PULSE_TIMER_NUM != STEP_TIMER_NUM + if (timer == get_timer_dev(PULSE_TIMER_NUM)) return; + #endif - if (!(timer->regs.bas->SR & TIMER_CR1_CEN)) // Ensure the timer is enabled - timer_init(timer); + if (!(timer->regs.bas->SR & TIMER_CR1_CEN)) // Ensure the timer is enabled + timer_init(timer); - timer_set_mode(timer, channel, TIMER_PWM); - uint16_t preload = 255; // Lock 255 PWM resolution for high frequencies - int32_t prescaler = (HAL_TIMER_RATE) / (preload + 1) / f_desired - 1; - if (prescaler > 65535) { // For low frequencies increase prescaler - prescaler = 65535; - preload = (HAL_TIMER_RATE) / (prescaler + 1) / f_desired - 1; - } - if (prescaler < 0) return; // Too high frequency - timer_set_reload(timer, preload); - timer_set_prescaler(timer, prescaler); + timer_set_mode(timer, channel, TIMER_PWM); + uint16_t preload = 255; // Lock 255 PWM resolution for high frequencies + int32_t prescaler = (HAL_TIMER_RATE) / (preload + 1) / f_desired - 1; + if (prescaler > 65535) { // For low frequencies increase prescaler + prescaler = 65535; + preload = (HAL_TIMER_RATE) / (prescaler + 1) / f_desired - 1; } + if (prescaler < 0) return; // Too high frequency + timer_set_reload(timer, preload); + timer_set_prescaler(timer, prescaler); +} -#endif // NEEDS_HARDWARE_PWM #endif // __STM32F1__ diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index f56d68366cbc0..cc8458ce43efc 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -345,7 +345,7 @@ static bool longName2DosName(const char *longName, char *dosName) { hdma->DmaBaseAddress->IFCR = (DMA_ISR_GIF1 << hdma->ChannelIndex); SET_BIT(hdma->ErrorCode, HAL_DMA_ERROR_TE); // Update error code - hdma->State= HAL_DMA_STATE_READY; // Change the DMA state + hdma->State = HAL_DMA_STATE_READY; // Change the DMA state __HAL_UNLOCK(hdma); // Process Unlocked return HAL_ERROR; } diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index 3a8019a27e9c6..c6f1e014e0760 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -96,7 +96,6 @@ #else #define FAST_PWM_FAN // STM32 Variant allow TIMER2 Hardware PWM #define FAST_PWM_FAN_FREQUENCY 31400 // This frequency allow a good range, fan starts at 3%, half noise at 50% - #define NEEDS_HARDWARE_PWM 1 #define FAN_MIN_PWM 5 #define FAN_MAX_PWM 255 #endif From de398b4fd2f96349e73d63512021a3fca800712d Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Wed, 24 Nov 2021 04:19:32 +0700 Subject: [PATCH 080/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20serial=5Fdata=5Fav?= =?UTF-8?q?ailable=20(#23160)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/queue.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index fd98a39cd6cb7..cc52a3bb9e805 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -281,7 +281,7 @@ void GCodeQueue::flush_and_request_resend(const serial_index_t serial_ind) { static bool serial_data_available(serial_index_t index) { const int a = SERIAL_IMPL.available(index); - #if BOTH(RX_BUFFER_MONITOR, RX_BUFFER_SIZE) + #if ENABLED(RX_BUFFER_MONITOR) && RX_BUFFER_SIZE if (a > RX_BUFFER_SIZE - 2) { PORT_REDIRECT(SERIAL_PORTMASK(index)); SERIAL_ERROR_MSG("RX BUF overflow, increase RX_BUFFER_SIZE: ", a); From e5154ec28179c7dc7b58a830412e7cb09c2f878c Mon Sep 17 00:00:00 2001 From: John Robertson Date: Tue, 23 Nov 2021 21:24:24 +0000 Subject: [PATCH 081/273] =?UTF-8?q?=E2=9C=A8=20MarkForged=20YX=20kinematic?= =?UTF-8?q?s=20(#23163)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 1 + Marlin/src/core/types.h | 2 +- Marlin/src/core/utility.cpp | 3 +- Marlin/src/feature/backlash.cpp | 2 +- Marlin/src/gcode/host/M360.cpp | 3 +- Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/inc/SanityCheck.h | 16 ++--- Marlin/src/lcd/menu/menu_backlash.cpp | 2 +- Marlin/src/module/endstops.cpp | 10 +-- Marlin/src/module/motion.cpp | 12 ++-- Marlin/src/module/planner.cpp | 99 ++++++++++++++------------- Marlin/src/module/stepper.cpp | 14 +++- 13 files changed, 92 insertions(+), 76 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 28040bf1c71f2..060c07bbbc794 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -756,6 +756,7 @@ //#define COREZX //#define COREZY //#define MARKFORGED_XY // MarkForged. See https://reprap.org/forum/read.php?152,504042 +//#define MARKFORGED_YX // Enable for a belt style printer with endless "Z" motion //#define BELTPRINTER diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 72099fb408737..9a5b64c22e864 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -82,7 +82,7 @@ enum AxisEnum : uint8_t { #undef _EN_ITEM // Core also keeps toolhead directions - #if EITHER(IS_CORE, MARKFORGED_XY) + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) , X_HEAD, Y_HEAD, Z_HEAD #endif diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index b70e2fa9a94d9..cc3b1ace2fdbf 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -60,7 +60,8 @@ void safe_delay(millis_t ms) { TERN_(DELTA, "Delta") TERN_(IS_SCARA, "SCARA") TERN_(IS_CORE, "Core") - TERN_(MARKFORGED_XY, "MarkForged") + TERN_(MARKFORGED_XY, "MarkForgedXY") + TERN_(MARKFORGED_YX, "MarkForgedYX") TERN_(IS_CARTESIAN, "Cartesian") ); diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index b646e19f15aba..24c0f2ca0c159 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -64,7 +64,7 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const static axis_bits_t last_direction_bits; axis_bits_t changed_dir = last_direction_bits ^ dm; // Ignore direction change unless steps are taken in that direction - #if DISABLED(CORE_BACKLASH) || ENABLED(MARKFORGED_XY) + #if DISABLED(CORE_BACKLASH) || EITHER(MARKFORGED_XY, MARKFORGED_YX) if (!da) CBI(changed_dir, X_AXIS); if (!db) CBI(changed_dir, Y_AXIS); if (!dc) CBI(changed_dir, Z_AXIS); diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index b1b558b033d39..1feb57996adb8 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -162,7 +162,8 @@ void GcodeSuite::M360() { TERN_(DELTA, "Delta") TERN_(IS_SCARA, "SCARA") TERN_(IS_CORE, "Core") - TERN_(MARKFORGED_XY, "MarkForged") + TERN_(MARKFORGED_XY, "MarkForgedXY") + TERN_(MARKFORGED_YX, "MarkForgedYX") TERN_(IS_CARTESIAN, "Cartesian") ); diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 7d8b50f7be007..9e050101aa366 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1079,7 +1079,7 @@ #define CORE_AXIS_2 C_AXIS #endif #define CORESIGN(n) (ANY(COREYX, COREZX, COREZY) ? (-(n)) : (n)) -#elif ENABLED(MARKFORGED_XY) +#elif EITHER(MARKFORGED_XY, MARKFORGED_YX) // Markforged kinematics #define CORE_AXIS_1 A_AXIS #define CORE_AXIS_2 B_AXIS diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index d0b5aff5dda3d..971318518d0f7 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -193,7 +193,7 @@ // Calibration codes only for non-core axes #if EITHER(BACKLASH_GCODE, CALIBRATION_GCODE) - #if EITHER(IS_CORE, MARKFORGED_XY) + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) #define CAN_CALIBRATE(A,B) (_AXIS(A) == B) #else #define CAN_CALIBRATE(A,B) true diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 193750ef2664d..39a154cb53251 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -914,7 +914,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if ENABLED(BABYSTEPPING) #if ENABLED(SCARA) #error "BABYSTEPPING is not implemented for SCARA yet." - #elif BOTH(MARKFORGED_XY, BABYSTEP_XY) + #elif ENABLED(BABYSTEP_XY) && EITHER(MARKFORGED_XY, MARKFORGED_YX) #error "BABYSTEPPING only implemented for Z axis on MarkForged." #elif BOTH(DELTA, BABYSTEP_XY) #error "BABYSTEPPING only implemented for Z axis on deltabots." @@ -1459,8 +1459,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Allow only one kinematic type to be defined */ -#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, FOAMCUTTER_XYUV) - #error "Please enable only one of DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, or FOAMCUTTER_XYUV." +#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, MARKFORGED_YX, FOAMCUTTER_XYUV) + #error "Please enable only one of DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, MARKFORGED_YX, or FOAMCUTTER_XYUV." #endif /** @@ -1958,8 +1958,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if ENABLED(DUAL_X_CARRIAGE) #if EXTRUDERS < 2 #error "DUAL_X_CARRIAGE requires 2 (or more) extruders." - #elif ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) - #error "DUAL_X_CARRIAGE cannot be used with COREXY, COREYX, COREXZ, COREZX, or MARKFORGED_XY." + #elif ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, MARKFORGED_YX) + #error "DUAL_X_CARRIAGE cannot be used with COREXY, COREYX, COREXZ, COREZX, MARKFORGED_YX, or MARKFORGED_XY." #elif !GOOD_AXIS_PINS(X2) #error "DUAL_X_CARRIAGE requires X2 stepper pins to be defined." #elif !HAS_X_MAX @@ -3201,8 +3201,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "CoreXZ requires both X and Z to use sensorless homing if either one does." #elif CORE_IS_YZ && Y_SENSORLESS != Z_SENSORLESS && !HOMING_Z_WITH_PROBE #error "CoreYZ requires both Y and Z to use sensorless homing if either one does." -#elif ENABLED(MARKFORGED_XY) && X_SENSORLESS != Y_SENSORLESS - #error "MARKFORGED_XY requires both X and Y to use sensorless homing if either one does." +#elif EITHER(MARKFORGED_XY, MARKFORGED_YX) && X_SENSORLESS != Y_SENSORLESS + #error "MARKFORGED requires both X and Y to use sensorless homing if either one does." #endif // Other TMC feature requirements @@ -3462,7 +3462,7 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #error "BACKLASH_COMPENSATION requires BACKLASH_DISTANCE_MM." #elif !defined(BACKLASH_CORRECTION) #error "BACKLASH_COMPENSATION requires BACKLASH_CORRECTION." - #elif ENABLED(MARKFORGED_XY) + #elif EITHER(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."); diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index b9adacc5021dd..ad276e11c0485 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -38,7 +38,7 @@ void menu_backlash() { EDIT_ITEM_FAST(percent, MSG_BACKLASH_CORRECTION, &backlash.correction, all_off, all_on); - #if DISABLED(CORE_BACKLASH) || ENABLED(MARKFORGED_XY) + #if DISABLED(CORE_BACKLASH) || EITHER(MARKFORGED_XY, MARKFORGED_YX) #define _CAN_CALI AXIS_CAN_CALIBRATE #else #define _CAN_CALI(A) true diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index aa5907477eb1e..06cbb839cd38f 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -617,7 +617,7 @@ void Endstops::update() { #define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT_TO(live_state, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX))) #define COPY_LIVE_STATE(SRC_BIT, DST_BIT) SET_BIT_TO(live_state, DST_BIT, TEST(live_state, SRC_BIT)) - #if ENABLED(G38_PROBE_TARGET) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) + #if ENABLED(G38_PROBE_TARGET) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, MARKFORGED_XY) #define HAS_G38_PROBE 1 // For G38 moves check the probe's pin for ALL movement if (G38_move) UPDATE_ENDSTOP_BIT(Z, TERN(USES_Z_MIN_PROBE_PIN, MIN_PROBE, MIN)); @@ -628,12 +628,12 @@ void Endstops::update() { #define X_MAX_TEST() TERN1(DUAL_X_CARRIAGE, TERN0(X_HOME_TO_MAX, stepper.last_moved_extruder == 0) || TERN0(X2_HOME_TO_MAX, stepper.last_moved_extruder != 0)) // Use HEAD for core axes, AXIS for others - #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) + #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, MARKFORGED_XY) #define X_AXIS_HEAD X_HEAD #else #define X_AXIS_HEAD X_AXIS #endif - #if ANY(CORE_IS_XY, CORE_IS_YZ, MARKFORGED_XY) + #if ANY(CORE_IS_XY, CORE_IS_YZ, MARKFORGED_XY, MARKFORGED_YX) #define Y_AXIS_HEAD Y_HEAD #else #define Y_AXIS_HEAD Y_AXIS @@ -1111,7 +1111,7 @@ void Endstops::update() { bool hit = false; #if X_SPI_SENSORLESS if (tmc_spi_homing.x && (stepperX.test_stall_status() - #if ANY(CORE_IS_XY, MARKFORGED_XY) && Y_SPI_SENSORLESS + #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) && Y_SPI_SENSORLESS || stepperY.test_stall_status() #elif CORE_IS_XZ && Z_SPI_SENSORLESS || stepperZ.test_stall_status() @@ -1123,7 +1123,7 @@ void Endstops::update() { #endif #if Y_SPI_SENSORLESS if (tmc_spi_homing.y && (stepperY.test_stall_status() - #if ANY(CORE_IS_XY, MARKFORGED_XY) && X_SPI_SENSORLESS + #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) && X_SPI_SENSORLESS || stepperX.test_stall_status() #elif CORE_IS_YZ && Z_SPI_SENSORLESS || stepperZ.test_stall_status() diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 71239501fd840..9ff668bf30d25 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1367,7 +1367,7 @@ void prepare_line_to_destination() { #if AXIS_HAS_STALLGUARD(X2) stealth_states.x2 = tmc_enable_stallguard(stepperX2); #endif - #if EITHER(CORE_IS_XY, MARKFORGED_XY) && Y_SENSORLESS + #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) && Y_SENSORLESS stealth_states.y = tmc_enable_stallguard(stepperY); #elif CORE_IS_XZ && Z_SENSORLESS stealth_states.z = tmc_enable_stallguard(stepperZ); @@ -1380,7 +1380,7 @@ void prepare_line_to_destination() { #if AXIS_HAS_STALLGUARD(Y2) stealth_states.y2 = tmc_enable_stallguard(stepperY2); #endif - #if EITHER(CORE_IS_XY, MARKFORGED_XY) && X_SENSORLESS + #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) && X_SENSORLESS stealth_states.x = tmc_enable_stallguard(stepperX); #elif CORE_IS_YZ && Z_SENSORLESS stealth_states.z = tmc_enable_stallguard(stepperZ); @@ -1444,7 +1444,7 @@ void prepare_line_to_destination() { #if AXIS_HAS_STALLGUARD(X2) tmc_disable_stallguard(stepperX2, enable_stealth.x2); #endif - #if EITHER(CORE_IS_XY, MARKFORGED_XY) && Y_SENSORLESS + #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) && Y_SENSORLESS tmc_disable_stallguard(stepperY, enable_stealth.y); #elif CORE_IS_XZ && Z_SENSORLESS tmc_disable_stallguard(stepperZ, enable_stealth.z); @@ -1457,7 +1457,7 @@ void prepare_line_to_destination() { #if AXIS_HAS_STALLGUARD(Y2) tmc_disable_stallguard(stepperY2, enable_stealth.y2); #endif - #if EITHER(CORE_IS_XY, MARKFORGED_XY) && X_SENSORLESS + #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) && X_SENSORLESS tmc_disable_stallguard(stepperX, enable_stealth.x); #elif CORE_IS_YZ && Z_SENSORLESS tmc_disable_stallguard(stepperZ, enable_stealth.z); @@ -2011,7 +2011,7 @@ void prepare_line_to_destination() { do_homing_move(axis, adjDistance, get_homing_bump_feedrate(axis)); } - #else // CARTESIAN / CORE / MARKFORGED_XY + #else // CARTESIAN / CORE / MARKFORGED_XY / MARKFORGED_YX set_axis_is_at_home(axis); sync_plan_position(); @@ -2041,7 +2041,7 @@ void prepare_line_to_destination() { #if ENABLED(SENSORLESS_HOMING) planner.synchronize(); if (false - #if EITHER(IS_CORE, MARKFORGED_XY) + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) || axis != NORMAL_AXIS #endif ) safe_delay(200); // Short delay to allow belts to spring back diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 28364d4be0b1f..cd8729edace94 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1745,7 +1745,7 @@ float Planner::get_axis_position_mm(const AxisEnum axis) { else axis_steps = stepper.position(axis); - #elif ENABLED(MARKFORGED_XY) + #elif EITHER(MARKFORGED_XY, MARKFORGED_YX) // Requesting one of the joined axes? if (axis == CORE_AXIS_1 || axis == CORE_AXIS_2) { @@ -1919,42 +1919,28 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Compute direction bit-mask for this block axis_bits_t dm = 0; - #if CORE_IS_XY - if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X - if (db < 0) SBI(dm, Y_HEAD); // ...and Y - if (dc < 0) SBI(dm, Z_AXIS); - if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction - if (CORESIGN(da - db) < 0) SBI(dm, B_AXIS); // Motor B direction - #elif CORE_IS_XZ - if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X - if (db < 0) SBI(dm, Y_AXIS); - if (dc < 0) SBI(dm, Z_HEAD); // ...and Z - if (da + dc < 0) SBI(dm, A_AXIS); // Motor A direction - if (CORESIGN(da - dc) < 0) SBI(dm, C_AXIS); // Motor C direction - #elif CORE_IS_YZ - if (da < 0) SBI(dm, X_AXIS); - if (db < 0) SBI(dm, Y_HEAD); // Save the toolhead's true direction in Y - if (dc < 0) SBI(dm, Z_HEAD); // ...and Z - if (db + dc < 0) SBI(dm, B_AXIS); // Motor B direction - if (CORESIGN(db - dc) < 0) SBI(dm, C_AXIS); // Motor C direction - #elif ENABLED(MARKFORGED_XY) - if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X - if (db < 0) SBI(dm, Y_HEAD); // ...and Y + #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) + if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X + if (db < 0) SBI(dm, Y_HEAD); // ...and Y if (dc < 0) SBI(dm, Z_AXIS); - if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction - if (db < 0) SBI(dm, B_AXIS); // Motor B direction - #else - LINEAR_AXIS_CODE( - if (da < 0) SBI(dm, X_AXIS), - if (db < 0) SBI(dm, Y_AXIS), - if (dc < 0) SBI(dm, Z_AXIS), - if (di < 0) SBI(dm, I_AXIS), - if (dj < 0) SBI(dm, J_AXIS), - if (dk < 0) SBI(dm, K_AXIS) - ); #endif - #if IS_CORE + #if CORE_IS_XY + if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction + if (CORESIGN(da - db) < 0) SBI(dm, B_AXIS); // Motor B direction + #elif CORE_IS_XZ + if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X + if (db < 0) SBI(dm, Y_AXIS); + if (dc < 0) SBI(dm, Z_HEAD); // ...and Z + if (da + dc < 0) SBI(dm, A_AXIS); // Motor A direction + if (CORESIGN(da - dc) < 0) SBI(dm, C_AXIS); // Motor C direction + #elif CORE_IS_YZ + if (da < 0) SBI(dm, X_AXIS); + if (db < 0) SBI(dm, Y_HEAD); // Save the toolhead's true direction in Y + if (dc < 0) SBI(dm, Z_HEAD); // ...and Z + if (db + dc < 0) SBI(dm, B_AXIS); // Motor B direction + if (CORESIGN(db - dc) < 0) SBI(dm, C_AXIS); // Motor C direction + #endif #if LINEAR_AXES >= 4 if (di < 0) SBI(dm, I_AXIS); #endif @@ -1964,11 +1950,25 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if LINEAR_AXES >= 6 if (dk < 0) SBI(dm, K_AXIS); #endif + #elif ENABLED(MARKFORGED_XY) + if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction + if (db < 0) SBI(dm, B_AXIS); // Motor B direction + #elif ENABLED(MARKFORGED_YX) + if (da < 0) SBI(dm, A_AXIS); // Motor A direction + if (db + da < 0) SBI(dm, B_AXIS); // Motor B direction + #else + LINEAR_AXIS_CODE( + if (da < 0) SBI(dm, X_AXIS), + if (db < 0) SBI(dm, Y_AXIS), + if (dc < 0) SBI(dm, Z_AXIS), + if (di < 0) SBI(dm, I_AXIS), + if (dj < 0) SBI(dm, J_AXIS), + if (dk < 0) SBI(dm, K_AXIS) + ); #endif - TERN_(HAS_EXTRUDERS, if (de < 0) SBI(dm, E_AXIS)); - #if HAS_EXTRUDERS + if (de < 0) SBI(dm, E_AXIS); const float esteps_float = de * e_factor[extruder]; const uint32_t esteps = ABS(esteps_float) + 0.5f; #else @@ -1998,6 +1998,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db + dc), ABS(db - dc), ABS(di), ABS(dj), ABS(dk))); #elif ENABLED(MARKFORGED_XY) block->steps.set(LINEAR_AXIS_LIST(ABS(da + db), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk))); + #elif ENABLED(MARKFORGED_YX) + block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db + da), ABS(dc), ABS(di), ABS(dj), ABS(dk))); #elif IS_SCARA block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk))); #else @@ -2014,15 +2016,18 @@ bool Planner::_populate_block(block_t * const block, bool split_move, * Having the real displacement of the head, we can calculate the total movement length and apply the desired speed. */ struct DistanceMM : abce_float_t { - #if EITHER(IS_CORE, MARKFORGED_XY) + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) struct { float x, y, z; } head; #endif } steps_dist_mm; + + #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) + steps_dist_mm.head.x = da * mm_per_step[A_AXIS]; + steps_dist_mm.head.y = db * mm_per_step[B_AXIS]; + steps_dist_mm.z = dc * mm_per_step[Z_AXIS]; + #endif #if IS_CORE #if CORE_IS_XY - steps_dist_mm.head.x = da * mm_per_step[A_AXIS]; - steps_dist_mm.head.y = db * mm_per_step[B_AXIS]; - steps_dist_mm.z = dc * mm_per_step[Z_AXIS]; steps_dist_mm.a = (da + db) * mm_per_step[A_AXIS]; steps_dist_mm.b = CORESIGN(da - db) * mm_per_step[B_AXIS]; #elif CORE_IS_XZ @@ -2048,11 +2053,11 @@ bool Planner::_populate_block(block_t * const block, bool split_move, steps_dist_mm.k = dk * mm_per_step[K_AXIS]; #endif #elif ENABLED(MARKFORGED_XY) - steps_dist_mm.head.x = da * mm_per_step[A_AXIS]; - steps_dist_mm.head.y = db * mm_per_step[B_AXIS]; - steps_dist_mm.z = dc * mm_per_step[Z_AXIS]; steps_dist_mm.a = (da - db) * mm_per_step[A_AXIS]; steps_dist_mm.b = db * mm_per_step[B_AXIS]; + #elif ENABLED(MARKFORGED_YX) + steps_dist_mm.a = da * mm_per_step[A_AXIS]; + steps_dist_mm.b = (db - da) * mm_per_step[B_AXIS]; #else LINEAR_AXIS_CODE( steps_dist_mm.a = da * mm_per_step[A_AXIS], @@ -2084,7 +2089,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->millimeters = millimeters; else { block->millimeters = SQRT( - #if EITHER(CORE_IS_XY, MARKFORGED_XY) + #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) LINEAR_AXIS_GANG( sq(steps_dist_mm.head.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.z), + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) @@ -2163,7 +2168,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif // Enable active axes - #if EITHER(CORE_IS_XY, MARKFORGED_XY) + #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) if (block->steps.a || block->steps.b) { stepper.enable_axis(X_AXIS); stepper.enable_axis(Y_AXIS); @@ -2193,7 +2198,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (block->steps.k) stepper.enable_axis(K_AXIS) ); #endif - #if EITHER(IS_CORE, MARKFORGED_XY) + #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) #if LINEAR_AXES >= 4 if (block->steps.i) stepper.enable_axis(I_AXIS); #endif @@ -2551,7 +2556,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, * => normalize the complete junction vector. * Elsewise, when needed JD will factor-in the E component */ - if (EITHER(IS_CORE, MARKFORGED_XY) || esteps > 0) + if (ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) || esteps > 0) normalize_junction_vector(unit_vec); // Normalize with XYZE components else unit_vec *= inverse_millimeters; // Use pre-calculated (1 / SQRT(x^2 + y^2 + z^2)) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 2c8933266fa33..69818aff7ae17 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2212,6 +2212,8 @@ uint32_t Stepper::block_phase_isr() { #define Y_CMP(A,B) ((A)!=(B)) #endif #define Y_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && Y_CMP(D_(1),D_(2))) ) + #elif ENABLED(MARKFORGED_YX) + #define Y_MOVE_TEST (current_block->steps.a != current_block->steps.b) #else #define Y_MOVE_TEST !!current_block->steps.b #endif @@ -2800,7 +2802,7 @@ void Stepper::init() { * derive the current XYZE position later on. */ void Stepper::_set_position(const abce_long_t &spos) { - #if EITHER(IS_CORE, MARKFORGED_XY) + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) #if CORE_IS_XY // corexy positioning // these equations follow the form of the dA and dB equations on https://www.corexy.com/theory.html @@ -2813,6 +2815,8 @@ void Stepper::_set_position(const abce_long_t &spos) { count_position.set(spos.a, spos.b + spos.c, CORESIGN(spos.b - spos.c)); #elif ENABLED(MARKFORGED_XY) count_position.set(spos.a - spos.b, spos.b, spos.c); + #elif ENABLED(MARKFORGED_YX) + count_position.set(spos.a, spos.b - spos.a, spos.c); #endif TERN_(HAS_EXTRUDERS, count_position.e = spos.e); #else @@ -2884,6 +2888,10 @@ void Stepper::endstop_triggered(const AxisEnum axis) { axis == CORE_AXIS_1 ? count_position[CORE_AXIS_1] - count_position[CORE_AXIS_2] : count_position[CORE_AXIS_2] + #elif ENABLED(MARKFORGED_YX) + axis == CORE_AXIS_1 + ? count_position[CORE_AXIS_1] + : count_position[CORE_AXIS_2] - count_position[CORE_AXIS_1] #else // !IS_CORE count_position[axis] #endif @@ -2912,10 +2920,10 @@ int32_t Stepper::triggered_position(const AxisEnum axis) { return v; } -#if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, IS_SCARA, DELTA) +#if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, MARKFORGED_YX, IS_SCARA, DELTA) #define SAYS_A 1 #endif -#if ANY(CORE_IS_XY, CORE_IS_YZ, MARKFORGED_XY, IS_SCARA, DELTA) +#if ANY(CORE_IS_XY, CORE_IS_YZ, MARKFORGED_XY, MARKFORGED_YX, IS_SCARA, DELTA) #define SAYS_B 1 #endif #if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA) From 7bc18a707572d063ac3ba905f1f704dd965f26f3 Mon Sep 17 00:00:00 2001 From: lukrow80 <64228214+lukrow80@users.noreply.github.com> Date: Tue, 23 Nov 2021 22:30:13 +0100 Subject: [PATCH 082/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20homing=20current?= =?UTF-8?q?=20for=20extra=20axes=20(#23152)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #19112 --- Marlin/src/gcode/calibrate/G28.cpp | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 28df536c51ef6..8743c0d8951ca 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -262,7 +262,7 @@ void GcodeSuite::G28() { reset_stepper_timeout(); #define HAS_CURRENT_HOME(N) (defined(N##_CURRENT_HOME) && N##_CURRENT_HOME != N##_CURRENT) - #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2) || (ENABLED(DELTA) && HAS_CURRENT_HOME(Z)) + #if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2) || HAS_CURRENT_HOME(I) || HAS_CURRENT_HOME(J) || HAS_CURRENT_HOME(K) || (ENABLED(DELTA) && HAS_CURRENT_HOME(Z)) #define HAS_HOMING_CURRENT 1 #endif @@ -290,6 +290,21 @@ void GcodeSuite::G28() { stepperY2.rms_current(Y2_CURRENT_HOME); if (DEBUGGING(LEVELING)) debug_current(F("Y2"), tmc_save_current_Y2, Y2_CURRENT_HOME); #endif + #if HAS_CURRENT_HOME(I) + const int16_t tmc_save_current_I = stepperI.getMilliamps(); + stepperI.rms_current(I_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(F(AXIS4_STR), tmc_save_current_I, I_CURRENT_HOME); + #endif + #if HAS_CURRENT_HOME(J) + const int16_t tmc_save_current_J = stepperJ.getMilliamps(); + stepperJ.rms_current(J_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(F(AXIS5_STR), tmc_save_current_J, J_CURRENT_HOME); + #endif + #if HAS_CURRENT_HOME(K) + const int16_t tmc_save_current_K = stepperK.getMilliamps(); + stepperK.rms_current(K_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(F(AXIS6_STR), tmc_save_current_K, K_CURRENT_HOME); + #endif #if HAS_CURRENT_HOME(Z) && ENABLED(DELTA) const int16_t tmc_save_current_Z = stepperZ.getMilliamps(); stepperZ.rms_current(Z_CURRENT_HOME); From 203047f859c23ee5053ed20c88531b7f15fcee5f Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Tue, 23 Nov 2021 22:33:33 +0100 Subject: [PATCH 083/273] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20include=20path=20(?= =?UTF-8?q?#23150)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index ff013967c08d1..a7ec99d982818 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -40,7 +40,7 @@ #endif #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../../feature/powerloss.h" + #include "../../../../feature/powerloss.h" #endif #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) From d4c78edfe37c62e82aee9bfa3ca8b685e3d5cb62 Mon Sep 17 00:00:00 2001 From: schmttc <89831403+schmttc@users.noreply.github.com> Date: Wed, 24 Nov 2021 08:52:18 +1100 Subject: [PATCH 084/273] =?UTF-8?q?=E2=9C=A8=20EasyThreeD=20ET4000+=20boar?= =?UTF-8?q?d=20and=20UI=20(#23080)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 5 + Marlin/src/MarlinCore.cpp | 10 + Marlin/src/feature/easythreed_ui.cpp | 236 ++++++++++++++++++ Marlin/src/feature/easythreed_ui.h | 35 +++ Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h | 50 +++- ini/features.ini | 1 + platformio.ini | 1 + 7 files changed, 329 insertions(+), 9 deletions(-) create mode 100644 Marlin/src/feature/easythreed_ui.cpp create mode 100644 Marlin/src/feature/easythreed_ui.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 060c07bbbc794..71a92113300c6 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2825,6 +2825,11 @@ //#define REPRAPWORLD_KEYPAD //#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // (mm) Distance to move per key-press +// +// EasyThreeD ET-4000+ with button input and status LED +// +//#define EASYTHREED_UI + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 827d2af86466a..941903149f344 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -248,6 +248,10 @@ #include "feature/power.h" #endif +#if ENABLED(EASYTHREED_UI) + #include "feature/easythreed_ui.h" +#endif + PGMSTR(M112_KILL_STR, "M112 Shutdown"); MarlinState marlin_state = MF_INITIALIZING; @@ -637,6 +641,8 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { #endif #endif + TERN_(EASYTHREED_UI, easythreed_ui.run()); + TERN_(USE_CONTROLLER_FAN, controllerFan.update()); // Check if fan should be turned on to cool stepper drivers down TERN_(AUTO_POWER_CONTROL, powerManager.check(!ui.on_status_screen() || printJobOngoing() || printingIsPaused())); @@ -1606,6 +1612,10 @@ void setup() { SETUP_RUN(ui.check_touch_calibration()); #endif + #if ENABLED(EASYTHREED_UI) + SETUP_RUN(easythreed_ui.init()); + #endif + marlin_state = MF_RUNNING; SETUP_LOG("setup() completed."); diff --git a/Marlin/src/feature/easythreed_ui.cpp b/Marlin/src/feature/easythreed_ui.cpp new file mode 100644 index 0000000000000..3eff233c014ac --- /dev/null +++ b/Marlin/src/feature/easythreed_ui.cpp @@ -0,0 +1,236 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../inc/MarlinConfigPre.h" + +#if ENABLED(EASYTHREED_UI) + +#include "easythreed_ui.h" +#include "pause.h" +#include "../module/temperature.h" +#include "../module/printcounter.h" +#include "../sd/cardreader.h" +#include "../gcode/queue.h" +#include "../module/motion.h" +#include "../module/planner.h" +#include "../MarlinCore.h" + +EasythreedUI easythreed_ui; + +#define BTN_DEBOUNCE_MS 20 + +void EasythreedUI::init() { + SET_INPUT_PULLUP(BTN_HOME); SET_OUTPUT(BTN_HOME_GND); + SET_INPUT_PULLUP(BTN_FEED); SET_OUTPUT(BTN_FEED_GND); + SET_INPUT_PULLUP(BTN_RETRACT); SET_OUTPUT(BTN_RETRACT_GND); + SET_INPUT_PULLUP(BTN_PRINT); + SET_OUTPUT(EASYTHREED_LED_PIN); +} + +void EasythreedUI::run() { + blinkLED(); + loadButton(); + printButton(); +} + +enum LEDInterval : uint16_t { + LED_OFF = 0, + LED_ON = 4000, + LED_BLINK_0 = 2500, + LED_BLINK_1 = 1500, + LED_BLINK_2 = 1000, + LED_BLINK_3 = 800, + LED_BLINK_4 = 500, + LED_BLINK_5 = 300, + LED_BLINK_6 = 150, + LED_BLINK_7 = 50 +}; + +uint16_t blink_interval_ms = LED_ON; // Status LED on Start button + +void EasythreedUI::blinkLED() { + static millis_t prev_blink_interval_ms = 0, blink_start_ms = 0; + + if (blink_interval_ms == LED_OFF) { WRITE(EASYTHREED_LED_PIN, HIGH); return; } // OFF + if (blink_interval_ms >= LED_ON) { WRITE(EASYTHREED_LED_PIN, LOW); return; } // ON + + const millis_t ms = millis(); + if (prev_blink_interval_ms != blink_interval_ms) { + prev_blink_interval_ms = blink_interval_ms; + blink_start_ms = ms; + } + if (PENDING(ms, blink_start_ms + blink_interval_ms)) + WRITE(EASYTHREED_LED_PIN, LOW); + else if (PENDING(ms, blink_start_ms + 2 * blink_interval_ms)) + WRITE(EASYTHREED_LED_PIN, HIGH); + else + blink_start_ms = ms; +} + +// +// Filament Load/Unload Button +// Load/Unload buttons are a 3 position switch with a common center ground. +// +void EasythreedUI::loadButton() { + if (printingIsActive()) return; + + enum FilamentStatus : uint8_t { FS_IDLE, FS_PRESS, FS_CHECK, FS_PROCEED }; + static uint8_t filament_status = FS_IDLE; + static millis_t filament_time = 0; + + switch (filament_status) { + + case FS_IDLE: + if (!READ(BTN_RETRACT) || !READ(BTN_FEED)) { // If feed/retract switch is toggled... + filament_status++; // ...proceed to next test. + filament_time = millis(); + } + break; + + case FS_PRESS: + if (ELAPSED(millis(), filament_time + BTN_DEBOUNCE_MS)) { // After a short debounce delay... + if (!READ(BTN_RETRACT) || !READ(BTN_FEED)) { // ...if switch still toggled... + thermalManager.setTargetHotend(EXTRUDE_MINTEMP + 10, 0); // Start heating up + blink_interval_ms = LED_BLINK_7; // Set the LED to blink fast + filament_status++; + } + else + filament_status = FS_IDLE; // Switch not toggled long enough + } + break; + + case FS_CHECK: + if (READ(BTN_RETRACT) && READ(BTN_FEED)) { // Switch in center position (stop) + blink_interval_ms = LED_ON; // LED on steady + filament_status = FS_IDLE; + thermalManager.disable_all_heaters(); + } + else if (thermalManager.hotEnoughToExtrude(0)) { // Is the hotend hot enough to move material? + filament_status++; // Proceed to feed / retract. + blink_interval_ms = LED_BLINK_5; // Blink ~3 times per second + } + break; + + case FS_PROCEED: { + // Feed or Retract just once. Hard abort all moves and return to idle on swicth release. + static bool flag = false; + if (READ(BTN_RETRACT) && READ(BTN_FEED)) { // Switch in center position (stop) + flag = false; // Restore flag to false + filament_status = FS_IDLE; // Go back to idle state + quickstop_stepper(); // Hard-stop all the steppers ... now! + thermalManager.disable_all_heaters(); // And disable all the heaters + blink_interval_ms = LED_ON; + } + else if (!flag) { + flag = true; + queue.inject(!READ(BTN_RETRACT) ? F("G91\nG0 E10 F180\nG0 E-120 F180\nM104 S0") : F("G91\nG0 E100 F120\nM104 S0")); + } + } break; + } + +} + +#if HAS_STEPPER_RESET + void disableStepperDrivers(); +#endif + +// +// Print Start/Pause/Resume Button +// +void EasythreedUI::printButton() { + enum KeyStatus : uint8_t { KS_IDLE, KS_PRESS, KS_PROCEED }; + static uint8_t key_status = KS_IDLE; + static millis_t key_time = 0; + + enum PrintFlag : uint8_t { PF_START, PF_PAUSE, PF_RESUME }; + static PrintFlag print_key_flag = PF_START; + + const millis_t ms = millis(); + + switch (key_status) { + case KS_IDLE: + if (!READ(BTN_PRINT)) { // Print/Pause/Resume button pressed? + key_time = ms; // Save start time + key_status++; // Go to debounce test + } + break; + + case KS_PRESS: + if (ELAPSED(ms, key_time + BTN_DEBOUNCE_MS)) // Wait for debounce interval to expire + key_status = READ(BTN_PRINT) ? KS_IDLE : KS_PROCEED; // Proceed if still pressed + break; + + case KS_PROCEED: + if (!READ(BTN_PRINT)) break; // Wait for the button to be released + key_status = KS_IDLE; // Ready for the next press + if (PENDING(ms, key_time + 1200 - BTN_DEBOUNCE_MS)) { // Register a press < 1.2 seconds + switch (print_key_flag) { + case PF_START: { // The "Print" button starts an SD card print + if (printingIsActive()) break; // Already printing? (find another line that checks for 'is planner doing anything else right now?') + blink_interval_ms = LED_BLINK_2; // Blink the indicator LED at 1 second intervals + print_key_flag = PF_PAUSE; // The "Print" button now pauses the print + card.mount(); // Force SD card to mount - now! + if (!card.isMounted) { // Failed to mount? + blink_interval_ms = LED_OFF; // Turn off LED + print_key_flag = PF_START; + return; // Bail out + } + card.ls(); // List all files to serial output + const uint16_t filecnt = card.countFilesInWorkDir(); // Count printable files in cwd + if (filecnt == 0) return; // None are printable? + card.selectFileByIndex(filecnt); // Select the last file according to current sort options + card.openAndPrintFile(card.filename); // Start printing it + break; + } + case PF_PAUSE: { // Pause printing (not currently firing) + if (!printingIsActive()) break; + blink_interval_ms = LED_ON; // Set indicator to steady ON + queue.inject(F("M25")); // Queue Pause + print_key_flag = PF_RESUME; // The "Print" button now resumes the print + break; + } + case PF_RESUME: { // Resume printing + if (printingIsActive()) break; + blink_interval_ms = LED_BLINK_2; // Blink the indicator LED at 1 second intervals + queue.inject(F("M24")); // Queue resume + print_key_flag = PF_PAUSE; // The "Print" button now pauses the print + break; + } + } + } + else { // Register a longer press + if (print_key_flag == PF_START && !printingIsActive()) { // While not printing, this moves Z up 10mm + blink_interval_ms = LED_ON; + queue.inject(F("G91\nG0 Z10 F600\nG90")); // Raise Z soon after returning to main loop + } + else { // While printing, cancel print + card.abortFilePrintSoon(); // There is a delay while the current steps play out + blink_interval_ms = LED_OFF; // Turn off LED + } + planner.synchronize(); // Wait for commands already in the planner to finish + TERN_(HAS_STEPPER_RESET, disableStepperDrivers()); // Disable all steppers - now! + print_key_flag = PF_START; // The "Print" button now starts a new print + } + break; + } +} +#endif // EASYTHREED_UI diff --git a/Marlin/src/feature/easythreed_ui.h b/Marlin/src/feature/easythreed_ui.h new file mode 100644 index 0000000000000..af9ad2d090b15 --- /dev/null +++ b/Marlin/src/feature/easythreed_ui.h @@ -0,0 +1,35 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +class EasythreedUI { + public: + static void init(); + static void run(); + + private: + static void blinkLED(); + static void loadButton(); + static void printButton(); +}; + +extern EasythreedUI easythreed_ui; diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index 94f7313996d0c..9f33d4392a14c 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -79,31 +79,51 @@ #define FIL_RUNOUT_PIN PB8 // MT_DET +/** ------ + * (BEEPER) PD2 |10 9 | PB3 (BTN_ENC) + * (BTN_EN1) PB5 | 8 7 | PA11 (RESET?) + * (BTN_EN2) PB4 6 5 | PC1 (LCD_D4) + * (LCD_RS) PC3 | 4 3 | PC2 (LCD_EN) + * GND | 2 1 | 5V + * ------ + * "E3" EXP1 + */ +#define E3_EXP1_01_PIN -1 // 5V +#define E3_EXP1_02_PIN -1 // GND +#define E3_EXP1_03_PIN PC2 +#define E3_EXP1_04_PIN PC3 +#define E3_EXP1_05_PIN PC1 +#define E3_EXP1_06_PIN PB4 +#define E3_EXP1_07_PIN PA11 // RESET? +#define E3_EXP1_08_PIN PB5 +#define E3_EXP1_09_PIN PB3 +#define E3_EXP1_10_PIN PD2 + // // LCD Pins // #if HAS_WIRED_LCD - #define BEEPER_PIN PD2 - #define BTN_ENC PB3 - #define LCD_PINS_RS PC3 + #define BEEPER_PIN E3_EXP1_10_PIN + #define BTN_ENC E3_EXP1_09_PIN + #define LCD_PINS_RS E3_EXP1_04_PIN - #define BTN_EN1 PB5 - #define BTN_EN2 PB4 + #define BTN_EN1 E3_EXP1_08_PIN + #define BTN_EN2 E3_EXP1_06_PIN - #define LCD_PINS_ENABLE PC2 + #define LCD_PINS_ENABLE E3_EXP1_03_PIN #if ENABLED(MKS_MINI_12864) #define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN -1 - #define DOGLCD_A0 PC1 - #define DOGLCD_CS PC2 + #define DOGLCD_A0 E3_EXP1_05_PIN + #define DOGLCD_CS E3_EXP1_03_PIN #define DOGLCD_SCK PB13 #define DOGLCD_MOSI PB15 #else // !MKS_MINI_12864 - #define LCD_PINS_D4 PC1 + #define LCD_PINS_D4 E3_EXP1_05_PIN #if IS_ULTIPANEL #define LCD_PINS_D5 -1 #define LCD_PINS_D6 -1 @@ -141,3 +161,15 @@ #define SD_MISO_PIN PB14 #define SD_MOSI_PIN PB15 #define SD_SS_PIN PA15 + +// EXP1 replace LCD with keys for EasyThreeD ET4000+ Mainboard +#if ENABLED(EASYTHREED_UI) + #define BTN_HOME E3_EXP1_04_PIN // INPUT_PULLUP (unused) + #define BTN_FEED E3_EXP1_09_PIN // Run E Forward + #define BTN_RETRACT E3_EXP1_08_PIN // Run E Backward + #define BTN_PRINT E3_EXP1_07_PIN // Start File Print + #define BTN_HOME_GND E3_EXP1_03_PIN // OUTPUT (LOW) + #define BTN_FEED_GND E3_EXP1_06_PIN // OUTPUT (LOW) + #define BTN_RETRACT_GND E3_EXP1_05_PIN // OUTPUT (LOW) + #define EASYTHREED_LED_PIN E3_EXP1_10_PIN // Indicator LED +#endif diff --git a/ini/features.ini b/ini/features.ini index 606370e07a6a8..91baa601cab11 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -111,6 +111,7 @@ HAS_COOLER|LASER_COOLANT_FLOW_METER = src_filter=+ HAS_MOTOR_CURRENT_DAC = src_filter=+ DIRECT_STEPPING = src_filter=+ + EMERGENCY_PARSER = src_filter=+ - +EASYTHREED_UI = src_filter=+ I2C_POSITION_ENCODERS = src_filter=+ IIC_BL24CXX_EEPROM = src_filter=+ HAS_SPI_FLASH = src_filter=+ diff --git a/platformio.ini b/platformio.ini index 0be12fb6ae8f3..07821fca96b67 100644 --- a/platformio.ini +++ b/platformio.ini @@ -109,6 +109,7 @@ default_src_filter = + - - + - - - - - + - - - - - From f0e48ce104b5e3dc06f91127e69b3ef5b46370cd Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Tue, 23 Nov 2021 13:54:31 -0800 Subject: [PATCH 085/273] =?UTF-8?q?=F0=9F=93=8C=20Biqu=20BX=20temporary=20?= =?UTF-8?q?framework=20workaround=20(#23131)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/PlatformIO/scripts/generic_create_variant.py | 2 +- ini/stm32h7.ini | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/buildroot/share/PlatformIO/scripts/generic_create_variant.py b/buildroot/share/PlatformIO/scripts/generic_create_variant.py index 52473c752ac6f..06929e0504e9d 100644 --- a/buildroot/share/PlatformIO/scripts/generic_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -30,7 +30,7 @@ else: platform_name = PackageSpec(platform_packages[0]).name - if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "usb-host-msc-cdc-msc-2", "usb-host-msc-cdc-msc-3", "tool-stm32duino" ]: + if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "usb-host-msc-cdc-msc-2", "usb-host-msc-cdc-msc-3", "tool-stm32duino", "biqu-bx-workaround" ]: platform_name = "framework-arduinoststm32" FRAMEWORK_DIR = platform.get_package_dir(platform_name) diff --git a/ini/stm32h7.ini b/ini/stm32h7.ini index fb39d4cc6b73a..16d1067e52c92 100644 --- a/ini/stm32h7.ini +++ b/ini/stm32h7.ini @@ -25,7 +25,7 @@ [env:BTT_SKR_SE_BX] platform = ${common_stm32.platform} extends = stm32_variant -platform_packages = ${stm_flash_drive.platform_packages} +platform_packages = framework-arduinoststm32@https://github.com/thisiskeithb/Arduino_Core_STM32/archive/biqu-bx-workaround.zip board = marlin_BTT_SKR_SE_BX board_build.offset = 0x20000 build_flags = ${stm32_variant.build_flags} ${stm_flash_drive.build_flags} From b6a8cc06fadd2ef3e5b06c7bb2a006ee42f7bfef Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 24 Nov 2021 01:01:07 +0000 Subject: [PATCH 086/273] [cron] Bump distribution date (2021-11-24) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index b025ee39a323c..e678293220d03 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 "2021-11-23" +//#define STRING_DISTRIBUTION_DATE "2021-11-24" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 71086876afe1a..b8e5b4b02044e 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 "2021-11-23" + #define STRING_DISTRIBUTION_DATE "2021-11-24" #endif /** From a7549aac5c5efc7097d6ebe69b2d46b3e7acbfab Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 22 Oct 2021 13:21:26 -0500 Subject: [PATCH 087/273] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20issue=20review?= =?UTF-8?q?=20patches?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 8 ++++---- Marlin/src/gcode/feature/pause/M600.cpp | 4 ++-- Marlin/src/gcode/feature/pause/M701_M702.cpp | 10 +++++----- .../lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.h | 2 +- Marlin/src/module/temperature.cpp | 8 ++++---- 5 files changed, 16 insertions(+), 16 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index a1366fc511144..8dc6fc9132e03 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -329,14 +329,14 @@ * Thermal Protection parameters for the laser cooler. */ #if ENABLED(THERMAL_PROTECTION_COOLER) - #define THERMAL_PROTECTION_COOLER_PERIOD 10 // Seconds - #define THERMAL_PROTECTION_COOLER_HYSTERESIS 3 // Degrees Celsius + #define THERMAL_PROTECTION_COOLER_PERIOD 10 // Seconds + #define THERMAL_PROTECTION_COOLER_HYSTERESIS 3 // Degrees Celsius /** * Laser cooling watch settings (M143/M193). */ - #define WATCH_COOLER_TEMP_PERIOD 60 // Seconds - #define WATCH_COOLER_TEMP_INCREASE 3 // Degrees Celsius + #define WATCH_COOLER_TEMP_PERIOD 60 // Seconds + #define WATCH_COOLER_TEMP_INCREASE 3 // Degrees Celsius #endif #if ENABLED(PIDTEMP) diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index 541fa08350e67..a95e3e02b49e4 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -106,7 +106,7 @@ void GcodeSuite::M600() { // Change toolhead if specified const uint8_t active_extruder_before_filament_change = active_extruder; if (active_extruder != target_extruder && TERN1(DUAL_X_CARRIAGE, !idex_is_duplicating())) - tool_change(target_extruder, false); + tool_change(target_extruder); #endif // Initial retract before move to filament change position @@ -159,7 +159,7 @@ void GcodeSuite::M600() { #if HAS_MULTI_EXTRUDER // Restore toolhead if it was changed if (active_extruder_before_filament_change != active_extruder) - tool_change(active_extruder_before_filament_change, false); + tool_change(active_extruder_before_filament_change); #endif TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index d46bb234bcebb..21e389a5f2013 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -85,7 +85,7 @@ void GcodeSuite::M701() { // Change toolhead if specified uint8_t active_extruder_before_filament_change = active_extruder; if (active_extruder != target_extruder) - tool_change(target_extruder, false); + tool_change(target_extruder); #endif auto move_z_by = [](const_float_t zdist) { @@ -124,7 +124,7 @@ void GcodeSuite::M701() { #if HAS_MULTI_EXTRUDER && (HAS_PRUSA_MMU1 || !HAS_MMU) // Restore toolhead if it was changed if (active_extruder_before_filament_change != active_extruder) - tool_change(active_extruder_before_filament_change, false); + tool_change(active_extruder_before_filament_change); #endif TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool @@ -188,7 +188,7 @@ void GcodeSuite::M702() { // Change toolhead if specified uint8_t active_extruder_before_filament_change = active_extruder; if (active_extruder != target_extruder) - tool_change(target_extruder, false); + tool_change(target_extruder); #endif // Lift Z axis @@ -202,7 +202,7 @@ void GcodeSuite::M702() { #if BOTH(HAS_MULTI_EXTRUDER, FILAMENT_UNLOAD_ALL_EXTRUDERS) if (!parser.seenval('T')) { HOTEND_LOOP() { - if (e != active_extruder) tool_change(e, false); + if (e != active_extruder) tool_change(e); unload_filament(-fc_settings[e].unload_length, true, PAUSE_MODE_UNLOAD_FILAMENT); } } @@ -228,7 +228,7 @@ void GcodeSuite::M702() { #if HAS_MULTI_EXTRUDER && (HAS_PRUSA_MMU1 || !HAS_MMU) // Restore toolhead if it was changed if (active_extruder_before_filament_change != active_extruder) - tool_change(active_extruder_before_filament_change, false); + tool_change(active_extruder_before_filament_change); #endif TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.h b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.h index fa62b545dcdde..8fcadc1553fd9 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.h +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.h @@ -39,7 +39,7 @@ enum AnycubicMediaPauseState { AMPAUSESTATE_PARKING, AMPAUSESTATE_PARKED, AMPAUSESTATE_FILAMENT_OUT, - AMPAUSESTATE_FIAMENT_PRUGING, + AMPAUSESTATE_FILAMENT_PURGING, AMPAUSESTATE_HEATER_TIMEOUT, AMPAUSESTATE_REHEATING, AMPAUSESTATE_REHEAT_FINISHED diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 7afec4408e386..fc5eb2dc6c49d 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -593,7 +593,7 @@ 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 BOTH(WATCH_CHAMBER, PIDTEMPCHAMBER) || BOTH(WATCH_BED, PIDTEMPBED) || BOTH(WATCH_HOTENDS, PIDTEMP) + #define WATCH_PID DISABLED(NO_WATCH_PID_TUNING) && (BOTH(WATCH_CHAMBER, PIDTEMPCHAMBER) || BOTH(WATCH_BED, PIDTEMPBED) || BOTH(WATCH_HOTENDS, PIDTEMP)) #if WATCH_PID #if BOTH(THERMAL_PROTECTION_CHAMBER, PIDTEMPCHAMBER) @@ -684,8 +684,8 @@ volatile bool Temperature::raw_temps_ready = false; if (cycles > 2) { const float Ku = (4.0f * d) / (float(M_PI) * (maxT - minT) * 0.5f), Tu = float(t_low + t_high) * 0.001f, - pf = ischamber ? 0.2f : (isbed ? 0.2f : 0.6f), - df = ischamber ? 1.0f / 3.0f : (isbed ? 1.0f / 3.0f : 1.0f / 8.0f); + pf = (ischamber || isbed) ? 0.2f : 0.6f, + df = (ischamber || isbed) ? 1.0f / 3.0f : 1.0f / 8.0f; tune_pid.Kp = Ku * pf; tune_pid.Ki = tune_pid.Kp * 2.0f / Tu; @@ -731,7 +731,7 @@ volatile bool Temperature::raw_temps_ready = false; if (!heated) { // If not yet reached target... if (current_temp > next_watch_temp) { // Over the watch temp? next_watch_temp = current_temp + watch_temp_increase; // - set the next temp to watch for - temp_change_ms = ms + SEC_TO_MS(watch_temp_period); // - move the expiration timer up + temp_change_ms = ms + SEC_TO_MS(watch_temp_period); // - move the expiration timer up if (current_temp > watch_temp_target) heated = true; // - Flag if target temperature reached } else if (ELAPSED(ms, temp_change_ms)) // Watch timer expired From 9e7b9d01a18f4a77d51c2d8d4c7094b2b5e8bfb4 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 25 Nov 2021 01:02:19 +0000 Subject: [PATCH 088/273] [cron] Bump distribution date (2021-11-25) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e678293220d03..4bde5ecfe4ef9 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 "2021-11-24" +//#define STRING_DISTRIBUTION_DATE "2021-11-25" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b8e5b4b02044e..36baa26676b8f 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 "2021-11-24" + #define STRING_DISTRIBUTION_DATE "2021-11-25" #endif /** From 981ad44ded7b3805ce54da389581403c230f7dbd Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 26 Nov 2021 01:00:27 +0000 Subject: [PATCH 089/273] [cron] Bump distribution date (2021-11-26) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 4bde5ecfe4ef9..1913f2d8dfd81 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 "2021-11-25" +//#define STRING_DISTRIBUTION_DATE "2021-11-26" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 36baa26676b8f..b9267a1fccab9 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 "2021-11-25" + #define STRING_DISTRIBUTION_DATE "2021-11-26" #endif /** From 47d34682519cb1524e71e71c018e946824803660 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 27 Nov 2021 00:59:57 +0000 Subject: [PATCH 090/273] [cron] Bump distribution date (2021-11-27) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 1913f2d8dfd81..e635eb5f10028 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 "2021-11-26" +//#define STRING_DISTRIBUTION_DATE "2021-11-27" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b9267a1fccab9..4f9c01170399c 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 "2021-11-26" + #define STRING_DISTRIBUTION_DATE "2021-11-27" #endif /** From 716d74131576c01c69f438e7640cc9857334bd0e Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Sat, 27 Nov 2021 11:23:23 -0800 Subject: [PATCH 091/273] =?UTF-8?q?=F0=9F=90=9B=20Swap=20BTT002=20Tachomet?= =?UTF-8?q?er=20Pins=20(#23199)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #23086 --- Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) 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 602c8b05480fd..653ebd82a1dd3 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -190,9 +190,9 @@ #ifndef E0_FAN_TACHO_PIN #ifdef MK3_FAN_PINS - #define E0_FAN_TACHO_PIN PE0 // Fan1 + #define E0_FAN_TACHO_PIN PE1 // Fan1 #else - #define E0_FAN_TACHO_PIN PE1 // Fan0 + #define E0_FAN_TACHO_PIN PE0 // Fan0 #endif #endif From a3c4a5eca693bb5794c0374f5ca72ed8f2dc422f Mon Sep 17 00:00:00 2001 From: George Fu Date: Sun, 28 Nov 2021 03:26:53 +0800 Subject: [PATCH 092/273] =?UTF-8?q?=E2=9C=A8=20=20FYSETC=20Spider=20v2.2?= =?UTF-8?q?=20(#23208)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 1 + Marlin/src/pins/pins.h | 2 ++ Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 12 +++++-- .../pins/stm32f4/pins_FYSETC_SPIDER_V2_2.h | 34 +++++++++++++++++++ .../MARLIN_FYSETC_S6/PeripheralPins.c | 4 +-- 5 files changed, 48 insertions(+), 5 deletions(-) create mode 100644 Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_V2_2.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 789512c4ef717..ebb130698c5b0 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -407,6 +407,7 @@ #define BOARD_MKS_ROBIN_NANO_V1_3_F4 4235 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VET6) #define BOARD_MKS_EAGLE 4236 // MKS Eagle (STM32F407VET6) #define BOARD_ARTILLERY_RUBY 4237 // Artillery Ruby (STM32F401RCT6) +#define BOARD_FYSETC_SPIDER_V2_2 4238 // FYSETC Spider V2.2 (STM32F446VET6) // // ARM Cortex M7 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 57648b3e16fe0..3843441712b49 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -643,6 +643,8 @@ #include "stm32f4/pins_FYSETC_S6_V2_0.h" // STM32F4 env:FYSETC_S6 env:FYSETC_S6_8000 #elif MB(FYSETC_SPIDER) #include "stm32f4/pins_FYSETC_SPIDER.h" // STM32F4 env:FYSETC_S6 env:FYSETC_S6_8000 +#elif MB(FYSETC_SPIDER_V2_2) + #include "stm32f4/pins_FYSETC_SPIDER_V2_2.h" // STM32F4 env:FYSETC_S6 env:FYSETC_S6_8000 #elif MB(FLYF407ZG) #include "stm32f4/pins_FLYF407ZG.h" // STM32F4 env:FLYF407ZG #elif MB(MKS_ROBIN2) diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 37a48cab7fdc6..85071034c2a8f 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -162,7 +162,9 @@ #define TEMP_0_PIN PC0 #define TEMP_1_PIN PC1 #define TEMP_2_PIN PC2 -#define TEMP_BED_PIN PC3 +#ifndef TEMP_BED_PIN + #define TEMP_BED_PIN PC3 +#endif // // Heaters / Fans @@ -180,8 +182,12 @@ #define HEATER_BED_PIN PC8 #endif -#define FAN_PIN PB0 -#define FAN1_PIN PB1 +#ifndef FAN_PIN + #define FAN_PIN PB0 +#endif +#ifndef FAN1_PIN + #define FAN1_PIN PB1 +#endif #define FAN2_PIN PB2 // diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_V2_2.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_V2_2.h new file mode 100644 index 0000000000000..50a19fa3d3c30 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_V2_2.h @@ -0,0 +1,34 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define BOARD_INFO_NAME "FYSETC SPIDER V22" +#define DEFAULT_MACHINE_NAME BOARD_INFO_NAME + +#define TEMP_3_PIN PC3 +#define TEMP_4_PIN PB1 +#define TEMP_BED_PIN PB0 + +#define FAN_PIN PA13 +#define FAN1_PIN PA14 + +#include "pins_FYSETC_SPIDER.h" diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/PeripheralPins.c index ec28776ebe66e..f63000e88a52f 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/PeripheralPins.c @@ -60,9 +60,9 @@ const PinMap PinMap_ADC[] = { //{PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 //{PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 //{PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 - //{PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 //{PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 - //{PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 //{PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 //{PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 From 1861f780de948cbfdad4357604a45441ec0b25ce Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sat, 27 Nov 2021 13:54:39 -0800 Subject: [PATCH 093/273] =?UTF-8?q?=F0=9F=A9=B9=20Handle=20nullptr=20in=20?= =?UTF-8?q?CardReader::printLongPath=20(#23197)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/sd/cardreader.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 513d682de68ba..b2f950bc04fbf 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -359,7 +359,7 @@ void CardReader::ls(TERN_(LONG_FILENAME_HOST_SUPPORT, bool includeLongNames/*=fa // void CardReader::printLongPath(char * const path) { - int i, pathLen = strlen(path); + int i, pathLen = path ? strlen(path) : 0; // SERIAL_ECHOPGM("Full Path: "); SERIAL_ECHOLN(path); From 6fa278b7418ebdc4f02b49749d34888c67c22024 Mon Sep 17 00:00:00 2001 From: Anson Liu Date: Sat, 27 Nov 2021 17:58:05 -0500 Subject: [PATCH 094/273] =?UTF-8?q?=F0=9F=A9=B9=20UM2=20extruder=20cooling?= =?UTF-8?q?=20fan=20on=20PJ6=20(#23194)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/temperature.cpp | 16 ++++++++++++++-- Marlin/src/pins/ramps/pins_ULTIMAIN_2.h | 2 +- 2 files changed, 15 insertions(+), 3 deletions(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index fc5eb2dc6c49d..187776de12f7c 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -878,9 +878,21 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { }; uint8_t fanState = 0; - HOTEND_LOOP() - if (temp_hotend[e].celsius >= EXTRUDER_AUTO_FAN_TEMPERATURE) + HOTEND_LOOP() { + if (temp_hotend[e].celsius >= EXTRUDER_AUTO_FAN_TEMPERATURE) { SBI(fanState, pgm_read_byte(&fanBit[e])); + #if MOTHERBOARD == BOARD_ULTIMAIN_2 + // For the UM2 the head fan is connected to PJ6, which does not have an Arduino PIN definition. So use direct register access. + // https://github.com/Ultimaker/Ultimaker2Marlin/blob/master/Marlin/temperature.cpp#L553 + SBI(DDRJ, 6); SBI(PORTJ, 6); + #endif + } + else { + #if MOTHERBOARD == BOARD_ULTIMAIN_2 + SBI(DDRJ, 6); CBI(PORTJ, 6); + #endif + } + } #if HAS_AUTO_CHAMBER_FAN if (temp_chamber.celsius >= CHAMBER_AUTO_FAN_TEMPERATURE) diff --git a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h index 128f1974e0e63..9823d4cf4b758 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h @@ -98,7 +98,7 @@ #endif #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 77 + #define E0_AUTO_FAN_PIN 69 #endif // From 09ee63caf1f78bbb63518164895fd2a7cafd96d6 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Sat, 27 Nov 2021 14:59:32 -0800 Subject: [PATCH 095/273] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20Fix=20Unicode=20(#?= =?UTF-8?q?23186)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 8dc6fc9132e03..d4fcd510037a6 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1667,7 +1667,7 @@ //#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap //#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames //#define STATUS_HEAT_PERCENT // Show heating in a progress bar - //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~‭3260 (or ~940) bytes of PROGMEM. + //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~3260 (or ~940) bytes of PROGMEM. // Frivolous Game Options //#define MARLIN_BRICKOUT From 0539e870de30877a38c78d29a304a97a6068cc80 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 27 Nov 2021 18:33:32 -0600 Subject: [PATCH 096/273] =?UTF-8?q?=F0=9F=8E=A8=20Rename=20HAL=20timer=20e?= =?UTF-8?q?lements?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/timers.h | 16 ++--- Marlin/src/HAL/DUE/Tone.cpp | 6 +- Marlin/src/HAL/DUE/timers.cpp | 16 ++--- Marlin/src/HAL/DUE/timers.h | 48 ++++++------- Marlin/src/HAL/ESP32/HAL.cpp | 6 +- Marlin/src/HAL/ESP32/Tone.cpp | 6 +- Marlin/src/HAL/ESP32/timers.cpp | 18 ++--- Marlin/src/HAL/ESP32/timers.h | 32 ++++----- Marlin/src/HAL/LINUX/timers.h | 23 +++--- Marlin/src/HAL/LPC1768/timers.cpp | 4 +- Marlin/src/HAL/LPC1768/timers.h | 62 ++++++++-------- Marlin/src/HAL/NATIVE_SIM/timers.h | 26 +++---- Marlin/src/HAL/SAMD51/Servo.cpp | 8 +-- Marlin/src/HAL/SAMD51/inc/SanityCheck.h | 2 +- Marlin/src/HAL/SAMD51/timers.cpp | 20 +++--- Marlin/src/HAL/SAMD51/timers.h | 62 ++++++++-------- Marlin/src/HAL/STM32/fast_pwm.cpp | 11 ++- Marlin/src/HAL/STM32/timers.cpp | 14 ++-- Marlin/src/HAL/STM32/timers.h | 22 +++--- Marlin/src/HAL/STM32F1/HAL.h | 4 +- Marlin/src/HAL/STM32F1/Servo.cpp | 18 ++--- Marlin/src/HAL/STM32F1/fast_pwm.cpp | 9 ++- Marlin/src/HAL/STM32F1/timers.cpp | 30 ++++---- Marlin/src/HAL/STM32F1/timers.h | 70 +++++++++---------- Marlin/src/HAL/TEENSY31_32/timers.cpp | 20 +++--- Marlin/src/HAL/TEENSY31_32/timers.h | 34 ++++----- Marlin/src/HAL/TEENSY35_36/timers.cpp | 20 +++--- Marlin/src/HAL/TEENSY35_36/timers.h | 34 ++++----- Marlin/src/HAL/TEENSY40_41/timers.cpp | 28 +++----- Marlin/src/HAL/TEENSY40_41/timers.h | 38 +++++----- Marlin/src/feature/easythreed_ui.cpp | 4 +- Marlin/src/module/planner.h | 2 +- Marlin/src/module/stepper.cpp | 20 +++--- Marlin/src/module/temperature.cpp | 6 +- Marlin/src/pins/sam/pins_ARCHIM1.h | 3 +- Marlin/src/pins/stm32f0/pins_MALYAN_M300.h | 4 +- Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h | 2 +- Marlin/src/pins/stm32f1/pins_MALYAN_M200.h | 4 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 2 +- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 2 +- .../pins/stm32f1/pins_MKS_ROBIN_NANO_common.h | 2 +- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 2 +- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 2 +- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 4 +- Marlin/src/pins/stm32f4/pins_LERDGE_S.h | 4 +- Marlin/src/pins/stm32f4/pins_LERDGE_X.h | 4 +- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 2 +- .../stm32f4/pins_MKS_ROBIN_NANO_V3_common.h | 2 +- Marlin/src/pins/stm32f4/pins_RUMBA32_common.h | 4 +- Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h | 4 +- Marlin/src/pins/stm32f7/pins_REMRAM_V1.h | 2 +- 51 files changed, 384 insertions(+), 404 deletions(-) diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index 82eb8b14b161f..29907204acc58 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -34,14 +34,14 @@ typedef uint16_t hal_timer_t; #define HAL_TIMER_RATE ((F_CPU) / 8) // i.e., 2MHz or 2.5MHz -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 1 +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 1 #endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP #endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 0 +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP 0 #endif #define TEMP_TIMER_FREQUENCY ((F_CPU) / 64.0 / 256.0) @@ -64,7 +64,7 @@ typedef uint16_t hal_timer_t; FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) { switch (timer_num) { - case STEP_TIMER_NUM: + case MF_TIMER_STEP: // waveform generation = 0100 = CTC SET_WGM(1, CTC_OCRnA); @@ -84,7 +84,7 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) { TCNT1 = 0; break; - case TEMP_TIMER_NUM: + case MF_TIMER_TEMP: // Use timer0 for temperature measurement // Interleave temperature interrupt with millies interrupt OCR0B = 128; diff --git a/Marlin/src/HAL/DUE/Tone.cpp b/Marlin/src/HAL/DUE/Tone.cpp index 9beb6022237f0..1ac81faaf0e1c 100644 --- a/Marlin/src/HAL/DUE/Tone.cpp +++ b/Marlin/src/HAL/DUE/Tone.cpp @@ -38,17 +38,17 @@ volatile static int32_t toggles; void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) { tone_pin = _pin; toggles = 2 * frequency * duration / 1000; - HAL_timer_start(TONE_TIMER_NUM, 2 * frequency); + HAL_timer_start(MF_TIMER_TONE, 2 * frequency); } void noTone(const pin_t _pin) { - HAL_timer_disable_interrupt(TONE_TIMER_NUM); + HAL_timer_disable_interrupt(MF_TIMER_TONE); extDigitalWrite(_pin, LOW); } HAL_TONE_TIMER_ISR() { static uint8_t pin_state = 0; - HAL_timer_isr_prologue(TONE_TIMER_NUM); + HAL_timer_isr_prologue(MF_TIMER_TONE); if (toggles) { toggles--; diff --git a/Marlin/src/HAL/DUE/timers.cpp b/Marlin/src/HAL/DUE/timers.cpp index 65073c510d7c4..a7bf7fbd6d857 100644 --- a/Marlin/src/HAL/DUE/timers.cpp +++ b/Marlin/src/HAL/DUE/timers.cpp @@ -42,7 +42,7 @@ // Private Variables // ------------------------ -const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = { +const tTimerConfig timer_config[NUM_HARDWARE_TIMERS] = { { TC0, 0, TC0_IRQn, 3}, // 0 - [servo timer5] { TC0, 1, TC1_IRQn, 0}, // 1 { TC0, 2, TC2_IRQn, 2}, // 2 - stepper @@ -66,9 +66,9 @@ const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = { */ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { - Tc *tc = TimerConfig[timer_num].pTimerRegs; - IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; - uint32_t channel = TimerConfig[timer_num].channel; + Tc *tc = timer_config[timer_num].pTimerRegs; + IRQn_Type irq = timer_config[timer_num].IRQ_Id; + uint32_t channel = timer_config[timer_num].channel; // Disable interrupt, just in case it was already enabled NVIC_DisableIRQ(irq); @@ -86,7 +86,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { pmc_set_writeprotect(false); pmc_enable_periph_clk((uint32_t)irq); - NVIC_SetPriority(irq, TimerConfig [timer_num].priority); + NVIC_SetPriority(irq, timer_config[timer_num].priority); // wave mode, reset counter on match with RC, TC_Configure(tc, channel, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK1); @@ -105,12 +105,12 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { } void HAL_timer_enable_interrupt(const uint8_t timer_num) { - IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; + IRQn_Type irq = timer_config[timer_num].IRQ_Id; NVIC_EnableIRQ(irq); } void HAL_timer_disable_interrupt(const uint8_t timer_num) { - IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; + IRQn_Type irq = timer_config[timer_num].IRQ_Id; NVIC_DisableIRQ(irq); // We NEED memory barriers to ensure Interrupts are actually disabled! @@ -125,7 +125,7 @@ static bool NVIC_GetEnabledIRQ(IRQn_Type IRQn) { } bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { - IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; + IRQn_Type irq = timer_config[timer_num].IRQ_Id; return NVIC_GetEnabledIRQ(irq); } diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index 0e1ea07cc2e47..bab67826df788 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -37,35 +37,35 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_RATE ((F_CPU) / 2) // frequency of timers peripherals -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 2 // Timer Index for Stepper +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 2 // Timer Index for Stepper #endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP #endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 4 // Timer Index for Temperature +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP 4 // Timer Index for Temperature #endif -#ifndef TONE_TIMER_NUM - #define TONE_TIMER_NUM 6 // index of timer to use for beeper tones +#ifndef MF_TIMER_TONE + #define MF_TIMER_TONE 6 // index of timer to use for beeper tones #endif #define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency -#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs -#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR #define HAL_STEP_TIMER_ISR() void TC2_Handler() @@ -92,7 +92,7 @@ typedef struct { // Public Variables // ------------------------ -extern const tTimerConfig TimerConfig[]; +extern const tTimerConfig timer_config[]; // ------------------------ // Public functions @@ -101,17 +101,17 @@ extern const tTimerConfig TimerConfig[]; void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { - const tTimerConfig * const pConfig = &TimerConfig[timer_num]; + const tTimerConfig * const pConfig = &timer_config[timer_num]; pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC = compare; } FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { - const tTimerConfig * const pConfig = &TimerConfig[timer_num]; + const tTimerConfig * const pConfig = &timer_config[timer_num]; return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC; } FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { - const tTimerConfig * const pConfig = &TimerConfig[timer_num]; + const tTimerConfig * const pConfig = &timer_config[timer_num]; return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_CV; } @@ -120,7 +120,7 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { - const tTimerConfig * const pConfig = &TimerConfig[timer_num]; + const tTimerConfig * const pConfig = &timer_config[timer_num]; // Reading the status register clears the interrupt flag pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR; } diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 6a66d519b33cd..810e386894ec4 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -276,7 +276,7 @@ void analogWrite(pin_t pin, int value) { idx = numPWMUsed; pwmPins[idx] = pin; // Start timer on first use - if (idx == 0) HAL_timer_start(PWM_TIMER_NUM, PWM_TIMER_FREQUENCY); + if (idx == 0) HAL_timer_start(MF_TIMER_PWM, PWM_TIMER_FREQUENCY); ++numPWMUsed; } @@ -287,7 +287,7 @@ void analogWrite(pin_t pin, int value) { // Handle PWM timer interrupt HAL_PWM_TIMER_ISR() { - HAL_timer_isr_prologue(PWM_TIMER_NUM); + HAL_timer_isr_prologue(MF_TIMER_PWM); static uint8_t count = 0; @@ -301,7 +301,7 @@ HAL_PWM_TIMER_ISR() { // 128 for 7 Bit resolution count = (count + 1) & 0x7F; - HAL_timer_isr_epilogue(PWM_TIMER_NUM); + HAL_timer_isr_epilogue(MF_TIMER_PWM); } #endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/ESP32/Tone.cpp b/Marlin/src/HAL/ESP32/Tone.cpp index 376c0f32e1291..9c16cdde800ae 100644 --- a/Marlin/src/HAL/ESP32/Tone.cpp +++ b/Marlin/src/HAL/ESP32/Tone.cpp @@ -38,16 +38,16 @@ volatile static int32_t toggles; void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) { tone_pin = _pin; toggles = 2 * frequency * duration / 1000; - HAL_timer_start(TONE_TIMER_NUM, 2 * frequency); + HAL_timer_start(MF_TIMER_TONE, 2 * frequency); } void noTone(const pin_t _pin) { - HAL_timer_disable_interrupt(TONE_TIMER_NUM); + HAL_timer_disable_interrupt(MF_TIMER_TONE); WRITE(_pin, LOW); } HAL_TONE_TIMER_ISR() { - HAL_timer_isr_prologue(TONE_TIMER_NUM); + HAL_timer_isr_prologue(MF_TIMER_TONE); if (toggles) { toggles--; diff --git a/Marlin/src/HAL/ESP32/timers.cpp b/Marlin/src/HAL/ESP32/timers.cpp index 57662a6658822..df0065f45396b 100644 --- a/Marlin/src/HAL/ESP32/timers.cpp +++ b/Marlin/src/HAL/ESP32/timers.cpp @@ -41,7 +41,7 @@ static timg_dev_t *TG[2] = {&TIMERG0, &TIMERG1}; -const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = { +const tTimerConfig timer_config[NUM_HARDWARE_TIMERS] = { { TIMER_GROUP_0, TIMER_0, STEPPER_TIMER_PRESCALE, stepTC_Handler }, // 0 - Stepper { TIMER_GROUP_0, TIMER_1, TEMP_TIMER_PRESCALE, tempTC_Handler }, // 1 - Temperature { TIMER_GROUP_1, TIMER_0, PWM_TIMER_PRESCALE, pwmTC_Handler }, // 2 - PWM @@ -53,7 +53,7 @@ const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = { // ------------------------ void IRAM_ATTR timer_isr(void *para) { - const tTimerConfig& timer = TimerConfig[(int)para]; + const tTimerConfig& timer = timer_config[(int)para]; // Retrieve the interrupt status and the counter value // from the timer that reported the interrupt @@ -82,7 +82,7 @@ void IRAM_ATTR timer_isr(void *para) { * @param frequency frequency of the timer */ void HAL_timer_start(const uint8_t timer_num, uint32_t frequency) { - const tTimerConfig timer = TimerConfig[timer_num]; + const tTimerConfig timer = timer_config[timer_num]; timer_config_t config; config.divider = timer.divider; @@ -115,7 +115,7 @@ void HAL_timer_start(const uint8_t timer_num, uint32_t frequency) { * @param count threshold at which the interrupt is triggered */ void HAL_timer_set_compare(const uint8_t timer_num, hal_timer_t count) { - const tTimerConfig timer = TimerConfig[timer_num]; + const tTimerConfig timer = timer_config[timer_num]; timer_set_alarm_value(timer.group, timer.idx, count); } @@ -125,7 +125,7 @@ void HAL_timer_set_compare(const uint8_t timer_num, hal_timer_t count) { * @return the timer current threshold for the alarm to be triggered */ hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { - const tTimerConfig timer = TimerConfig[timer_num]; + const tTimerConfig timer = timer_config[timer_num]; uint64_t alarm_value; timer_get_alarm_value(timer.group, timer.idx, &alarm_value); @@ -139,7 +139,7 @@ hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { * @return the current counter of the alarm */ hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { - const tTimerConfig timer = TimerConfig[timer_num]; + const tTimerConfig timer = timer_config[timer_num]; uint64_t counter_value; timer_get_counter_value(timer.group, timer.idx, &counter_value); return counter_value; @@ -150,7 +150,7 @@ hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { * @param timer_num timer number to enable interrupts on */ void HAL_timer_enable_interrupt(const uint8_t timer_num) { - //const tTimerConfig timer = TimerConfig[timer_num]; + //const tTimerConfig timer = timer_config[timer_num]; //timer_enable_intr(timer.group, timer.idx); } @@ -159,12 +159,12 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num) { * @param timer_num timer number to disable interrupts on */ void HAL_timer_disable_interrupt(const uint8_t timer_num) { - //const tTimerConfig timer = TimerConfig[timer_num]; + //const tTimerConfig timer = timer_config[timer_num]; //timer_disable_intr(timer.group, timer.idx); } bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { - const tTimerConfig timer = TimerConfig[timer_num]; + const tTimerConfig timer = timer_config[timer_num]; return TG[timer.group]->int_ena.val | BIT(timer_num); } diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index a47697113d5d6..b651ffe6b11d5 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -32,20 +32,20 @@ typedef uint64_t hal_timer_t; #define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFFULL -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 0 // Timer Index for Stepper #endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP #endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP 1 // Timer Index for Temperature #endif -#ifndef PWM_TIMER_NUM - #define PWM_TIMER_NUM 2 // index of timer to use for PWM outputs +#ifndef MF_TIMER_PWM + #define MF_TIMER_PWM 2 // index of timer to use for PWM outputs #endif -#ifndef TONE_TIMER_NUM - #define TONE_TIMER_NUM 3 // index of timer for beeper tones +#ifndef MF_TIMER_TONE + #define MF_TIMER_TONE 3 // index of timer for beeper tones #endif #define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals @@ -79,12 +79,12 @@ typedef uint64_t hal_timer_t; #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_TEMP_TIMER_ISR #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler() @@ -121,7 +121,7 @@ typedef struct { // Public Variables // ------------------------ -extern const tTimerConfig TimerConfig[]; +extern const tTimerConfig timer_config[]; // ------------------------ // Public functions diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index 1beaea95abc6b..21dba620717e7 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -37,14 +37,14 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 0 // Timer Index for Stepper #endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP #endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP 1 // Timer Index for Temperature #endif #define TEMP_TIMER_RATE 1000000 @@ -58,12 +58,12 @@ typedef uint32_t hal_timer_t; #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR #define HAL_STEP_TIMER_ISR() extern "C" void TIMER0_IRQHandler() @@ -77,7 +77,6 @@ typedef uint32_t hal_timer_t; #define HAL_PWM_TIMER_ISR() extern "C" void TIMER3_IRQHandler() #define HAL_PWM_TIMER_IRQn - void HAL_timer_init(); void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); diff --git a/Marlin/src/HAL/LPC1768/timers.cpp b/Marlin/src/HAL/LPC1768/timers.cpp index a7a40584dabc3..bbb13f81da05c 100644 --- a/Marlin/src/HAL/LPC1768/timers.cpp +++ b/Marlin/src/HAL/LPC1768/timers.cpp @@ -40,7 +40,7 @@ void HAL_timer_init() { void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { switch (timer_num) { - case 0: + case MF_TIMER_STEP: LPC_TIM0->MCR = _BV(SBIT_MR0I) | _BV(SBIT_MR0R); // Match on MR0, reset on MR0, interrupts when NVIC enables them LPC_TIM0->MR0 = uint32_t(STEPPER_TIMER_RATE) / frequency; // Match value (period) to set frequency LPC_TIM0->TCR = _BV(SBIT_CNTEN); // Counter Enable @@ -49,7 +49,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { NVIC_EnableIRQ(TIMER0_IRQn); break; - case 1: + case MF_TIMER_TEMP: LPC_TIM1->MCR = _BV(SBIT_MR0I) | _BV(SBIT_MR0R); // Match on MR0, reset on MR0, interrupts when NVIC enables them LPC_TIM1->MR0 = uint32_t(TEMP_TIMER_RATE) / frequency; LPC_TIM1->TCR = _BV(SBIT_CNTEN); // Counter Enable diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index 4b638546856f5..ef437cabac12e 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -60,17 +60,17 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_RATE ((F_CPU) / 4) // frequency of timers peripherals -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 0 // Timer Index for Stepper #endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP #endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP 1 // Timer Index for Temperature #endif -#ifndef PWM_TIMER_NUM - #define PWM_TIMER_NUM 3 // Timer Index for PWM +#ifndef MF_TIMER_PWM + #define MF_TIMER_PWM 3 // Timer Index for PWM #endif #define TEMP_TIMER_RATE 1000000 @@ -84,23 +84,23 @@ typedef uint32_t hal_timer_t; #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() _HAL_TIMER_ISR(STEP_TIMER_NUM) + #define HAL_STEP_TIMER_ISR() _HAL_TIMER_ISR(MF_TIMER_STEP) #endif #ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(TEMP_TIMER_NUM) + #define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(MF_TIMER_TEMP) #endif // Timer references by index -#define STEP_TIMER_PTR _HAL_TIMER(STEP_TIMER_NUM) -#define TEMP_TIMER_PTR _HAL_TIMER(TEMP_TIMER_NUM) +#define STEP_TIMER_PTR _HAL_TIMER(MF_TIMER_STEP) +#define TEMP_TIMER_PTR _HAL_TIMER(MF_TIMER_TEMP) // ------------------------ // Public functions @@ -110,38 +110,38 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { switch (timer_num) { - case 0: STEP_TIMER_PTR->MR0 = compare; break; // Stepper Timer Match Register 0 - case 1: TEMP_TIMER_PTR->MR0 = compare; break; // Temp Timer Match Register 0 + case MF_TIMER_STEP: STEP_TIMER_PTR->MR0 = compare; break; // Stepper Timer Match Register 0 + case MF_TIMER_TEMP: TEMP_TIMER_PTR->MR0 = compare; break; // Temp Timer Match Register 0 } } FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { switch (timer_num) { - case 0: return STEP_TIMER_PTR->MR0; // Stepper Timer Match Register 0 - case 1: return TEMP_TIMER_PTR->MR0; // Temp Timer Match Register 0 + case MF_TIMER_STEP: return STEP_TIMER_PTR->MR0; // Stepper Timer Match Register 0 + case MF_TIMER_TEMP: return TEMP_TIMER_PTR->MR0; // Temp Timer Match Register 0 } return 0; } FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { switch (timer_num) { - case 0: return STEP_TIMER_PTR->TC; // Stepper Timer Count - case 1: return TEMP_TIMER_PTR->TC; // Temp Timer Count + case MF_TIMER_STEP: return STEP_TIMER_PTR->TC; // Stepper Timer Count + case MF_TIMER_TEMP: return TEMP_TIMER_PTR->TC; // Temp Timer Count } return 0; } FORCE_INLINE static void HAL_timer_enable_interrupt(const uint8_t timer_num) { switch (timer_num) { - case 0: NVIC_EnableIRQ(TIMER0_IRQn); break; // Enable interrupt handler - case 1: NVIC_EnableIRQ(TIMER1_IRQn); break; // Enable interrupt handler + case MF_TIMER_STEP: NVIC_EnableIRQ(TIMER0_IRQn); break; // Enable interrupt handler + case MF_TIMER_TEMP: NVIC_EnableIRQ(TIMER1_IRQn); break; // Enable interrupt handler } } FORCE_INLINE static void HAL_timer_disable_interrupt(const uint8_t timer_num) { switch (timer_num) { - case 0: NVIC_DisableIRQ(TIMER0_IRQn); break; // Disable interrupt handler - case 1: NVIC_DisableIRQ(TIMER1_IRQn); break; // Disable interrupt handler + case MF_TIMER_STEP: NVIC_DisableIRQ(TIMER0_IRQn); break; // Disable interrupt handler + case MF_TIMER_TEMP: NVIC_DisableIRQ(TIMER1_IRQn); break; // Disable interrupt handler } // We NEED memory barriers to ensure Interrupts are actually disabled! @@ -157,16 +157,16 @@ FORCE_INLINE static bool NVIC_GetEnableIRQ(IRQn_Type IRQn) { FORCE_INLINE static bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { switch (timer_num) { - case 0: return NVIC_GetEnableIRQ(TIMER0_IRQn); // Check if interrupt is enabled or not - case 1: return NVIC_GetEnableIRQ(TIMER1_IRQn); // Check if interrupt is enabled or not + case MF_TIMER_STEP: return NVIC_GetEnableIRQ(TIMER0_IRQn); // Check if interrupt is enabled or not + case MF_TIMER_TEMP: return NVIC_GetEnableIRQ(TIMER1_IRQn); // Check if interrupt is enabled or not } return false; } FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { switch (timer_num) { - case 0: SBI(STEP_TIMER_PTR->IR, SBIT_CNTEN); break; - case 1: SBI(TEMP_TIMER_PTR->IR, SBIT_CNTEN); break; + case MF_TIMER_STEP: SBI(STEP_TIMER_PTR->IR, SBIT_CNTEN); break; + case MF_TIMER_TEMP: SBI(TEMP_TIMER_PTR->IR, SBIT_CNTEN); break; } } diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index c61eb29e76cfc..4d140a4b6cd7a 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -37,17 +37,17 @@ typedef uint64_t hal_timer_t; #define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 0 // Timer Index for Stepper #endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP #endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP 1 // Timer Index for Temperature #endif -#ifndef SYSTICK_TIMER_NUM - #define SYSTICK_TIMER_NUM 2 // Timer Index for Systick +#ifndef MF_TIMER_SYSTICK + #define MF_TIMER_SYSTICK 2 // Timer Index for Systick #endif #define SYSTICK_TIMER_FREQUENCY 1000 @@ -62,12 +62,12 @@ typedef uint64_t hal_timer_t; #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR #define HAL_STEP_TIMER_ISR() extern "C" void TIMER0_IRQHandler() diff --git a/Marlin/src/HAL/SAMD51/Servo.cpp b/Marlin/src/HAL/SAMD51/Servo.cpp index 9bab8e89be23e..23ab21c615c40 100644 --- a/Marlin/src/HAL/SAMD51/Servo.cpp +++ b/Marlin/src/HAL/SAMD51/Servo.cpp @@ -53,7 +53,7 @@ static volatile int8_t currentServoIndex[_Nbr_16timers]; // index for the servo being pulsed for each timer (or -1 if refresh interval) FORCE_INLINE static uint16_t getTimerCount() { - Tc * const tc = TimerConfig[SERVO_TC].pTc; + Tc * const tc = timer_config[SERVO_TC].pTc; tc->COUNT16.CTRLBSET.reg = TC_CTRLBCLR_CMD_READSYNC; SYNC(tc->COUNT16.SYNCBUSY.bit.CTRLB || tc->COUNT16.SYNCBUSY.bit.COUNT); @@ -65,7 +65,7 @@ FORCE_INLINE static uint16_t getTimerCount() { // Interrupt handler for the TC // ---------------------------- HAL_SERVO_TIMER_ISR() { - Tc * const tc = TimerConfig[SERVO_TC].pTc; + Tc * const tc = timer_config[SERVO_TC].pTc; const timer16_Sequence_t timer = #ifndef _useTimer1 _timer2 @@ -125,7 +125,7 @@ HAL_SERVO_TIMER_ISR() { } void initISR(timer16_Sequence_t timer) { - Tc * const tc = TimerConfig[SERVO_TC].pTc; + Tc * const tc = timer_config[SERVO_TC].pTc; const uint8_t tcChannel = TIMER_TCCHANNEL(timer); static bool initialized = false; // Servo TC has been initialized @@ -202,7 +202,7 @@ void initISR(timer16_Sequence_t timer) { } void finISR(timer16_Sequence_t timer) { - Tc * const tc = TimerConfig[SERVO_TC].pTc; + Tc * const tc = timer_config[SERVO_TC].pTc; const uint8_t tcChannel = TIMER_TCCHANNEL(timer); // Disable the match channel interrupt request diff --git a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h index 38c6dd9e08def..1b876c947dc7a 100644 --- a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h +++ b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h @@ -36,7 +36,7 @@ #error "OnBoard SPI BUS can't be shared with other devices." #endif -#if SERVO_TC == RTC_TIMER_NUM +#if SERVO_TC == MF_TIMER_RTC #error "Servos can't use RTC timer" #endif diff --git a/Marlin/src/HAL/SAMD51/timers.cpp b/Marlin/src/HAL/SAMD51/timers.cpp index 7a535299db9ab..ce13dd231ecd9 100644 --- a/Marlin/src/HAL/SAMD51/timers.cpp +++ b/Marlin/src/HAL/SAMD51/timers.cpp @@ -31,13 +31,13 @@ // Local defines // -------------------------------------------------------------------------- -#define NUM_HARDWARE_TIMERS 8 +#define NUM_HARDWARE_TIMERS 9 // -------------------------------------------------------------------------- // Private Variables // -------------------------------------------------------------------------- -const tTimerConfig TimerConfig[NUM_HARDWARE_TIMERS+1] = { +const tTimerConfig timer_config[NUM_HARDWARE_TIMERS] = { { {.pTc=TC0}, TC0_IRQn, TC_PRIORITY(0) }, // 0 - stepper (assigned priority 2) { {.pTc=TC1}, TC1_IRQn, TC_PRIORITY(1) }, // 1 - stepper (needed by 32 bit timers) { {.pTc=TC2}, TC2_IRQn, 5 }, // 2 - tone (reserved by framework and fixed assigned priority 5) @@ -67,13 +67,13 @@ FORCE_INLINE void Disable_Irq(IRQn_Type irq) { // -------------------------------------------------------------------------- void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { - IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; + IRQn_Type irq = timer_config[timer_num].IRQ_Id; // Disable interrupt, just in case it was already enabled Disable_Irq(irq); - if (timer_num == RTC_TIMER_NUM) { - Rtc * const rtc = TimerConfig[timer_num].pRtc; + if (timer_num == MF_TIMER_RTC) { + Rtc * const rtc = timer_config[timer_num].pRtc; // Disable timer interrupt rtc->MODE0.INTENCLR.reg = RTC_MODE0_INTENCLR_CMP0; @@ -101,7 +101,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { SYNC(rtc->MODE0.SYNCBUSY.bit.ENABLE); } else { - Tc * const tc = TimerConfig[timer_num].pTc; + Tc * const tc = timer_config[timer_num].pTc; // Disable timer interrupt tc->COUNT32.INTENCLR.reg = TC_INTENCLR_OVF; // disable overflow interrupt @@ -141,17 +141,17 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { } // Finally, enable IRQ - NVIC_SetPriority(irq, TimerConfig[timer_num].priority); + NVIC_SetPriority(irq, timer_config[timer_num].priority); NVIC_EnableIRQ(irq); } void HAL_timer_enable_interrupt(const uint8_t timer_num) { - const IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; + const IRQn_Type irq = timer_config[timer_num].IRQ_Id; NVIC_EnableIRQ(irq); } void HAL_timer_disable_interrupt(const uint8_t timer_num) { - const IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; + const IRQn_Type irq = timer_config[timer_num].IRQ_Id; Disable_Irq(irq); } @@ -161,7 +161,7 @@ static bool NVIC_GetEnabledIRQ(IRQn_Type IRQn) { } bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { - const IRQn_Type irq = TimerConfig[timer_num].IRQ_Id; + const IRQn_Type irq = timer_config[timer_num].IRQ_Id; return NVIC_GetEnabledIRQ(irq); } diff --git a/Marlin/src/HAL/SAMD51/timers.h b/Marlin/src/HAL/SAMD51/timers.h index dc6e38b7307cc..86e980c566903 100644 --- a/Marlin/src/HAL/SAMD51/timers.h +++ b/Marlin/src/HAL/SAMD51/timers.h @@ -25,21 +25,22 @@ // -------------------------------------------------------------------------- // Defines // -------------------------------------------------------------------------- -#define RTC_TIMER_NUM 8 // This is not a TC but a RTC typedef uint32_t hal_timer_t; #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF #define HAL_TIMER_RATE F_CPU // frequency of timers peripherals -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#define MF_TIMER_RTC 8 // This is not a TC but a RTC + +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 0 // Timer Index for Stepper #endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP #endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM RTC_TIMER_NUM // Timer Index for Temperature +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP MF_TIMER_RTC // Timer Index for Temperature #endif #define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency @@ -52,30 +53,29 @@ typedef uint32_t hal_timer_t; #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) -#define TC_PRIORITY(t) t == SERVO_TC ? 1 \ - : (t == STEP_TIMER_NUM || t == PULSE_TIMER_NUM) ? 2 \ - : (t == TEMP_TIMER_NUM) ? 6 \ - : 7 +#define TC_PRIORITY(t) ( t == SERVO_TC ? 1 \ + : (t == MF_TIMER_STEP || t == MF_TIMER_PULSE) ? 2 \ + : (t == MF_TIMER_TEMP) ? 6 : 7 ) #define _TC_HANDLER(t) void TC##t##_Handler() #define TC_HANDLER(t) _TC_HANDLER(t) #ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() TC_HANDLER(STEP_TIMER_NUM) + #define HAL_STEP_TIMER_ISR() TC_HANDLER(MF_TIMER_STEP) #endif -#if STEP_TIMER_NUM != PULSE_TIMER_NUM - #define HAL_PULSE_TIMER_ISR() TC_HANDLER(PULSE_TIMER_NUM) +#if MF_TIMER_STEP != MF_TIMER_PULSE + #define HAL_PULSE_TIMER_ISR() TC_HANDLER(MF_TIMER_PULSE) #endif -#if TEMP_TIMER_NUM == RTC_TIMER_NUM +#if MF_TIMER_TEMP == MF_TIMER_RTC #define HAL_TEMP_TIMER_ISR() void RTC_Handler() #else - #define HAL_TEMP_TIMER_ISR() TC_HANDLER(TEMP_TIMER_NUM) + #define HAL_TEMP_TIMER_ISR() TC_HANDLER(MF_TIMER_TEMP) #endif // -------------------------------------------------------------------------- @@ -95,7 +95,7 @@ typedef struct { // Public Variables // -------------------------------------------------------------------------- -extern const tTimerConfig TimerConfig[]; +extern const tTimerConfig timer_config[]; // -------------------------------------------------------------------------- // Public functions @@ -104,20 +104,20 @@ extern const tTimerConfig TimerConfig[]; void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { - // Should never be called with timer RTC_TIMER_NUM - Tc * const tc = TimerConfig[timer_num].pTc; + // Should never be called with timer MF_TIMER_RTC + Tc * const tc = timer_config[timer_num].pTc; tc->COUNT32.CC[0].reg = compare; } FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { - // Should never be called with timer RTC_TIMER_NUM - Tc * const tc = TimerConfig[timer_num].pTc; + // Should never be called with timer MF_TIMER_RTC + Tc * const tc = timer_config[timer_num].pTc; return (hal_timer_t)tc->COUNT32.CC[0].reg; } FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { - // Should never be called with timer RTC_TIMER_NUM - Tc * const tc = TimerConfig[timer_num].pTc; + // Should never be called with timer MF_TIMER_RTC + Tc * const tc = timer_config[timer_num].pTc; tc->COUNT32.CTRLBSET.reg = TC_CTRLBCLR_CMD_READSYNC; SYNC(tc->COUNT32.SYNCBUSY.bit.CTRLB || tc->COUNT32.SYNCBUSY.bit.COUNT); return tc->COUNT32.COUNT.reg; @@ -128,13 +128,13 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { - if (timer_num == RTC_TIMER_NUM) { - Rtc * const rtc = TimerConfig[timer_num].pRtc; + if (timer_num == MF_TIMER_RTC) { + Rtc * const rtc = timer_config[timer_num].pRtc; // Clear interrupt flag rtc->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_CMP0; } else { - Tc * const tc = TimerConfig[timer_num].pTc; + Tc * const tc = timer_config[timer_num].pTc; // Clear interrupt flag tc->COUNT32.INTFLAG.reg = TC_INTFLAG_OVF; } diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index 4986e138a181d..8eaecd718e557 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -70,9 +70,6 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 void set_pwm_frequency(const pin_t pin, int f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer - HardwareTimer *HT; - PinName pin_name = digitalPinToPinName(pin); - TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance uint32_t index = get_timer_index(Instance); @@ -83,11 +80,13 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { #endif ) return; - if (HardwareTimer_Handle[index] == nullptr) // If frequency is set before duty we need to create a handle here. + const PinName pin_name = digitalPinToPinName(pin); + TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance + if (HardwareTimer_Handle[index] == nullptr) // If frequency is set before duty we need to create a handle here. HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM)); - HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + HardwareTimer * const HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); timer_freq[index] = f_desired; // Save the last frequency so duty will not set the default for this timer number. - HT->setOverflow(f_desired, HERTZ_FORMAT); + HT->setOverflow(f_desired, HERTZ_FORMAT); } #endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index 9b69323ef5433..8f1659591b1fe 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -110,7 +110,7 @@ HardwareTimer *timer_instance[NUM_HARDWARE_TIMERS] = { nullptr }; uint32_t GetStepperTimerClkFreq() { // Timer input clocks vary between devices, and in some cases between timers on the same device. // Retrieve at runtime to ensure device compatibility. Cache result to avoid repeated overhead. - static uint32_t clkfreq = timer_instance[STEP_TIMER_NUM]->getTimerClkFreq(); + static uint32_t clkfreq = timer_instance[MF_TIMER_STEP]->getTimerClkFreq(); return clkfreq; } @@ -118,7 +118,7 @@ uint32_t GetStepperTimerClkFreq() { void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { if (!HAL_timer_initialized(timer_num)) { switch (timer_num) { - case STEP_TIMER_NUM: // STEPPER TIMER - use a 32bit timer if possible + case MF_TIMER_STEP: // STEPPER TIMER - use a 32bit timer if possible timer_instance[timer_num] = new HardwareTimer(STEP_TIMER_DEV); /* Set the prescaler to the final desired value. * This will change the effective ISR callback frequency but when @@ -137,7 +137,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { timer_instance[timer_num]->setPrescaleFactor(STEPPER_TIMER_PRESCALE); //the -1 is done internally timer_instance[timer_num]->setOverflow(_MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* /frequency */), TICK_FORMAT); break; - case TEMP_TIMER_NUM: // TEMP TIMER - any available 16bit timer + case MF_TIMER_TEMP: // TEMP TIMER - any available 16bit timer timer_instance[timer_num] = new HardwareTimer(TEMP_TIMER_DEV); // The prescale factor is computed automatically for HERTZ_FORMAT timer_instance[timer_num]->setOverflow(frequency, HERTZ_FORMAT); @@ -157,10 +157,10 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { // These calls can be removed and replaced with // timer_instance[timer_num]->setInterruptPriority switch (timer_num) { - case STEP_TIMER_NUM: + case MF_TIMER_STEP: timer_instance[timer_num]->setInterruptPriority(STEP_TIMER_IRQ_PRIO, 0); break; - case TEMP_TIMER_NUM: + case MF_TIMER_TEMP: timer_instance[timer_num]->setInterruptPriority(TEMP_TIMER_IRQ_PRIO, 0); break; } @@ -170,10 +170,10 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { void HAL_timer_enable_interrupt(const uint8_t timer_num) { if (HAL_timer_initialized(timer_num) && !timer_instance[timer_num]->hasInterrupt()) { switch (timer_num) { - case STEP_TIMER_NUM: + case MF_TIMER_STEP: timer_instance[timer_num]->attachInterrupt(Step_Handler); break; - case TEMP_TIMER_NUM: + case MF_TIMER_TEMP: timer_instance[timer_num]->attachInterrupt(Temp_Handler); break; } diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 7a35e432102df..ae70e658868ed 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -42,14 +42,14 @@ #define NUM_HARDWARE_TIMERS 2 -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 0 // Timer Index for Stepper #endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP #endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP 1 // Timer Index for Temperature #endif #define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() is expected to be called at around 1kHz @@ -64,12 +64,12 @@ extern uint32_t GetStepperTimerClkFreq(); #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) extern void Step_Handler(); extern void Temp_Handler(); diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 026e83bc0d7b0..153cfe8ac89e6 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -266,7 +266,7 @@ void flashFirmware(const int16_t); #ifndef PWM_FREQUENCY #define PWM_FREQUENCY 1000 // Default PWM Frequency -#endif +#endif #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment /** @@ -281,6 +281,6 @@ void set_pwm_frequency(const pin_t pin, int f_desired); * Set the PWM duty cycle of the provided pin to the provided value * Optionally allows inverting the duty cycle [default = false] * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. + * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. */ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp index 36f7c6d51273e..8dc1ef7b6a5b6 100644 --- a/Marlin/src/HAL/STM32F1/Servo.cpp +++ b/Marlin/src/HAL/STM32F1/Servo.cpp @@ -60,7 +60,7 @@ uint8_t ServoCount = 0; #define US_TO_ANGLE(us) int16_t(map((us), SERVO_DEFAULT_MIN_PW, SERVO_DEFAULT_MAX_PW, minAngle, maxAngle)) void libServo::servoWrite(uint8_t inPin, uint16_t duty_cycle) { - #ifdef SERVO0_TIMER_NUM + #ifdef MF_TIMER_SERVO0 if (servoIndex == 0) { pwmSetDuty(duty_cycle); return; @@ -74,7 +74,7 @@ void libServo::servoWrite(uint8_t inPin, uint16_t duty_cycle) { libServo::libServo() { servoIndex = ServoCount < MAX_SERVOS ? ServoCount++ : INVALID_SERVO; - timer_set_interrupt_priority(SERVO0_TIMER_NUM, SERVO0_TIMER_IRQ_PRIO); + HAL_timer_set_interrupt_priority(MF_TIMER_SERVO0, SERVO0_TIMER_IRQ_PRIO); } bool libServo::attach(const int32_t inPin, const int32_t inMinAngle, const int32_t inMaxAngle) { @@ -85,7 +85,7 @@ bool libServo::attach(const int32_t inPin, const int32_t inMinAngle, const int32 maxAngle = inMaxAngle; angle = -1; - #ifdef SERVO0_TIMER_NUM + #ifdef MF_TIMER_SERVO0 if (servoIndex == 0 && setupSoftPWM(inPin)) { pin = inPin; // set attached() return true; @@ -119,7 +119,7 @@ bool libServo::detach() { int32_t libServo::read() const { if (attached()) { - #ifdef SERVO0_TIMER_NUM + #ifdef MF_TIMER_SERVO0 if (servoIndex == 0) return angle; #endif timer_dev *tdev = PIN_MAP[pin].timer_device; @@ -141,9 +141,9 @@ void libServo::move(const int32_t value) { } } -#ifdef SERVO0_TIMER_NUM +#ifdef MF_TIMER_SERVO0 extern "C" void Servo_IRQHandler() { - static timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM); + static timer_dev *tdev = HAL_get_timer_dev(MF_TIMER_SERVO0); uint16_t SR = timer_get_status(tdev); if (SR & TIMER_SR_CC1IF) { // channel 1 off #ifdef SERVO0_PWM_OD @@ -164,7 +164,7 @@ void libServo::move(const int32_t value) { } bool libServo::setupSoftPWM(const int32_t inPin) { - timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM); + timer_dev *tdev = HAL_get_timer_dev(MF_TIMER_SERVO0); if (!tdev) return false; #ifdef SERVO0_PWM_OD OUT_WRITE_OD(inPin, 1); @@ -189,7 +189,7 @@ void libServo::move(const int32_t value) { } void libServo::pwmSetDuty(const uint16_t duty_cycle) { - timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM); + timer_dev *tdev = HAL_get_timer_dev(MF_TIMER_SERVO0); timer_set_compare(tdev, 1, duty_cycle); timer_generate_update(tdev); if (duty_cycle) { @@ -208,7 +208,7 @@ void libServo::move(const int32_t value) { } void libServo::pauseSoftPWM() { // detach - timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM); + timer_dev *tdev = HAL_get_timer_dev(MF_TIMER_SERVO0); timer_pause(tdev); pwmSetDuty(0); } diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp index b510a4c8a022b..994e62dbcd4fb 100644 --- a/Marlin/src/HAL/STM32F1/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp @@ -35,7 +35,6 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 uint16_t max_val = timer->regs.bas->ARR * v / v_size; if (invert) max_val = v_size - max_val; pwmWrite(pin, max_val); - } void set_pwm_frequency(const pin_t pin, int f_desired) { @@ -45,10 +44,10 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { uint8_t channel = PIN_MAP[pin].timer_channel; // Protect used timers - if (timer == get_timer_dev(TEMP_TIMER_NUM)) return; - if (timer == get_timer_dev(STEP_TIMER_NUM)) return; - #if PULSE_TIMER_NUM != STEP_TIMER_NUM - if (timer == get_timer_dev(PULSE_TIMER_NUM)) return; + if (timer == HAL_get_timer_dev(MF_TIMER_TEMP)) return; + if (timer == HAL_get_timer_dev(MF_TIMER_STEP)) return; + #if MF_TIMER_PULSE != MF_TIMER_STEP + if (timer == HAL_get_timer_dev(MF_TIMER_PULSE)) return; #endif if (!(timer->regs.bas->SR & TIMER_CR1_CEN)) // Ensure the timer is enabled diff --git a/Marlin/src/HAL/STM32F1/timers.cpp b/Marlin/src/HAL/STM32F1/timers.cpp index 8c2df1e216e7d..112c730b9accb 100644 --- a/Marlin/src/HAL/STM32F1/timers.cpp +++ b/Marlin/src/HAL/STM32F1/timers.cpp @@ -47,10 +47,7 @@ * TODO: Calculate Timer prescale value, so we get the 32bit to adjust */ - - - -void timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority) { +void HAL_timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority) { nvic_irq_num irq_num; switch (timer_num) { case 1: irq_num = NVIC_TIMER1_CC; break; @@ -73,7 +70,6 @@ void timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority) nvic_irq_set_priority(irq_num, priority); } - void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { /** * Give the Stepper ISR a higher priority (lower number) @@ -81,7 +77,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { */ switch (timer_num) { - case STEP_TIMER_NUM: + case MF_TIMER_STEP: timer_pause(STEP_TIMER_DEV); timer_set_mode(STEP_TIMER_DEV, STEP_TIMER_CHAN, TIMER_OUTPUT_COMPARE); // counter timer_set_count(STEP_TIMER_DEV, 0); @@ -91,11 +87,11 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE) / frequency)); timer_no_ARR_preload_ARPE(STEP_TIMER_DEV); // Need to be sure no preload on ARR register timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler); - timer_set_interrupt_priority(STEP_TIMER_NUM, STEP_TIMER_IRQ_PRIO); + HAL_timer_set_interrupt_priority(MF_TIMER_STEP, STEP_TIMER_IRQ_PRIO); timer_generate_update(STEP_TIMER_DEV); timer_resume(STEP_TIMER_DEV); break; - case TEMP_TIMER_NUM: + case MF_TIMER_TEMP: timer_pause(TEMP_TIMER_DEV); timer_set_mode(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, TIMER_OUTPUT_COMPARE); timer_set_count(TEMP_TIMER_DEV, 0); @@ -103,7 +99,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { timer_set_reload(TEMP_TIMER_DEV, 0xFFFF); timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (F_CPU) / (TEMP_TIMER_PRESCALE) / frequency)); timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler); - timer_set_interrupt_priority(TEMP_TIMER_NUM, TEMP_TIMER_IRQ_PRIO); + HAL_timer_set_interrupt_priority(MF_TIMER_TEMP, TEMP_TIMER_IRQ_PRIO); timer_generate_update(TEMP_TIMER_DEV); timer_resume(TEMP_TIMER_DEV); break; @@ -112,31 +108,31 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { void HAL_timer_enable_interrupt(const uint8_t timer_num) { switch (timer_num) { - case STEP_TIMER_NUM: ENABLE_STEPPER_DRIVER_INTERRUPT(); break; - case TEMP_TIMER_NUM: ENABLE_TEMPERATURE_INTERRUPT(); break; + case MF_TIMER_STEP: ENABLE_STEPPER_DRIVER_INTERRUPT(); break; + case MF_TIMER_TEMP: ENABLE_TEMPERATURE_INTERRUPT(); break; } } void HAL_timer_disable_interrupt(const uint8_t timer_num) { switch (timer_num) { - case STEP_TIMER_NUM: DISABLE_STEPPER_DRIVER_INTERRUPT(); break; - case TEMP_TIMER_NUM: DISABLE_TEMPERATURE_INTERRUPT(); break; + case MF_TIMER_STEP: DISABLE_STEPPER_DRIVER_INTERRUPT(); break; + case MF_TIMER_TEMP: DISABLE_TEMPERATURE_INTERRUPT(); break; } } -static inline bool timer_irq_enabled(const timer_dev * const dev, const uint8_t interrupt) { +static inline bool HAL_timer_irq_enabled(const timer_dev * const dev, const uint8_t interrupt) { return bool(*bb_perip(&(dev->regs).gen->DIER, interrupt)); } bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { switch (timer_num) { - case STEP_TIMER_NUM: return timer_irq_enabled(STEP_TIMER_DEV, STEP_TIMER_CHAN); - case TEMP_TIMER_NUM: return timer_irq_enabled(TEMP_TIMER_DEV, TEMP_TIMER_CHAN); + case MF_TIMER_STEP: return HAL_timer_irq_enabled(STEP_TIMER_DEV, STEP_TIMER_CHAN); + case MF_TIMER_TEMP: return HAL_timer_irq_enabled(TEMP_TIMER_DEV, TEMP_TIMER_CHAN); } return false; } -timer_dev* get_timer_dev(int number) { +timer_dev* HAL_get_timer_dev(int number) { switch (number) { #if STM32_HAVE_TIMER(1) case 1: return &timer1; diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index c89d55a134b47..24e241ee3d52c 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -65,30 +65,30 @@ typedef uint16_t hal_timer_t; * - Otherwise it uses Timer 8 on boards with STM32_HIGH_DENSITY * or Timer 4 on other boards. */ -#ifndef STEP_TIMER_NUM +#ifndef MF_TIMER_STEP #if defined(MCU_STM32F103CB) || defined(MCU_STM32F103C8) - #define STEP_TIMER_NUM 4 // For C8/CB boards, use timer 4 + #define MF_TIMER_STEP 4 // For C8/CB boards, use timer 4 #else - #define STEP_TIMER_NUM 5 // for other boards, five is fine. + #define MF_TIMER_STEP 5 // for other boards, five is fine. #endif #endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP #endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 2 // Timer Index for Temperature - //#define TEMP_TIMER_NUM 4 // 2->4, Timer 2 for Stepper Current PWM +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP 2 // Timer Index for Temperature + //#define MF_TIMER_TEMP 4 // 2->4, Timer 2 for Stepper Current PWM #endif #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE, MKS_ROBIN_E3D, MKS_ROBIN_E3) // SKR Mini E3 boards use PA8 as FAN_PIN, so TIMER 1 is used for Fan PWM. #ifdef STM32_HIGH_DENSITY - #define SERVO0_TIMER_NUM 8 // tone.cpp uses Timer 4 + #define MF_TIMER_SERVO0 8 // tone.cpp uses Timer 4 #else - #define SERVO0_TIMER_NUM 3 // tone.cpp uses Timer 8 + #define MF_TIMER_SERVO0 3 // tone.cpp uses Timer 8 #endif #else - #define SERVO0_TIMER_NUM 1 // SERVO0 or BLTOUCH + #define MF_TIMER_SERVO0 1 // SERVO0 or BLTOUCH #endif #define STEP_TIMER_IRQ_PRIO 2 @@ -98,22 +98,22 @@ typedef uint16_t hal_timer_t; #define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz #define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency -#define STEPPER_TIMER_PRESCALE 18 // prescaler for setting stepper timer, 4Mhz -#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs +#define STEPPER_TIMER_PRESCALE 18 // prescaler for setting stepper timer, 4Mhz +#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -timer_dev* get_timer_dev(int number); -#define TIMER_DEV(num) get_timer_dev(num) -#define STEP_TIMER_DEV TIMER_DEV(STEP_TIMER_NUM) -#define TEMP_TIMER_DEV TIMER_DEV(TEMP_TIMER_NUM) +timer_dev* HAL_get_timer_dev(int number); +#define TIMER_DEV(num) HAL_get_timer_dev(num) +#define STEP_TIMER_DEV TIMER_DEV(MF_TIMER_STEP) +#define TEMP_TIMER_DEV TIMER_DEV(MF_TIMER_TEMP) #define ENABLE_STEPPER_DRIVER_INTERRUPT() timer_enable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN) #define DISABLE_STEPPER_DRIVER_INTERRUPT() timer_disable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) #define ENABLE_TEMPERATURE_INTERRUPT() timer_enable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN) #define DISABLE_TEMPERATURE_INTERRUPT() timer_disable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN) @@ -138,8 +138,8 @@ extern "C" { // Public Variables // ------------------------ -//static HardwareTimer StepperTimer(STEP_TIMER_NUM); -//static HardwareTimer TempTimer(TEMP_TIMER_NUM); +//static HardwareTimer StepperTimer(MF_TIMER_STEP); +//static HardwareTimer TempTimer(MF_TIMER_TEMP); // ------------------------ // Public functions @@ -163,13 +163,13 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num); FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { switch (timer_num) { - case STEP_TIMER_NUM: + case MF_TIMER_STEP: // NOTE: WE have set ARPE = 0, which means the Auto reload register is not preloaded // and there is no need to use any compare, as in the timer mode used, setting ARR to the compare value // will result in exactly the same effect, ie triggering an interrupt, and on top, set counter to 0 timer_set_reload(STEP_TIMER_DEV, compare); // We reload direct ARR as needed during counting up break; - case TEMP_TIMER_NUM: + case MF_TIMER_TEMP: timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, compare); break; } @@ -177,14 +177,14 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { switch (timer_num) { - case STEP_TIMER_NUM: - // No counter to clear - timer_generate_update(STEP_TIMER_DEV); - return; - case TEMP_TIMER_NUM: - timer_set_count(TEMP_TIMER_DEV, 0); - timer_generate_update(TEMP_TIMER_DEV); - return; + case MF_TIMER_STEP: + // No counter to clear + timer_generate_update(STEP_TIMER_DEV); + return; + case MF_TIMER_TEMP: + timer_set_count(TEMP_TIMER_DEV, 0); + timer_generate_update(TEMP_TIMER_DEV); + return; } } @@ -196,6 +196,6 @@ FORCE_INLINE static void timer_no_ARR_preload_ARPE(timer_dev *dev) { bb_peri_set_bit(&(dev->regs).gen->CR1, TIMER_CR1_ARPE_BIT, 0); } -void timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority); +void HAL_timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority); #define TIMER_OC_NO_PRELOAD 0 // Need to disable preload also on compare registers. diff --git a/Marlin/src/HAL/TEENSY31_32/timers.cpp b/Marlin/src/HAL/TEENSY31_32/timers.cpp index 7e01a38f89468..f217715a3fed0 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.cpp +++ b/Marlin/src/HAL/TEENSY31_32/timers.cpp @@ -47,7 +47,7 @@ FORCE_INLINE static void __DSB() { void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { switch (timer_num) { - case 0: + case MF_TIMER_STEP: FTM0_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN; FTM0_SC = 0x00; // Set this to zero before changing the modulus FTM0_CNT = 0x0000; // Reset the count to zero @@ -56,7 +56,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { FTM0_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM0_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 8 FTM0_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA; break; - case 1: + case MF_TIMER_TEMP: FTM1_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN; // Disable write protection, Enable FTM1 FTM1_SC = 0x00; // Set this to zero before changing the modulus FTM1_CNT = 0x0000; // Reset the count to zero @@ -70,15 +70,15 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { void HAL_timer_enable_interrupt(const uint8_t timer_num) { switch (timer_num) { - case 0: NVIC_ENABLE_IRQ(IRQ_FTM0); break; - case 1: NVIC_ENABLE_IRQ(IRQ_FTM1); break; + case MF_TIMER_STEP: NVIC_ENABLE_IRQ(IRQ_FTM0); break; + case MF_TIMER_TEMP: NVIC_ENABLE_IRQ(IRQ_FTM1); break; } } void HAL_timer_disable_interrupt(const uint8_t timer_num) { switch (timer_num) { - case 0: NVIC_DISABLE_IRQ(IRQ_FTM0); break; - case 1: NVIC_DISABLE_IRQ(IRQ_FTM1); break; + case MF_TIMER_STEP: NVIC_DISABLE_IRQ(IRQ_FTM0); break; + case MF_TIMER_TEMP: NVIC_DISABLE_IRQ(IRQ_FTM1); break; } // We NEED memory barriers to ensure Interrupts are actually disabled! @@ -89,20 +89,20 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num) { bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { switch (timer_num) { - case 0: return NVIC_IS_ENABLED(IRQ_FTM0); - case 1: return NVIC_IS_ENABLED(IRQ_FTM1); + case MF_TIMER_STEP: return NVIC_IS_ENABLED(IRQ_FTM0); + case MF_TIMER_TEMP: return NVIC_IS_ENABLED(IRQ_FTM1); } return false; } void HAL_timer_isr_prologue(const uint8_t timer_num) { switch (timer_num) { - case 0: + case MF_TIMER_STEP: FTM0_CNT = 0x0000; FTM0_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag FTM0_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag break; - case 1: + case MF_TIMER_TEMP: FTM1_CNT = 0x0000; FTM1_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag FTM1_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 61b86735967e9..08f82f0b7dced 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -46,14 +46,14 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_RATE (FTM0_TIMER_RATE) -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 0 // Timer Index for Stepper #endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP #endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP 1 // Timer Index for Temperature #endif #define TEMP_TIMER_FREQUENCY 1000 @@ -66,12 +66,12 @@ typedef uint32_t hal_timer_t; #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() @@ -84,23 +84,23 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { switch (timer_num) { - case 0: FTM0_C0V = compare; break; - case 1: FTM1_C0V = compare; break; + case MF_TIMER_STEP: FTM0_C0V = compare; break; + case MF_TIMER_TEMP: FTM1_C0V = compare; break; } } FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { switch (timer_num) { - case 0: return FTM0_C0V; - case 1: return FTM1_C0V; + case MF_TIMER_STEP: return FTM0_C0V; + case MF_TIMER_TEMP: return FTM1_C0V; } return 0; } FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { switch (timer_num) { - case 0: return FTM0_CNT; - case 1: return FTM1_CNT; + case MF_TIMER_STEP: return FTM0_CNT; + case MF_TIMER_TEMP: return FTM1_CNT; } return 0; } diff --git a/Marlin/src/HAL/TEENSY35_36/timers.cpp b/Marlin/src/HAL/TEENSY35_36/timers.cpp index 8067d091dd01b..39095fbd77af5 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.cpp +++ b/Marlin/src/HAL/TEENSY35_36/timers.cpp @@ -47,7 +47,7 @@ FORCE_INLINE static void __DSB() { void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { switch (timer_num) { - case 0: + case MF_TIMER_STEP: FTM0_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN; FTM0_SC = 0x00; // Set this to zero before changing the modulus FTM0_CNT = 0x0000; // Reset the count to zero @@ -56,7 +56,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { FTM0_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM0_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 8 FTM0_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA; break; - case 1: + case MF_TIMER_TEMP: FTM1_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN; // Disable write protection, Enable FTM1 FTM1_SC = 0x00; // Set this to zero before changing the modulus FTM1_CNT = 0x0000; // Reset the count to zero @@ -70,15 +70,15 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { void HAL_timer_enable_interrupt(const uint8_t timer_num) { switch (timer_num) { - case 0: NVIC_ENABLE_IRQ(IRQ_FTM0); break; - case 1: NVIC_ENABLE_IRQ(IRQ_FTM1); break; + case MF_TIMER_STEP: NVIC_ENABLE_IRQ(IRQ_FTM0); break; + case MF_TIMER_TEMP: NVIC_ENABLE_IRQ(IRQ_FTM1); break; } } void HAL_timer_disable_interrupt(const uint8_t timer_num) { switch (timer_num) { - case 0: NVIC_DISABLE_IRQ(IRQ_FTM0); break; - case 1: NVIC_DISABLE_IRQ(IRQ_FTM1); break; + case MF_TIMER_STEP: NVIC_DISABLE_IRQ(IRQ_FTM0); break; + case MF_TIMER_TEMP: NVIC_DISABLE_IRQ(IRQ_FTM1); break; } // We NEED memory barriers to ensure Interrupts are actually disabled! @@ -89,20 +89,20 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num) { bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { switch (timer_num) { - case 0: return NVIC_IS_ENABLED(IRQ_FTM0); - case 1: return NVIC_IS_ENABLED(IRQ_FTM1); + case MF_TIMER_STEP: return NVIC_IS_ENABLED(IRQ_FTM0); + case MF_TIMER_TEMP: return NVIC_IS_ENABLED(IRQ_FTM1); } return false; } void HAL_timer_isr_prologue(const uint8_t timer_num) { switch (timer_num) { - case 0: + case MF_TIMER_STEP: FTM0_CNT = 0x0000; FTM0_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag FTM0_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag break; - case 1: + case MF_TIMER_TEMP: FTM1_CNT = 0x0000; FTM1_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag FTM1_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 99269ac6571fa..4f65bdffd176b 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -45,14 +45,14 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_RATE (FTM0_TIMER_RATE) -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 0 // Timer Index for Stepper #endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP #endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP 1 // Timer Index for Temperature #endif #define TEMP_TIMER_FREQUENCY 1000 @@ -65,12 +65,12 @@ typedef uint32_t hal_timer_t; #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() @@ -83,23 +83,23 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { switch (timer_num) { - case 0: FTM0_C0V = compare; break; - case 1: FTM1_C0V = compare; break; + case MF_TIMER_STEP: FTM0_C0V = compare; break; + case MF_TIMER_TEMP: FTM1_C0V = compare; break; } } FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { switch (timer_num) { - case 0: return FTM0_C0V; - case 1: return FTM1_C0V; + case MF_TIMER_STEP: return FTM0_C0V; + case MF_TIMER_TEMP: return FTM1_C0V; } return 0; } FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { switch (timer_num) { - case 0: return FTM0_CNT; - case 1: return FTM1_CNT; + case MF_TIMER_STEP: return FTM0_CNT; + case MF_TIMER_TEMP: return FTM1_CNT; } return 0; } diff --git a/Marlin/src/HAL/TEENSY40_41/timers.cpp b/Marlin/src/HAL/TEENSY40_41/timers.cpp index 81c9b08c17a5a..ed99f65d6e269 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.cpp +++ b/Marlin/src/HAL/TEENSY40_41/timers.cpp @@ -30,7 +30,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { switch (timer_num) { - case 0: + case MF_TIMER_STEP: CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode CCM_CCGR1 |= CCM_CCGR1_GPT1_BUS(CCM_CCGR_ON); @@ -48,7 +48,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { attachInterruptVector(IRQ_GPT1, &stepTC_Handler); NVIC_SET_PRIORITY(IRQ_GPT1, 16); break; - case 1: + case MF_TIMER_TEMP: CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode CCM_CCGR0 |= CCM_CCGR0_GPT2_BUS(CCM_CCGR_ON); @@ -71,19 +71,15 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { void HAL_timer_enable_interrupt(const uint8_t timer_num) { switch (timer_num) { - case 0: - NVIC_ENABLE_IRQ(IRQ_GPT1); - break; - case 1: - NVIC_ENABLE_IRQ(IRQ_GPT2); - break; + case MF_TIMER_STEP: NVIC_ENABLE_IRQ(IRQ_GPT1); break; + case MF_TIMER_TEMP: NVIC_ENABLE_IRQ(IRQ_GPT2); break; } } void HAL_timer_disable_interrupt(const uint8_t timer_num) { switch (timer_num) { - case 0: NVIC_DISABLE_IRQ(IRQ_GPT1); break; - case 1: NVIC_DISABLE_IRQ(IRQ_GPT2); break; + case MF_TIMER_STEP: NVIC_DISABLE_IRQ(IRQ_GPT1); break; + case MF_TIMER_TEMP: NVIC_DISABLE_IRQ(IRQ_GPT2); break; } // We NEED memory barriers to ensure Interrupts are actually disabled! @@ -93,20 +89,16 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num) { bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { switch (timer_num) { - case 0: return (NVIC_IS_ENABLED(IRQ_GPT1)); - case 1: return (NVIC_IS_ENABLED(IRQ_GPT2)); + case MF_TIMER_STEP: return (NVIC_IS_ENABLED(IRQ_GPT1)); + case MF_TIMER_TEMP: return (NVIC_IS_ENABLED(IRQ_GPT2)); } return false; } void HAL_timer_isr_prologue(const uint8_t timer_num) { switch (timer_num) { - case 0: - GPT1_SR = GPT_IR_OF1IE; // clear OF3 bit - break; - case 1: - GPT2_SR = GPT_IR_OF1IE; // clear OF3 bit - break; + case MF_TIMER_STEP: GPT1_SR = GPT_IR_OF1IE; break; // clear OF3 bit + case MF_TIMER_TEMP: GPT2_SR = GPT_IR_OF1IE; break; // clear OF3 bit } asm volatile("dsb"); } diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 556333d7f4082..afb373c599c3e 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -43,14 +43,14 @@ typedef uint32_t hal_timer_t; #define GPT1_TIMER_RATE (GPT_TIMER_RATE / GPT1_TIMER_PRESCALE) // 75MHz #define GPT2_TIMER_RATE (GPT_TIMER_RATE / GPT2_TIMER_PRESCALE) // 15MHz -#ifndef STEP_TIMER_NUM - #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#ifndef MF_TIMER_STEP + #define MF_TIMER_STEP 0 // Timer Index for Stepper #endif -#ifndef PULSE_TIMER_NUM - #define PULSE_TIMER_NUM STEP_TIMER_NUM +#ifndef MF_TIMER_PULSE + #define MF_TIMER_PULSE MF_TIMER_STEP #endif -#ifndef TEMP_TIMER_NUM - #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#ifndef MF_TIMER_TEMP + #define MF_TIMER_TEMP 1 // Timer Index for Temperature #endif #define TEMP_TIMER_RATE 1000000 @@ -64,12 +64,12 @@ typedef uint32_t hal_timer_t; #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() // GPT1_Handler() @@ -87,27 +87,23 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { switch (timer_num) { - case 0: - GPT1_OCR1 = compare - 1; - break; - case 1: - GPT2_OCR1 = compare - 1; - break; + case MF_TIMER_STEP: GPT1_OCR1 = compare - 1; break; + case MF_TIMER_TEMP: GPT2_OCR1 = compare - 1; break; } } FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { switch (timer_num) { - case 0: return GPT1_OCR1; - case 1: return GPT2_OCR1; + case MF_TIMER_STEP: return GPT1_OCR1; + case MF_TIMER_TEMP: return GPT2_OCR1; } return 0; } FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { switch (timer_num) { - case 0: return GPT1_CNT; - case 1: return GPT2_CNT; + case MF_TIMER_STEP: return GPT1_CNT; + case MF_TIMER_TEMP: return GPT2_CNT; } return 0; } diff --git a/Marlin/src/feature/easythreed_ui.cpp b/Marlin/src/feature/easythreed_ui.cpp index 3eff233c014ac..9f8af039478ca 100644 --- a/Marlin/src/feature/easythreed_ui.cpp +++ b/Marlin/src/feature/easythreed_ui.cpp @@ -88,7 +88,7 @@ void EasythreedUI::blinkLED() { // // Filament Load/Unload Button -// Load/Unload buttons are a 3 position switch with a common center ground. +// Load/Unload buttons are a 3 position switch with a common center ground. // void EasythreedUI::loadButton() { if (printingIsActive()) return; @@ -208,7 +208,7 @@ void EasythreedUI::printButton() { print_key_flag = PF_RESUME; // The "Print" button now resumes the print break; } - case PF_RESUME: { // Resume printing + case PF_RESUME: { // Resume printing if (printingIsActive()) break; blink_interval_ms = LED_BLINK_2; // Blink the indicator LED at 1 second intervals queue.inject(F("M24")); // Queue resume diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 60574b65f0582..69e3f035ba9de 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -875,7 +875,7 @@ class Planner { || TERN0(EXTERNAL_CLOSED_LOOP_CONTROLLER, CLOSED_LOOP_WAITING()) ); } - + // Block until all buffered steps are executed / cleaned static void synchronize(); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 69818aff7ae17..b93dd21198d92 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -464,8 +464,8 @@ xyze_int8_t Stepper::count_direction{0}; #define PULSE_LOW_TICK_COUNT hal_timer_t(NS_TO_PULSE_TIMER_TICKS(_MIN_PULSE_LOW_NS - _MIN(_MIN_PULSE_LOW_NS, TIMER_SETUP_NS))) #define USING_TIMED_PULSE() hal_timer_t start_pulse_count = 0 -#define START_TIMED_PULSE(DIR) (start_pulse_count = HAL_timer_get_count(PULSE_TIMER_NUM)) -#define AWAIT_TIMED_PULSE(DIR) while (PULSE_##DIR##_TICK_COUNT > HAL_timer_get_count(PULSE_TIMER_NUM) - start_pulse_count) { } +#define START_TIMED_PULSE(DIR) (start_pulse_count = HAL_timer_get_count(MF_TIMER_PULSE)) +#define AWAIT_TIMED_PULSE(DIR) while (PULSE_##DIR##_TICK_COUNT > HAL_timer_get_count(MF_TIMER_PULSE) - start_pulse_count) { } #define START_HIGH_PULSE() START_TIMED_PULSE(HIGH) #define AWAIT_HIGH_PULSE() AWAIT_TIMED_PULSE(HIGH) #define START_LOW_PULSE() START_TIMED_PULSE(LOW) @@ -1454,11 +1454,11 @@ void Stepper::set_directions() { */ HAL_STEP_TIMER_ISR() { - HAL_timer_isr_prologue(STEP_TIMER_NUM); + HAL_timer_isr_prologue(MF_TIMER_STEP); Stepper::isr(); - HAL_timer_isr_epilogue(STEP_TIMER_NUM); + HAL_timer_isr_epilogue(MF_TIMER_STEP); } #ifdef CPU_32_BIT @@ -1480,7 +1480,7 @@ void Stepper::isr() { // Program timer compare for the maximum period, so it does NOT // flag an interrupt while this ISR is running - So changes from small // periods to big periods are respected and the timer does not reset to 0 - HAL_timer_set_compare(STEP_TIMER_NUM, hal_timer_t(HAL_TIMER_TYPE_MAX)); + HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(HAL_TIMER_TYPE_MAX)); // Count of ticks for the next ISR hal_timer_t next_isr_ticks = 0; @@ -1584,7 +1584,7 @@ void Stepper::isr() { * On AVR the ISR epilogue+prologue is estimated at 100 instructions - Give 8µs as margin * On ARM the ISR epilogue+prologue is estimated at 20 instructions - Give 1µs as margin */ - min_ticks = HAL_timer_get_count(STEP_TIMER_NUM) + hal_timer_t( + min_ticks = HAL_timer_get_count(MF_TIMER_STEP) + hal_timer_t( #ifdef __AVR__ 8 #else @@ -1608,7 +1608,7 @@ void Stepper::isr() { // sure that the time has not arrived yet - Warrantied by the scheduler // Set the next ISR to fire at the proper time - HAL_timer_set_compare(STEP_TIMER_NUM, hal_timer_t(next_isr_ticks)); + HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(next_isr_ticks)); // Don't forget to finally reenable interrupts ENABLE_ISRS(); @@ -2769,7 +2769,7 @@ void Stepper::init() { #endif #if DISABLED(I2S_STEPPER_STREAM) - HAL_timer_start(STEP_TIMER_NUM, 122); // Init Stepper ISR to 122 Hz for quick starting + HAL_timer_start(MF_TIMER_STEP, 122); // Init Stepper ISR to 122 Hz for quick starting wake_up(); sei(); #endif @@ -2980,8 +2980,8 @@ void Stepper::report_positions() { #define EXTRA_CYCLES_BABYSTEP (STEP_PULSE_CYCLES - (CYCLES_EATEN_BABYSTEP)) #if EXTRA_CYCLES_BABYSTEP > 20 - #define _SAVE_START() const hal_timer_t pulse_start = HAL_timer_get_count(PULSE_TIMER_NUM) - #define _PULSE_WAIT() while (EXTRA_CYCLES_BABYSTEP > (uint32_t)(HAL_timer_get_count(PULSE_TIMER_NUM) - pulse_start) * (PULSE_TIMER_PRESCALE)) { /* nada */ } + #define _SAVE_START() const hal_timer_t pulse_start = HAL_timer_get_count(MF_TIMER_PULSE) + #define _PULSE_WAIT() while (EXTRA_CYCLES_BABYSTEP > (uint32_t)(HAL_timer_get_count(MF_TIMER_PULSE) - pulse_start) * (PULSE_TIMER_PRESCALE)) { /* nada */ } #else #define _SAVE_START() NOOP #if EXTRA_CYCLES_BABYSTEP > 0 diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 187776de12f7c..758275d21e315 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2387,7 +2387,7 @@ void Temperature::init() { HAL_ANALOG_SELECT(POWER_MONITOR_VOLTAGE_PIN); #endif - HAL_timer_start(TEMP_TIMER_NUM, TEMP_TIMER_FREQUENCY); + HAL_timer_start(MF_TIMER_TEMP, TEMP_TIMER_FREQUENCY); ENABLE_TEMPERATURE_INTERRUPT(); #if HAS_AUTO_FAN_0 @@ -2968,11 +2968,11 @@ void Temperature::readings_ready() { * - Call planner.isr to count down its "ignore" time */ HAL_TEMP_TIMER_ISR() { - HAL_timer_isr_prologue(TEMP_TIMER_NUM); + HAL_timer_isr_prologue(MF_TIMER_TEMP); Temperature::isr(); - HAL_timer_isr_epilogue(TEMP_TIMER_NUM); + HAL_timer_isr_epilogue(MF_TIMER_TEMP); } #if ENABLED(SLOW_PWM_HEATERS) && !defined(MIN_STATE_TIME) diff --git a/Marlin/src/pins/sam/pins_ARCHIM1.h b/Marlin/src/pins/sam/pins_ARCHIM1.h index 57bbeb62a2807..d9f1dcbf94272 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM1.h +++ b/Marlin/src/pins/sam/pins_ARCHIM1.h @@ -46,8 +46,7 @@ // // Timers // -// These are already defined in DUE, so must be undefined first -#define STEP_TIMER_NUM 3 +#define MF_TIMER_STEP 3 #define HAL_STEP_TIMER_ISR() void TC3_Handler() // diff --git a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h index 299b9ff49cee3..904a9a56fac60 100644 --- a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h +++ b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h @@ -45,8 +45,8 @@ // // Timers // -#define STEP_TIMER 6 -#define TEMP_TIMER 7 +#define STEP_TIMER 6 +#define TEMP_TIMER 7 // // Limit Switches diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h index e19d3300921a2..947e36c765e7b 100644 --- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -41,7 +41,7 @@ #define BOARD_NO_NATIVE_USB // Avoid conflict with TIMER_SERVO when using the STM32 HAL -#define TEMP_TIMER 5 +#define TEMP_TIMER 5 // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role diff --git a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h index 32d1937653d7e..94e53400996ea 100644 --- a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h +++ b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h @@ -47,8 +47,8 @@ // On STM32F103: // PB3, PB6, PB7, and PB8 can be used with pwm, which rules out TIM2 and TIM4. // On STM32F070, 16 and 17 are in use, but 1 and 3 are available. -#define STEP_TIMER 1 -#define TEMP_TIMER 3 +#define STEP_TIMER 1 +#define TEMP_TIMER 3 // // Limit Switches diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 67072968974b9..a51f28bf957fc 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -39,7 +39,7 @@ #define MKS_HARDWARE_TEST_ONLY_E0 // Avoid conflict with TIMER_SERVO when using the STM32 HAL -#define TEMP_TIMER 5 +#define TEMP_TIMER 5 // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role 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 e8d567bc70cfd..592d585982df7 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -39,7 +39,7 @@ #define USES_DIAG_PINS // Avoid conflict with TIMER_SERVO when using the STM32 HAL -#define TEMP_TIMER 5 +#define TEMP_TIMER 5 // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role 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 c76175a35c1b0..c1d0e591e9724 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h @@ -32,7 +32,7 @@ #define BOARD_NO_NATIVE_USB // Avoid conflict with TIMER_SERVO when using the STM32 HAL -#define TEMP_TIMER 5 +#define TEMP_TIMER 5 // // EEPROM 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 efeff04f256af..9db0459be9549 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -33,7 +33,7 @@ #define I2C_SDA_PIN PB9 // Avoid conflict with TIMER_TONE -#define STEP_TIMER 10 +#define STEP_TIMER 10 // // Servos 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 0a80c99878a2b..a2111d849ed37 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 @@ -50,7 +50,7 @@ #define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support // Avoid conflict with TIMER_TONE -#define STEP_TIMER 10 +#define STEP_TIMER 10 // // Servos diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 794649e4166e2..af316cf4b1d05 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -33,8 +33,8 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME // Avoid conflict with fans and TIMER_TONE -#define TEMP_TIMER 3 -#define STEP_TIMER 5 +#define TEMP_TIMER 3 +#define STEP_TIMER 5 // // EEPROM Emulation diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h index c686e19ccb294..c904d57a1f0aa 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h @@ -31,8 +31,8 @@ #define BOARD_INFO_NAME "Lerdge S" #define DEFAULT_MACHINE_NAME "LERDGE" -#define STEP_TIMER 4 -#define TEMP_TIMER 2 +#define STEP_TIMER 4 +#define TEMP_TIMER 2 #define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h index 93526db4425c8..5048933146feb 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h @@ -31,8 +31,8 @@ #define BOARD_INFO_NAME "Lerdge X" #define DEFAULT_MACHINE_NAME "LERDGE" -#define STEP_TIMER 4 -#define TEMP_TIMER 2 +#define STEP_TIMER 4 +#define TEMP_TIMER 2 #define I2C_EEPROM #define I2C_SCL_PIN PB8 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index 00dcade892fe7..2f77c0f9d6f93 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -38,7 +38,7 @@ //#define DISABLE_DEBUG // Avoid conflict with TIMER_TONE -#define STEP_TIMER 10 +#define STEP_TIMER 10 // Use one of these or SDCard-based Emulation will be used //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation 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 48d2ffef6ec85..c2dea50b29884 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 @@ -29,7 +29,7 @@ #define HAS_OTG_USB_HOST_SUPPORT // USB Flash Drive support // Avoid conflict with TIMER_TONE -#define STEP_TIMER 10 +#define STEP_TIMER 10 // Use one of these or SDCard-based Emulation will be used //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index 00f49acbeb46f..cf7c9ed8a6810 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -45,8 +45,8 @@ // This will be difficult to solve from the Arduino IDE, without modifying the RUMBA32 variant // included with the STM32 framework. -#define STEP_TIMER 10 -#define TEMP_TIMER 14 +#define STEP_TIMER 10 +#define TEMP_TIMER 14 // // Limit Switches diff --git a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h index c41b5ab1dec21..75c7217163b8a 100644 --- a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h +++ b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h @@ -57,8 +57,8 @@ * TIM14 - TEMP_TIMER (Marlin) * */ -#define STEP_TIMER 4 -#define TEMP_TIMER 14 +#define STEP_TIMER 4 +#define TEMP_TIMER 14 /** * These pin assignments are arbitrary and intending for testing purposes. diff --git a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h index dbf2593c481d1..486c10e71164f 100644 --- a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h +++ b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h @@ -134,4 +134,4 @@ // Timers // -#define STEP_TIMER 2 +#define STEP_TIMER 2 From 1874787b6bb840156e4ebb721ae6ee6b6438b97a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 28 Nov 2021 01:02:49 +0000 Subject: [PATCH 097/273] [cron] Bump distribution date (2021-11-28) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e635eb5f10028..0c76c76fd8a94 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 "2021-11-27" +//#define STRING_DISTRIBUTION_DATE "2021-11-28" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4f9c01170399c..a660a0cd9f98e 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 "2021-11-27" + #define STRING_DISTRIBUTION_DATE "2021-11-28" #endif /** From a276c088e33417403ca468879678d837c00433e2 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 29 Nov 2021 01:01:36 +0000 Subject: [PATCH 098/273] [cron] Bump distribution date (2021-11-29) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 0c76c76fd8a94..f50e7271af1cf 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 "2021-11-28" +//#define STRING_DISTRIBUTION_DATE "2021-11-29" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a660a0cd9f98e..04aa7b6449d1a 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 "2021-11-28" + #define STRING_DISTRIBUTION_DATE "2021-11-29" #endif /** From 9e71f9baf9aad453be1a5c4ff5cd604b18e65d2d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 30 Nov 2021 01:01:54 +0000 Subject: [PATCH 099/273] [cron] Bump distribution date (2021-11-30) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index f50e7271af1cf..fd3ceff1faf5a 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 "2021-11-29" +//#define STRING_DISTRIBUTION_DATE "2021-11-30" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 04aa7b6449d1a..b3541e84044b9 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 "2021-11-29" + #define STRING_DISTRIBUTION_DATE "2021-11-30" #endif /** From 7ffada64ceb4d8e5a2ca1e7a75638a3bb6be6cf4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 30 Nov 2021 13:03:31 -0600 Subject: [PATCH 100/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20STM32=20FastPWM?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/fast_pwm.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index 8eaecd718e557..d28bc1b84bc4c 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -71,6 +71,8 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 void set_pwm_frequency(const pin_t pin, int f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer + const PinName pin_name = digitalPinToPinName(pin); + TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance uint32_t index = get_timer_index(Instance); // Protect used timers @@ -80,8 +82,6 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { #endif ) return; - const PinName pin_name = digitalPinToPinName(pin); - TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance if (HardwareTimer_Handle[index] == nullptr) // If frequency is set before duty we need to create a handle here. HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM)); HardwareTimer * const HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); From 1f5eaf29b947a1486699c588cbe1e274cfb72ec4 Mon Sep 17 00:00:00 2001 From: Jiri Jirus Date: Tue, 30 Nov 2021 21:46:48 +0100 Subject: [PATCH 101/273] =?UTF-8?q?=F0=9F=A9=B9=20Assume=204K=20EEPROM=20f?= =?UTF-8?q?or=20RUMBA32=20BTT=20(#23205)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h index f2fc53379be15..28d2dfd1806f4 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_BTT.h @@ -30,7 +30,7 @@ #if NO_EEPROM_SELECTED #define I2C_EEPROM - #define MARLIN_EEPROM_SIZE 0x2000 // 8KB (24LC64T-I/OT) + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB (24LC32AT-I/OT) #endif #if ENABLED(FLASH_EEPROM_EMULATION) From c09641c7c0cddadd67eb7f873d0c9e2633376821 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 30 Nov 2021 15:04:05 -0600 Subject: [PATCH 102/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20STM32=20FastPWM?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/fast_pwm.cpp | 30 +++++++++++------------------- 1 file changed, 11 insertions(+), 19 deletions(-) diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index d28bc1b84bc4c..209918489333e 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -32,26 +32,17 @@ static uint16_t timer_freq[TIMER_NUM]; void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer - bool needs_freq; PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); - HardwareTimer *HT; - TimerModes_t previousMode; - uint16_t value = v; - if (invert) value = v_size - value; - - uint32_t index = get_timer_index(Instance); - - if (HardwareTimer_Handle[index] == nullptr) { + const uint32_t index = get_timer_index(Instance); + bool needs_freq = (HardwareTimer_Handle[index] == nullptr); // A new instance must be set to the default frequency of PWM_FREQUENCY + if (needs_freq) HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM)); - needs_freq = true; // The instance must be new set the default frequency of PWM_FREQUENCY - } - - HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); - uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin_name, PinMap_PWM)); - previousMode = HT->getMode(channel); + HardwareTimer * const HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); + const uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin_name, PinMap_PWM)); + const TimerModes_t previousMode = HT->getMode(channel); if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, pin); @@ -63,6 +54,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 } // Note the resolution is sticky here, the input can be upto 16 bits and that would require RESOLUTION_16B_COMPARE_FORMAT (16) // If such a need were to manifest then we would need to calc the resolution based on the v_size parameter and add code for it. + const uint16_t value = invert ? v_size - v : v; HT->setCaptureCompare(channel, value, RESOLUTION_8B_COMPARE_FORMAT); // Sets the duty, the calc is done in the library :) pinmap_pinout(pin_name, PinMap_PWM); // Make sure the pin output state is set. if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume(); @@ -73,12 +65,12 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { const PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance - uint32_t index = get_timer_index(Instance); + const uint32_t index = get_timer_index(Instance); // Protect used timers - if (index == TEMP_TIMER_NUM || index == STEP_TIMER_NUM - #if PULSE_TIMER_NUM != STEP_TIMER_NUM - || index == PULSE_TIMER_NUM + if (index == MF_TIMER_TEMP || index == MF_TIMER_STEP + #if MF_TIMER_PULSE != MF_TIMER_STEP + || index == MF_TIMER_PULSE #endif ) return; From f46c76f3608ed3e229a36229bf6d0878fb4ab51e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 1 Dec 2021 01:05:56 +0000 Subject: [PATCH 103/273] [cron] Bump distribution date (2021-12-01) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index fd3ceff1faf5a..efd79c97f84f5 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 "2021-11-30" +//#define STRING_DISTRIBUTION_DATE "2021-12-01" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b3541e84044b9..8c09fbb850c77 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 "2021-11-30" + #define STRING_DISTRIBUTION_DATE "2021-12-01" #endif /** From b9ee84e8dcc6ae81aba3d46e079ed26e1a308a49 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 2 Dec 2021 01:02:43 +0000 Subject: [PATCH 104/273] [cron] Bump distribution date (2021-12-02) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index efd79c97f84f5..da5596aae39b6 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 "2021-12-01" +//#define STRING_DISTRIBUTION_DATE "2021-12-02" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 8c09fbb850c77..436384c2d4888 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 "2021-12-01" + #define STRING_DISTRIBUTION_DATE "2021-12-02" #endif /** From e3d7274c84242aebdfef2b164d5b89cb99ee6ac3 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 3 Dec 2021 01:02:06 +0000 Subject: [PATCH 105/273] [cron] Bump distribution date (2021-12-03) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index da5596aae39b6..456a5c33bce90 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 "2021-12-02" +//#define STRING_DISTRIBUTION_DATE "2021-12-03" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 436384c2d4888..42c737ca3cfd1 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 "2021-12-02" + #define STRING_DISTRIBUTION_DATE "2021-12-03" #endif /** From 2a1facf8530ac931760ca43b9ecb11d57409ff74 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Fri, 3 Dec 2021 19:31:48 +0100 Subject: [PATCH 106/273] =?UTF-8?q?=F0=9F=8F=97=EF=B8=8F=20Rework=20STM32?= =?UTF-8?q?=20timer=20frequency=20protection=20(#23187)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/fast_pwm.cpp | 41 +++++++++++++++---------------- Marlin/src/HAL/STM32/timers.h | 15 +++++------ 2 files changed, 26 insertions(+), 30 deletions(-) diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index 209918489333e..b1bea5ce20eb8 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -25,19 +25,18 @@ #ifdef HAL_STM32 #include "../../inc/MarlinConfig.h" -#include "timers.h" // Array to support sticky frequency sets per timer static uint16_t timer_freq[TIMER_NUM]; void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer - PinName pin_name = digitalPinToPinName(pin); - TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); + const PinName pin_name = digitalPinToPinName(pin); + TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); - const uint32_t index = get_timer_index(Instance); - bool needs_freq = (HardwareTimer_Handle[index] == nullptr); // A new instance must be set to the default frequency of PWM_FREQUENCY - if (needs_freq) + const timer_index_t index = get_timer_index(Instance); + const bool needs_freq = (HardwareTimer_Handle[index] == nullptr); + if (needs_freq) // A new instance must be set to the default frequency of PWM_FREQUENCY HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM)); HardwareTimer * const HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); @@ -46,12 +45,9 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, pin); - if (needs_freq) { - if (timer_freq[index] == 0 ) { // If the timer is unconfigured and no freq is set then default PWM_FREQUENCY. - timer_freq[index] = PWM_FREQUENCY; - set_pwm_frequency(pin_name, timer_freq[index]); // Set the frequency and save the value to the assigned index no. - } - } + if (needs_freq && timer_freq[index] == 0) // If the timer is unconfigured and no freq is set then default PWM_FREQUENCY + set_pwm_frequency(pin_name, PWM_FREQUENCY); // Set the frequency and save the value to the assigned index no. + // Note the resolution is sticky here, the input can be upto 16 bits and that would require RESOLUTION_16B_COMPARE_FORMAT (16) // If such a need were to manifest then we would need to calc the resolution based on the v_size parameter and add code for it. const uint16_t value = invert ? v_size - v : v; @@ -62,23 +58,26 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 void set_pwm_frequency(const pin_t pin, int f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer - const PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance - const uint32_t index = get_timer_index(Instance); + const timer_index_t index = get_timer_index(Instance); - // Protect used timers - if (index == MF_TIMER_TEMP || index == MF_TIMER_STEP - #if MF_TIMER_PULSE != MF_TIMER_STEP - || index == MF_TIMER_PULSE - #endif - ) return; + // Protect used timers. + #ifdef STEP_TIMER + if (index == TIMER_INDEX(STEP_TIMER)) return; + #endif + #ifdef TEMP_TIMER + if (index == TIMER_INDEX(TEMP_TIMER)) return; + #endif + #if defined(PULSE_TIMER) && MF_TIMER_PULSE != MF_TIMER_STEP + if (index == TIMER_INDEX(PULSE_TIMER)) return; + #endif if (HardwareTimer_Handle[index] == nullptr) // If frequency is set before duty we need to create a handle here. HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM)); HardwareTimer * const HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this); - timer_freq[index] = f_desired; // Save the last frequency so duty will not set the default for this timer number. HT->setOverflow(f_desired, HERTZ_FORMAT); + timer_freq[index] = f_desired; // Save the last frequency so duty will not set the default for this timer number. } #endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index ae70e658868ed..33b5d8470f32e 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -40,17 +40,14 @@ #define hal_timer_t uint32_t #define HAL_TIMER_TYPE_MAX UINT16_MAX +// Marlin timer_instance[] content (unrelated to timer selection) #define NUM_HARDWARE_TIMERS 2 +#define MF_TIMER_STEP 0 // Timer Index for Stepper +#define MF_TIMER_TEMP 1 // Timer Index for Temperature +#define MF_TIMER_PULSE MF_TIMER_STEP -#ifndef MF_TIMER_STEP - #define MF_TIMER_STEP 0 // Timer Index for Stepper -#endif -#ifndef MF_TIMER_PULSE - #define MF_TIMER_PULSE MF_TIMER_STEP -#endif -#ifndef MF_TIMER_TEMP - #define MF_TIMER_TEMP 1 // Timer Index for Temperature -#endif +#define TIMER_INDEX_(T) TIMER##T##_INDEX // TIMER#_INDEX enums (timer_index_t) depend on TIM#_BASE defines. +#define TIMER_INDEX(T) TIMER_INDEX_(T) // Convert Timer ID to HardwareTimer_Handle index. #define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() is expected to be called at around 1kHz From 4411af655e60646b0b114f759a62cedc8e0e6aa4 Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Fri, 3 Dec 2021 12:48:48 -0600 Subject: [PATCH 107/273] =?UTF-8?q?=F0=9F=8F=97=EF=B8=8F=20Fix=20Maple=20H?= =?UTF-8?q?AL/STM32F1=20PWM=20(#23211)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/timers.h | 4 ++-- Marlin/src/HAL/DUE/timers.h | 2 +- Marlin/src/HAL/ESP32/timers.h | 4 ++-- Marlin/src/HAL/LINUX/timers.h | 4 ++-- Marlin/src/HAL/LPC1768/timers.h | 2 +- Marlin/src/HAL/NATIVE_SIM/timers.h | 4 ++-- Marlin/src/HAL/STM32/timers.cpp | 10 +++++++-- Marlin/src/HAL/STM32/timers.h | 5 ++--- Marlin/src/HAL/STM32F1/fast_pwm.cpp | 32 +++++++++++++++++++++-------- Marlin/src/HAL/STM32F1/timers.h | 2 +- Marlin/src/HAL/TEENSY31_32/timers.h | 2 +- Marlin/src/HAL/TEENSY35_36/timers.h | 2 +- Marlin/src/HAL/TEENSY40_41/timers.h | 2 +- 13 files changed, 48 insertions(+), 27 deletions(-) diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index 29907204acc58..36b04eae0d1ff 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -109,8 +109,8 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) { * (otherwise, characters will be lost due to UART overflow). * Then: Stepper, Endstops, Temperature, and -finally- all others. */ -#define HAL_timer_isr_prologue(TIMER_NUM) -#define HAL_timer_isr_epilogue(TIMER_NUM) +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) /* 18 cycles maximum latency */ #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index bab67826df788..e2932ff36f91b 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -125,4 +125,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR; } -#define HAL_timer_isr_epilogue(TIMER_NUM) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index b651ffe6b11d5..266169848daf7 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -136,5 +136,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(TIMER_NUM) -#define HAL_timer_isr_epilogue(TIMER_NUM) +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index 21dba620717e7..a98ceb6f391d9 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -92,5 +92,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(TIMER_NUM) -#define HAL_timer_isr_epilogue(TIMER_NUM) +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index ef437cabac12e..78e856db28578 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -170,4 +170,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(TIMER_NUM) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index 4d140a4b6cd7a..cedfdb62d631f 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -87,5 +87,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(TIMER_NUM) -#define HAL_timer_isr_epilogue(TIMER_NUM) +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index 8f1659591b1fe..53a1f2a8e97be 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -97,9 +97,15 @@ #define STEP_TIMER_DEV _TIMER_DEV(STEP_TIMER) #define TEMP_TIMER_DEV _TIMER_DEV(TEMP_TIMER) -// ------------------------ +// -------------------------------------------------------------------------- +// Local defines +// -------------------------------------------------------------------------- + +#define NUM_HARDWARE_TIMERS 2 + +// -------------------------------------------------------------------------- // Private Variables -// ------------------------ +// -------------------------------------------------------------------------- HardwareTimer *timer_instance[NUM_HARDWARE_TIMERS] = { nullptr }; diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 33b5d8470f32e..aad543229e164 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -41,7 +41,6 @@ #define HAL_TIMER_TYPE_MAX UINT16_MAX // Marlin timer_instance[] content (unrelated to timer selection) -#define NUM_HARDWARE_TIMERS 2 #define MF_TIMER_STEP 0 // Timer Index for Stepper #define MF_TIMER_TEMP 1 // Timer Index for Temperature #define MF_TIMER_PULSE MF_TIMER_STEP @@ -117,5 +116,5 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha } } -#define HAL_timer_isr_prologue(TIMER_NUM) -#define HAL_timer_isr_epilogue(TIMER_NUM) +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp index 994e62dbcd4fb..98d56bc5e9319 100644 --- a/Marlin/src/HAL/STM32F1/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp @@ -27,21 +27,35 @@ #include "HAL.h" #include "timers.h" +#define NR_TIMERS TERN(STM32_XL_DENSITY, 14, 8) // Maple timers, 14 for STM32_XL_DENSITY (F/G chips), 8 for HIGH density (C D E) + +static uint16_t timer_freq[NR_TIMERS]; + +inline uint8_t timer_and_index_for_pin(const pin_t pin, timer_dev **timer_ptr) { + *timer_ptr = PIN_MAP[pin].timer_device; + for (uint8_t i = 0; i < NR_TIMERS; i++) if (*timer_ptr == HAL_get_timer_dev(i)) + return i; + return 0; +} + void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!PWM_PIN(pin)) return; - timer_dev *timer = PIN_MAP[pin].timer_device; - if (!(timer->regs.bas->SR & TIMER_CR1_CEN)) // Ensure the timer is enabled + + timer_dev *timer; UNUSED(timer); + if (timer_freq[timer_and_index_for_pin(pin, &timer)] == 0) set_pwm_frequency(pin, PWM_FREQUENCY); - uint16_t max_val = timer->regs.bas->ARR * v / v_size; - if (invert) max_val = v_size - max_val; - pwmWrite(pin, max_val); + + const uint8_t channel = PIN_MAP[pin].timer_channel; + const uint16_t duty = invert ? v_size - v : v; + timer_set_compare(timer, channel, duty); + timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode } void set_pwm_frequency(const pin_t pin, int f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer - timer_dev *timer = PIN_MAP[pin].timer_device; - uint8_t channel = PIN_MAP[pin].timer_channel; + timer_dev *timer; UNUSED(timer); + timer_freq[timer_and_index_for_pin(pin, &timer)] = f_desired; // Protect used timers if (timer == HAL_get_timer_dev(MF_TIMER_TEMP)) return; @@ -53,8 +67,10 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { if (!(timer->regs.bas->SR & TIMER_CR1_CEN)) // Ensure the timer is enabled timer_init(timer); + const uint8_t channel = PIN_MAP[pin].timer_channel; timer_set_mode(timer, channel, TIMER_PWM); - uint16_t preload = 255; // Lock 255 PWM resolution for high frequencies + // Preload (resolution) cannot be equal to duty of 255 otherwise it may not result in digital off or on. + uint16_t preload = 254; int32_t prescaler = (HAL_TIMER_RATE) / (preload + 1) / f_desired - 1; if (prescaler > 65535) { // For low frequencies increase prescaler prescaler = 65535; diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 24e241ee3d52c..f9ab6d13d3741 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -188,7 +188,7 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(TIMER_NUM) +#define HAL_timer_isr_epilogue(T) // No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple. // Needed here to reset ARPE=0 for stepper timer diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 08f82f0b7dced..3b073d63ab293 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -110,4 +110,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(TIMER_NUM) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 4f65bdffd176b..6c342bbe0d252 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -109,4 +109,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(TIMER_NUM) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index afb373c599c3e..81cf67f7bc08a 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -114,4 +114,4 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); //void HAL_timer_isr_epilogue(const uint8_t timer_num) {} -#define HAL_timer_isr_epilogue(TIMER_NUM) +#define HAL_timer_isr_epilogue(T) From e949b4439becc0e440c64bbcba1825654dd9efce Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sat, 4 Dec 2021 09:48:54 +1300 Subject: [PATCH 108/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20TIMER=5FTONE=20for?= =?UTF-8?q?=20ZM3E4=20(#23212)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f1.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index da7cedd3a3db7..0e57848b10a6e 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -410,12 +410,12 @@ platform = ${ZONESTAR_ZM3E.platform} extends = ZONESTAR_ZM3E board = genericSTM32F103VC board_build.variant = MARLIN_F103Vx -build_flags = ${ZONESTAR_ZM3E.build_flags} -DTIMER_TONE=1 +build_flags = ${ZONESTAR_ZM3E.build_flags} -DTIMER_TONE=TIM1 [env:STM32F103VE_ZM3E4V2_USB] platform = ${ZONESTAR_ZM3E.platform} extends = ZONESTAR_ZM3E board = genericSTM32F103VE board_build.variant = MARLIN_F103Vx -build_flags = ${ZONESTAR_ZM3E.build_flags} -DTIMER_TONE=1 +build_flags = ${ZONESTAR_ZM3E.build_flags} -DTIMER_TONE=TIM1 board_upload.maximum_size = 499712 From 36a04190a01a83b2bf9a9fd810b082649aa53aa9 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 4 Dec 2021 01:02:04 +0000 Subject: [PATCH 109/273] [cron] Bump distribution date (2021-12-04) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 456a5c33bce90..689d35f4817a2 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 "2021-12-03" +//#define STRING_DISTRIBUTION_DATE "2021-12-04" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 42c737ca3cfd1..656c68abf9b74 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 "2021-12-03" + #define STRING_DISTRIBUTION_DATE "2021-12-04" #endif /** From bfead67544106ec2b3f2ba228a44319ad8510a52 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sun, 5 Dec 2021 11:10:29 +1300 Subject: [PATCH 110/273] =?UTF-8?q?=E2=9C=A8=20BigTree=20SKR=202=20with=20?= =?UTF-8?q?F429=20(#23177)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 2 +- Marlin/src/pins/pins.h | 2 +- .../boards/marlin_STM32F429VGT6.json | 50 +++++++++++++++++++ ini/stm32f4.ini | 33 ++++++++++++ 4 files changed, 85 insertions(+), 2 deletions(-) create mode 100644 buildroot/share/PlatformIO/boards/marlin_STM32F429VGT6.json diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index ebb130698c5b0..9483d6322aeea 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -382,7 +382,7 @@ #define BOARD_BTT_BTT002_V1_0 4210 // BigTreeTech BTT002 v1.0 (STM32F407VGT6) #define BOARD_BTT_E3_RRF 4211 // BigTreeTech E3 RRF (STM32F407VGT6) #define BOARD_BTT_SKR_V2_0_REV_A 4212 // BigTreeTech SKR v2.0 Rev A (STM32F407VGT6) -#define BOARD_BTT_SKR_V2_0_REV_B 4213 // BigTreeTech SKR v2.0 Rev B (STM32F407VGT6) +#define BOARD_BTT_SKR_V2_0_REV_B 4213 // BigTreeTech SKR v2.0 Rev B (STM32F407VGT6/STM32F429VGT6) #define BOARD_BTT_GTR_V1_0 4214 // BigTreeTech GTR v1.0 (STM32F407IGT) #define BOARD_BTT_OCTOPUS_V1_0 4215 // BigTreeTech Octopus v1.0 (STM32F446ZET6) #define BOARD_BTT_OCTOPUS_V1_1 4216 // BigTreeTech Octopus v1.1 (STM32F446ZET6) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 3843441712b49..59e06333078ec 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -622,7 +622,7 @@ #elif MB(BTT_SKR_V2_0_REV_A) #include "stm32f4/pins_BTT_SKR_V2_0_REV_A.h" // STM32F4 env:BIGTREE_SKR_2 env:BIGTREE_SKR_2_USB env:BIGTREE_SKR_2_USB_debug #elif MB(BTT_SKR_V2_0_REV_B) - #include "stm32f4/pins_BTT_SKR_V2_0_REV_B.h" // STM32F4 env:BIGTREE_SKR_2 env:BIGTREE_SKR_2_USB env:BIGTREE_SKR_2_USB_debug + #include "stm32f4/pins_BTT_SKR_V2_0_REV_B.h" // STM32F4 env:BIGTREE_SKR_2 env:BIGTREE_SKR_2_USB env:BIGTREE_SKR_2_USB_debug env:BIGTREE_SKR_2_F429 env:BIGTREE_SKR_2_F429_USB env:BIGTREE_SKR_2_F429_USB_debug #elif MB(BTT_OCTOPUS_V1_0) #include "stm32f4/pins_BTT_OCTOPUS_V1_0.h" // STM32F4 env:BIGTREE_OCTOPUS_V1 env:BIGTREE_OCTOPUS_V1_USB #elif MB(BTT_OCTOPUS_V1_1) diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32F429VGT6.json b/buildroot/share/PlatformIO/boards/marlin_STM32F429VGT6.json new file mode 100644 index 0000000000000..3ad2d9d99fcbd --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_STM32F429VGT6.json @@ -0,0 +1,50 @@ +{ + "build": { + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F4 -DSTM32F429xx", + "f_cpu": "168000000L", + "mcu": "stm32f429vgt6", + "product_line": "STM32F429xx", + "variant": "MARLIN_F4x7Vx" + }, + "connectivity": [ + "can" + ], + "debug": { + "default_tools": [ + "stlink" + ], + "jlink_device": "STM32F429VG", + "onboard_tools": [ + "stlink" + ], + "openocd_board": "stm32f429", + "openocd_target": "stm32f4x", + "svd_path": "STM32F429x.svd" + }, + "frameworks": [ + "arduino", + "cmsis", + "mbed", + "stm32cube", + "libopencm3", + "zephyr" + ], + "name": "STM32F429VG (128k RAM, 64k CCM RAM, 1024k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 131072, + "maximum_size": 1048576, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f429-439.html", + "vendor": "ST" +} diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 6fec1d46fce7d..d7c80cf0e9107 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -245,6 +245,39 @@ extends = env:BIGTREE_SKR_2_USB build_flags = ${env:BIGTREE_SKR_2_USB.build_flags} -O0 build_unflags = ${env:BIGTREE_SKR_2_USB.build_unflags} -Os -NDEBUG +# +# Bigtreetech SKR V2.0 F429 (STM32F429VGT6 ARM Cortex-M4) with USB Flash Drive Support +# +[env:BIGTREE_SKR_2_F429] +platform = ${common_stm32.platform} +extends = stm32_variant +platform_packages = ${stm_flash_drive.platform_packages} +board = marlin_STM32F429VGT6 +board_build.variant = MARLIN_F4x7Vx +board_build.offset = 0x8000 +board_upload.offset_address = 0x08008000 +build_flags = ${stm_flash_drive.build_flags} + -DUSE_USBHOST_HS -DUSE_USB_HS_IN_FS + -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 + -DHSE_VALUE=8000000U -DHAL_SD_MODULE_ENABLED + -DPIN_SERIAL3_RX=PD_9 -DPIN_SERIAL3_TX=PD_8 +upload_protocol = stlink + +# +# BigTreeTech SKR V2.0 F429 (STM32F429VGT6 ARM Cortex-M4) with USB Media Share Support +# +[env:BIGTREE_SKR_2_F429_USB] +platform = ${common_stm32.platform} +extends = env:BIGTREE_SKR_2_F429 +build_flags = ${env:BIGTREE_SKR_2_F429.build_flags} -DUSBD_USE_CDC_MSC +build_unflags = ${env:BIGTREE_SKR_2_F429.build_unflags} -DUSBD_USE_CDC + +[env:BIGTREE_SKR_2_F429_USB_debug] +platform = ${common_stm32.platform} +extends = env:BIGTREE_SKR_2_F429_USB +build_flags = ${env:BIGTREE_SKR_2_F429_USB.build_flags} -O0 +build_unflags = ${env:BIGTREE_SKR_2_F429_USB.build_unflags} -Os -NDEBUG + # # BigTreeTech Octopus V1.0/1.1 / Octopus Pro V1.0 (STM32F446ZET6 ARM Cortex-M4) # From 7daa76382f858817ea7b52d11f9fae88d252988d Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Sun, 5 Dec 2021 05:14:19 +0700 Subject: [PATCH 111/273] =?UTF-8?q?=F0=9F=9A=B8=20Park=20nozzle=20on=20"lo?= =?UTF-8?q?ud=20kill"=20(#23172)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/temperature.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 758275d21e315..9d6c8ae061bb5 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -67,6 +67,10 @@ #include "../gcode/gcode.h" #endif +#if ENABLED(NOZZLE_PARK_FEATURE) + #include "../libs/nozzle.h" +#endif + // MAX TC related macros #define TEMP_SENSOR_IS_MAX(n, M) (ENABLED(TEMP_SENSOR_##n##_IS_MAX##M) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX##M) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) #define TEMP_SENSOR_IS_ANY_MAX_TC(n) (ENABLED(TEMP_SENSOR_##n##_IS_MAX_TC) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) @@ -991,6 +995,12 @@ inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) { } WRITE(BEEPER_PIN, HIGH); #endif + #if ENABLED(NOZZLE_PARK_FEATURE) + if (!homing_needed_error()) { + nozzle.park(0); + planner.synchronize(); + } + #endif kill(lcd_msg, HEATER_FSTR(heater_id)); } From e6bbdd89b44a6d83df8788debf25880fadfab87a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 4 Dec 2021 17:17:10 -0600 Subject: [PATCH 112/273] =?UTF-8?q?=F0=9F=94=A7=20Cutter=20pins=20for=20SK?= =?UTF-8?q?R=202.0?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 83 +++++++++++++------ 1 file changed, 57 insertions(+), 26 deletions(-) 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 a2111d849ed37..bf3409210e0f2 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 @@ -190,16 +190,28 @@ #define Z_CS_PIN PD0 #endif -#define E0_STEP_PIN PD15 -#define E0_DIR_PIN PD14 -#define E0_ENABLE_PIN PC7 +#ifndef E0_STEP_PIN + #define E0_STEP_PIN PD15 +#endif +#ifndef E0_DIR_PIN + #define E0_DIR_PIN PD14 +#endif +#ifndef E0_ENABLE_PIN + #define E0_ENABLE_PIN PC7 +#endif #ifndef E0_CS_PIN #define E0_CS_PIN PC6 #endif -#define E1_STEP_PIN PD11 -#define E1_DIR_PIN PD10 -#define E1_ENABLE_PIN PD13 +#ifndef E1_STEP_PIN + #define E1_STEP_PIN PD11 +#endif +#ifndef E1_DIR_PIN + #define E1_DIR_PIN PD10 +#endif +#ifndef E1_ENABLE_PIN + #define E1_ENABLE_PIN PD13 +#endif #ifndef E1_CS_PIN #define E1_CS_PIN PD12 #endif @@ -207,9 +219,15 @@ // // Temperature Sensors // -#define TEMP_BED_PIN PA1 // TB -#define TEMP_0_PIN PA2 // TH0 -#define TEMP_1_PIN PA3 // TH1 +#ifndef TEMP_0_PIN + #define TEMP_0_PIN PA2 // TH0 +#endif +#ifndef TEMP_1_PIN + #define TEMP_1_PIN PA3 // TH1 +#endif +#ifndef TEMP_BED_PIN + #define TEMP_BED_PIN PA1 // TB +#endif #if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #if TEMP_SENSOR_PROBE @@ -234,12 +252,22 @@ #ifndef FAN_PIN #define FAN_PIN PB7 // Fan0 #endif -#ifndef FAN1_PIN - #define FAN1_PIN PB6 // Fan1 -#endif -#ifndef FAN2_PIN - #define FAN2_PIN PB5 // Fan2 -#endif + +#if EITHER(SPINDLE_FEATURE, LASER_FEATURE) + #ifndef SPINDLE_LASER_PWM_PIN + #define SPINDLE_LASER_PWM_PIN PB5 + #endif + #ifndef SPINDLE_LASER_ENA_PIN + #define SPINDLE_LASER_ENA_PIN PB6 + #endif +#else + #ifndef FAN1_PIN + #define FAN1_PIN PB6 // Fan1 + #endif + #ifndef FAN2_PIN + #define FAN2_PIN PB5 // Fan2 + #endif +#endif // SPINDLE_FEATURE || LASER_FEATURE // // Software SPI pins for TMC2130 stepper drivers @@ -275,6 +303,9 @@ //#define E3_HARDWARE_SERIAL Serial1 //#define E4_HARDWARE_SERIAL Serial1 + // + // Software serial + // #define X_SERIAL_TX_PIN PE0 #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN @@ -333,7 +364,16 @@ // Onboard SD card // Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 // -#if SD_CONNECTION_IS(ONBOARD) +#if SD_CONNECTION_IS(LCD) + + #define SDSS PA4 + #define SD_SS_PIN SDSS + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PC4 + +#elif SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD #define SDIO_D0_PIN PC8 @@ -343,17 +383,8 @@ #define SDIO_CK_PIN PC12 #define SDIO_CMD_PIN PD2 -#elif SD_CONNECTION_IS(LCD) - - #define SDSS PA4 - #define SD_SS_PIN SDSS - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PC4 - #elif SD_CONNECTION_IS(CUSTOM_CABLE) - #error "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" + #error "No custom SD drive cable defined for this board." #endif #if ENABLED(BTT_MOTOR_EXPANSION) From 363a17ac464e72bb013150e742b0e95f9df707eb Mon Sep 17 00:00:00 2001 From: Stuart Pittaway <1201909+stuartpittaway@users.noreply.github.com> Date: Sat, 4 Dec 2021 23:44:10 +0000 Subject: [PATCH 113/273] =?UTF-8?q?=E2=9C=A8=20M3426=20to=20read=20i2c=20M?= =?UTF-8?q?CP3426=20ADC=20(#23184)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/adc/adc_mcp3426.cpp | 104 +++++++++++++++++++++ Marlin/src/feature/adc/adc_mcp3426.h | 41 ++++++++ Marlin/src/feature/twibus.cpp | 15 ++- Marlin/src/gcode/feature/adc/M3426.cpp | 63 +++++++++++++ Marlin/src/gcode/gcode.cpp | 4 + Marlin/src/gcode/gcode.h | 5 + Marlin/src/pins/stm32f4/pins_INDEX_REV03.h | 5 + ini/features.ini | 1 + platformio.ini | 1 + 9 files changed, 234 insertions(+), 5 deletions(-) create mode 100644 Marlin/src/feature/adc/adc_mcp3426.cpp create mode 100644 Marlin/src/feature/adc/adc_mcp3426.h create mode 100644 Marlin/src/gcode/feature/adc/M3426.cpp diff --git a/Marlin/src/feature/adc/adc_mcp3426.cpp b/Marlin/src/feature/adc/adc_mcp3426.cpp new file mode 100644 index 0000000000000..aaddf46821b0c --- /dev/null +++ b/Marlin/src/feature/adc/adc_mcp3426.cpp @@ -0,0 +1,104 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * adc_mcp3426.cpp - library for MicroChip MCP3426 I2C A/D converter + * + * For implementation details, please take a look at the datasheet: + * https://www.microchip.com/en-us/product/MCP3426 + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(HAS_MCP3426_ADC) + +#include "adc_mcp3426.h" + +// Read the ADC value from MCP342X on a specific channel +int16_t MCP3426::ReadValue(uint8_t channel, uint8_t gain) { + Error = false; + + #if PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM) + Wire.setSDA(pin_t(I2C_SDA_PIN)); + Wire.setSCL(pin_t(I2C_SCL_PIN)); + #endif + + Wire.begin(); // No address joins the BUS as the master + + Wire.beginTransmission(I2C_ADDRESS(MCP342X_ADC_I2C_ADDRESS)); + + // Continuous Conversion Mode, 16 bit, Channel 1, Gain x4 + // 26 = 0b00011000 + // RXXCSSGG + // R = Ready Bit + // XX = Channel (00=1, 01=2, 10=3 (MCP3428), 11=4 (MCP3428)) + // C = Conversion Mode Bit (1= Continuous Conversion Mode (Default)) + // SS = Sample rate, 10=15 samples per second @ 16 bits + // GG = Gain 00 =x1 + uint8_t controlRegister = 0b00011000; + + if (channel == 2) controlRegister |= 0b00100000; // Select channel 2 + + if (gain == 2) + controlRegister |= 0b00000001; + else if (gain == 4) + controlRegister |= 0b00000010; + else if (gain == 8) + controlRegister |= 0b00000011; + + Wire.write(controlRegister); + if (Wire.endTransmission() != 0) { + Error = true; + return 0; + } + + const uint8_t len = 3; + uint8_t buffer[len] = {}; + + do { + Wire.requestFrom(I2C_ADDRESS(MCP342X_ADC_I2C_ADDRESS), len); + if (Wire.available() != len) { + Error = true; + return 0; + } + + for (uint8_t i = 0; i < len; ++i) + buffer[i] = Wire.read(); + + // Is conversion ready, if not loop around again + } while ((buffer[2] & 0x80) != 0); + + union TwoBytesToInt16 { + uint8_t bytes[2]; + int16_t integervalue; + }; + TwoBytesToInt16 ConversionUnion; + + ConversionUnion.bytes[1] = buffer[0]; + ConversionUnion.bytes[0] = buffer[1]; + + return ConversionUnion.integervalue; +} + +MCP3426 mcp3426; + +#endif // HAS_MCP3426_ADC diff --git a/Marlin/src/feature/adc/adc_mcp3426.h b/Marlin/src/feature/adc/adc_mcp3426.h new file mode 100644 index 0000000000000..35458716b9751 --- /dev/null +++ b/Marlin/src/feature/adc/adc_mcp3426.h @@ -0,0 +1,41 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Arduino library for MicroChip MCP3426 I2C A/D converter. + * https://www.microchip.com/en-us/product/MCP3426 + */ + +#include +#include + +// Address of MCP342X chip +#define MCP342X_ADC_I2C_ADDRESS 104 + +class MCP3426 { + public: + int16_t ReadValue(uint8_t channel, uint8_t gain); + bool Error; +}; + +extern MCP3426 mcp3426; diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index e33581676c4a3..bbe4c0966a6d8 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -34,13 +34,18 @@ TWIBus i2c; TWIBus::TWIBus() { #if I2C_SLAVE_ADDRESS == 0 - Wire.begin( // No address joins the BUS as the master - #if PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM) - pin_t(I2C_SDA_PIN), pin_t(I2C_SCL_PIN) - #endif - ); + + #if PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM) + Wire.setSDA(pin_t(I2C_SDA_PIN)); + Wire.setSCL(pin_t(I2C_SCL_PIN)); + #endif + + Wire.begin(); // No address joins the BUS as the master + #else + Wire.begin(I2C_SLAVE_ADDRESS); // Join the bus as a slave + #endif reset(); } diff --git a/Marlin/src/gcode/feature/adc/M3426.cpp b/Marlin/src/gcode/feature/adc/M3426.cpp new file mode 100644 index 0000000000000..8205fa01f2bd1 --- /dev/null +++ b/Marlin/src/gcode/feature/adc/M3426.cpp @@ -0,0 +1,63 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(HAS_MCP3426_ADC) + +#include "../../gcode.h" + +#include "../../../feature/adc/adc_mcp3426.h" + +/** + * M3426: Read 16 bit (signed) value from I2C MCP3426 ADC device + * + * M3426 C channel 1 or 2 + * M3426 G gain 1, 2, 4 or 8 + * M3426 I 0 or 1, invert reply + */ +void GcodeSuite::M3426() { + uint8_t channel = parser.byteval('C', 1), // Select the channel 1 or 2 + gain = parser.byteval('G', 1); + const bool inverted = parser.byteval('I') == 1; + + if (channel <= 2 && (gain == 1 || gain == 2 || gain == 4 || gain == 8)) { + int16_t result = mcp3426.ReadValue(channel, gain); + + if (mcp3426.Error == false) { + if (inverted) { + // Should we invert the reading (32767 - ADC value) ? + // Caters to end devices that expect values to increase when in reality they decrease. + // e.g., A pressure sensor in a vacuum when the end device expects a positive pressure. + result = INT16_MAX - result; + } + //SERIAL_ECHOPGM(STR_OK); + SERIAL_ECHOLNPGM("V:", result, " C:", channel, " G:", gain, " I:", inverted ? 1 : 0); + } + else + SERIAL_ERROR_MSG("MCP342X i2c error"); + } + else + SERIAL_ERROR_MSG("MCP342X Bad request"); +} + +#endif // HAS_MCP3426_ADC diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 24eb9914d1f47..c05ac5494d5a2 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -1054,6 +1054,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 7219: M7219(); break; // M7219: Set LEDs, columns, and rows #endif + #if ENABLED(HAS_MCP3426_ADC) + case 3426: M3426(); break; // M3426: Read MCP3426 ADC (over i2c) + #endif + default: parser.unknown_command_warning(); break; } break; diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 6bfaf00c13921..bbfb31a3fece4 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -297,6 +297,7 @@ * M917 - L6470 tuning: Find minimum current thresholds. (Requires at least one _DRIVER_TYPE L6470) * M918 - L6470 tuning: Increase speed until max or error. (Requires at least one _DRIVER_TYPE L6470) * M951 - Set Magnetic Parking Extruder parameters. (Requires MAGNETIC_PARKING_EXTRUDER) + * M3426 - Read MCP3426 ADC over I2C. (Requires HAS_MCP3426_ADC) * M7219 - Control Max7219 Matrix LEDs. (Requires MAX7219_GCODE) * *** SCARA *** @@ -1204,6 +1205,10 @@ class GcodeSuite { static void M1004(); #endif + #if ENABLED(HAS_MCP3426_ADC) + static void M3426(); + #endif + #if ENABLED(MAX7219_GCODE) static void M7219(); #endif diff --git a/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h b/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h index 8761ca955a8f2..8560a04375c00 100644 --- a/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h +++ b/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h @@ -42,6 +42,9 @@ #define SRAM_EEPROM_EMULATION #define MARLIN_EEPROM_SIZE 0x2000 // 8KB +// I2C MCP3426 (16-Bit, 240SPS, dual-channel ADC) +#define HAS_MCP3426_ADC + // // Servos // @@ -116,6 +119,8 @@ #define FAN2_PIN PE4 #define FAN3_PIN PE5 +#define FAN_SOFT_PWM + // Neopixel Rings #define NEOPIXEL_PIN PC7 #define NEOPIXEL2_PIN PC8 diff --git a/ini/features.ini b/ini/features.ini index 91baa601cab11..b56565b154ab9 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -94,6 +94,7 @@ NEXTION_TFT = src_filter=+ USE_UHS2_USB = src_filter=+ USE_UHS3_USB = src_filter=+ USB_FLASH_DRIVE_SUPPORT = src_filter=+ +HAS_MCP3426_ADC = src_filter=+ + AUTO_BED_LEVELING_BILINEAR = src_filter=+ AUTO_BED_LEVELING_(3POINT|(BI)?LINEAR) = src_filter=+ MESH_BED_LEVELING = src_filter=+ + diff --git a/platformio.ini b/platformio.ini index 07821fca96b67..1b4effcf25624 100644 --- a/platformio.ini +++ b/platformio.ini @@ -92,6 +92,7 @@ default_src_filter = + - - + - - - + - - - - - - From d6b332f4c7a79553a41c4a6166f21f802be930c8 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 5 Dec 2021 01:07:50 +0000 Subject: [PATCH 114/273] [cron] Bump distribution date (2021-12-05) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 689d35f4817a2..aca4b1d333ec2 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 "2021-12-04" +//#define STRING_DISTRIBUTION_DATE "2021-12-05" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 656c68abf9b74..a60bc91011b49 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 "2021-12-04" + #define STRING_DISTRIBUTION_DATE "2021-12-05" #endif /** From 97400e54b90a4fe40b60ea2f76e90cb14b0bf6ea Mon Sep 17 00:00:00 2001 From: ladismrkolj Date: Sun, 5 Dec 2021 22:41:39 +0100 Subject: [PATCH 115/273] =?UTF-8?q?=F0=9F=94=A7=20Chamber=20Fan=20index=20?= =?UTF-8?q?option=20(#23262)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 3 ++- Marlin/src/inc/SanityCheck.h | 4 ++-- Marlin/src/inc/Warnings.cpp | 4 ++++ Marlin/src/module/temperature.cpp | 4 +++- 4 files changed, 11 insertions(+), 4 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index d4fcd510037a6..5f02d25cc4803 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -186,7 +186,8 @@ //#define CHAMBER_FAN // Enable a fan on the chamber #if ENABLED(CHAMBER_FAN) - #define CHAMBER_FAN_MODE 2 // Fan control mode: 0=Static; 1=Linear increase when temp is higher than target; 2=V-shaped curve; 3=similar to 1 but fan is always on. + //#define CHAMBER_FAN_INDEX 2 // Index of a fan to repurpose as the chamber fan. (Default: first unused fan) + #define CHAMBER_FAN_MODE 2 // Fan control mode: 0=Static; 1=Linear increase when temp is higher than target; 2=V-shaped curve; 3=similar to 1 but fan is always on. #if CHAMBER_FAN_MODE == 0 #define CHAMBER_FAN_BASE 255 // Chamber fan PWM (0-255) #elif CHAMBER_FAN_MODE == 1 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 39a154cb53251..1442b9219fb22 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2270,8 +2270,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "LASER_COOLANT_FLOW_METER requires FLOWMETER_PIN and LASER_FEATURE." #endif -#if ENABLED(CHAMBER_FAN) && !(defined(CHAMBER_FAN_MODE) && WITHIN(CHAMBER_FAN_MODE, 0, 2)) - #error "CHAMBER_FAN_MODE must be between 0 and 2." +#if ENABLED(CHAMBER_FAN) && !(defined(CHAMBER_FAN_MODE) && WITHIN(CHAMBER_FAN_MODE, 0, 3)) + #error "CHAMBER_FAN_MODE must be between 0 and 3." #endif #if ENABLED(CHAMBER_VENT) diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index 1976c0958160f..b7eef9c49f530 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -524,6 +524,10 @@ #endif #endif +#if ENABLED(CHAMBER_FAN) && !defined(CHAMBER_FAN_INDEX) + #warning "Auto-assigned CHAMBER_FAN_INDEX to the first free FAN pin." +#endif + #if IS_LEGACY_TFT #warning "Don't forget to update your TFT settings in Configuration.h." #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 9d6c8ae061bb5..9d6c566ba0804 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -865,7 +865,9 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #define INIT_CHAMBER_AUTO_FAN_PIN(P) SET_OUTPUT(P) #endif - #define CHAMBER_FAN_INDEX HOTENDS + #ifndef CHAMBER_FAN_INDEX + #define CHAMBER_FAN_INDEX HOTENDS + #endif void Temperature::update_autofans() { #define _EFAN(B,A) _EFANOVERLAP(A,B) ? B : From 4d0880c74d8363948e63f22839c2a9ed5a672f7d Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Mon, 6 Dec 2021 10:42:56 +1300 Subject: [PATCH 116/273] =?UTF-8?q?=F0=9F=93=8C=20More=20Longer3D=20LKx=20?= =?UTF-8?q?Pro=20serial=20tests=20=20(#23260)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h index 75ee01946ae51..729a82b9c6339 100644 --- a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h +++ b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h @@ -32,13 +32,13 @@ #error "Longer3D LGT KIT V1.0 board only supports one hotend / E-stepper. Comment out this line to continue." #endif -#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 +#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 || SERIAL_PORT_3 == 1 #warning "Serial 1 is originally reserved to DGUS LCD." #endif -#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 +#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 || SERIAL_PORT_3 == 2 || LCD_SERIAL_PORT == 2 #warning "Serial 2 has no connector. Hardware changes may be required to use it." #endif -#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 +#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 || SERIAL_PORT_3 == 3 || LCD_SERIAL_PORT == 3 #define CHANGE_Y_LIMIT_PINS #warning "Serial 3 is originally reserved to Y limit switches. Hardware changes are required to use it." #endif From fcb48598e2e2dfebb92acdc103f7119c7f9fcaa3 Mon Sep 17 00:00:00 2001 From: tommywienert <53783769+tommywienert@users.noreply.github.com> Date: Sun, 5 Dec 2021 23:16:23 +0100 Subject: [PATCH 117/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20env:chitu=5Ff103?= =?UTF-8?q?=20(#23225)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f1.ini | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 0e57848b10a6e..a2cd1b0f58674 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -365,8 +365,9 @@ platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103ZE board_build.variant = MARLIN_F103Zx +board_build.offset = 0x8800 build_flags = ${stm32_variant.build_flags} - -DSTM32F1xx -DSTM32_XL_DENSITY + -DSTM32F1xx build_unflags = ${stm32_variant.build_unflags} extra_scripts = ${stm32_variant.extra_scripts} buildroot/share/PlatformIO/scripts/chitu_crypt.py From a010c4d1c8a9c6fdf296a33233deb99e235e188a Mon Sep 17 00:00:00 2001 From: Chris Pepper Date: Sun, 5 Dec 2021 22:18:02 +0000 Subject: [PATCH 118/273] =?UTF-8?q?=F0=9F=90=9B=20HAL=5Freboot=20for=20nat?= =?UTF-8?q?ive=20HAL=20(#23246)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/NATIVE_SIM/HAL.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 915339468b2cd..436b4b4daa265 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -140,6 +140,8 @@ inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, inline void HAL_clear_reset_source(void) {} inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } +void HAL_reboot(); + /* ---------------- Delay in cycles */ #define DELAY_CYCLES(x) Kernel::delayCycles(x) From ecd1ac70929b4b6b2bc0e4f9ea4e7c4b050e2396 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 6 Dec 2021 01:04:44 +0000 Subject: [PATCH 119/273] [cron] Bump distribution date (2021-12-06) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index aca4b1d333ec2..be5594a14881b 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 "2021-12-05" +//#define STRING_DISTRIBUTION_DATE "2021-12-06" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a60bc91011b49..134cacc336750 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 "2021-12-05" + #define STRING_DISTRIBUTION_DATE "2021-12-06" #endif /** From 6580e655fb255125d63e41e05045075452f5bef9 Mon Sep 17 00:00:00 2001 From: Stuart Pittaway <1201909+stuartpittaway@users.noreply.github.com> Date: Mon, 6 Dec 2021 21:40:18 +0000 Subject: [PATCH 120/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20TWIBus=20Wire.begi?= =?UTF-8?q?n=20call=20(#23183)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/twibus.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index bbe4c0966a6d8..9aec6b030537f 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -40,11 +40,11 @@ TWIBus::TWIBus() { Wire.setSCL(pin_t(I2C_SCL_PIN)); #endif - Wire.begin(); // No address joins the BUS as the master + Wire.begin(); // No address joins the BUS as the master #else - Wire.begin(I2C_SLAVE_ADDRESS); // Join the bus as a slave + Wire.begin(I2C_SLAVE_ADDRESS); // Join the bus as a slave #endif reset(); @@ -56,9 +56,8 @@ void TWIBus::reset() { } void TWIBus::address(const uint8_t adr) { - if (!WITHIN(adr, 8, 127)) { + if (!WITHIN(adr, 8, 127)) SERIAL_ECHO_MSG("Bad I2C address (8-127)"); - } addr = adr; From ea0d0e8e8b4552aff660be36a9b70c2c8960cdc3 Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Mon, 6 Dec 2021 15:52:18 -0600 Subject: [PATCH 121/273] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20non-PWM=20cutter?= =?UTF-8?q?=20compile=20(#23169)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/spindle_laser.h | 12 +++------ Marlin/src/feature/spindle_laser_types.h | 24 +++++++++++++++++- Marlin/src/gcode/control/M3-M5.cpp | 32 +++++++++++++----------- buildroot/tests/mega1280 | 6 +++++ 4 files changed, 50 insertions(+), 24 deletions(-) diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index ba82c4d7319a2..95d60ae486748 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -41,18 +41,10 @@ #define PCT_TO_PWM(X) ((X) * 255 / 100) #define PCT_TO_SERVO(X) ((X) * 180 / 100) -#ifndef SPEED_POWER_INTERCEPT - #define SPEED_POWER_INTERCEPT 0 -#endif - // #define _MAP(N,S1,S2,D1,D2) ((N)*_MAX((D2)-(D1),0)/_MAX((S2)-(S1),1)+(D1)) class SpindleLaser { public: - static constexpr float - min_pct = TERN(CUTTER_POWER_RELATIVE, 0, TERN(SPINDLE_FEATURE, round(100.0f * (SPEED_POWER_MIN) / (SPEED_POWER_MAX)), SPEED_POWER_MIN)), - max_pct = TERN(SPINDLE_FEATURE, 100, SPEED_POWER_MAX); - static const inline uint8_t pct_to_ocr(const_float_t pct) { return uint8_t(PCT_TO_PWM(pct)); } // cpower = configured values (e.g., SPEED_POWER_MAX) @@ -158,6 +150,9 @@ class SpindleLaser { } static inline cutter_power_t power_to_range(const cutter_power_t pwr, const uint8_t pwrUnit) { + static constexpr float + min_pct = TERN(CUTTER_POWER_RELATIVE, 0, TERN(SPINDLE_FEATURE, round(100.0f * (SPEED_POWER_MIN) / (SPEED_POWER_MAX)), SPEED_POWER_MIN)), + max_pct = TERN(SPINDLE_FEATURE, 100, SPEED_POWER_MAX); if (pwr <= 0) return 0; cutter_power_t upwr; switch (pwrUnit) { @@ -186,6 +181,7 @@ class SpindleLaser { } return upwr; } + #endif // SPINDLE_LASER_USE_PWM /** diff --git a/Marlin/src/feature/spindle_laser_types.h b/Marlin/src/feature/spindle_laser_types.h index 0075e54819003..d249a20e7531c 100644 --- a/Marlin/src/feature/spindle_laser_types.h +++ b/Marlin/src/feature/spindle_laser_types.h @@ -28,12 +28,34 @@ #include "../inc/MarlinConfigPre.h" +#define MSG_CUTTER(M) _MSG_CUTTER(M) + +#ifndef SPEED_POWER_INTERCEPT + #define SPEED_POWER_INTERCEPT 0 +#endif #if ENABLED(SPINDLE_FEATURE) #define _MSG_CUTTER(M) MSG_SPINDLE_##M + #ifndef SPEED_POWER_MIN + #define SPEED_POWER_MIN 5000 + #endif + #ifndef SPEED_POWER_MAX + #define SPEED_POWER_MAX 30000 + #endif + #ifndef SPEED_POWER_STARTUP + #define SPEED_POWER_STARTUP 25000 + #endif #else #define _MSG_CUTTER(M) MSG_LASER_##M + #ifndef SPEED_POWER_MIN + #define SPEED_POWER_MIN 0 + #endif + #ifndef SPEED_POWER_MAX + #define SPEED_POWER_MAX 255 + #endif + #ifndef SPEED_POWER_STARTUP + #define SPEED_POWER_STARTUP 255 + #endif #endif -#define MSG_CUTTER(M) _MSG_CUTTER(M) typedef IF<(SPEED_POWER_MAX > 255), uint16_t, uint8_t>::type cutter_cpower_t; diff --git a/Marlin/src/gcode/control/M3-M5.cpp b/Marlin/src/gcode/control/M3-M5.cpp index ecae8b06c69fe..ddbbc4ab68351 100644 --- a/Marlin/src/gcode/control/M3-M5.cpp +++ b/Marlin/src/gcode/control/M3-M5.cpp @@ -66,21 +66,23 @@ * PWM duty cycle goes from 0 (off) to 255 (always on). */ void GcodeSuite::M3_M4(const bool is_M4) { - auto get_s_power = [] { - if (parser.seenval('S')) { - const float spwr = parser.value_float(); - #if ENABLED(SPINDLE_SERVO) - cutter.unitPower = spwr; - #else - cutter.unitPower = TERN(SPINDLE_LASER_USE_PWM, - cutter.power_to_range(cutter_power_t(round(spwr))), - spwr > 0 ? 255 : 0); - #endif - } - else - cutter.unitPower = cutter.cpwr_to_upwr(SPEED_POWER_STARTUP); - return cutter.unitPower; - }; + #if EITHER(SPINDLE_LASER_USE_PWM, SPINDLE_SERVO) + auto get_s_power = [] { + if (parser.seenval('S')) { + const float spwr = parser.value_float(); + #if ENABLED(SPINDLE_SERVO) + cutter.unitPower = spwr; + #else + cutter.unitPower = TERN(SPINDLE_LASER_USE_PWM, + cutter.power_to_range(cutter_power_t(round(spwr))), + spwr > 0 ? 255 : 0); + #endif + } + else + cutter.unitPower = cutter.cpwr_to_upwr(SPEED_POWER_STARTUP); + return cutter.unitPower; + }; + #endif #if ENABLED(LASER_POWER_INLINE) if (parser.seen('I') == DISABLED(LASER_POWER_INLINE_INVERT)) { diff --git a/buildroot/tests/mega1280 b/buildroot/tests/mega1280 index cae747017f1c7..a7f25953acd03 100755 --- a/buildroot/tests/mega1280 +++ b/buildroot/tests/mega1280 @@ -27,6 +27,12 @@ opt_enable SPINDLE_FEATURE ULTIMAKERCONTROLLER LCD_BED_LEVELING \ EXTERNAL_CLOSED_LOOP_CONTROLLER POWER_MONITOR_CURRENT POWER_MONITOR_VOLTAGE exec_test $1 $2 "Spindle, MESH_BED_LEVELING, closed loop, Power Monitor, and LCD" "$3" +# +# ...and without PWM +# +opt_disable SPINDLE_LASER_USE_PWM +exec_test $1 $2 "(No PWM)" "$3" + # # Test DUAL_X_CARRIAGE # From c67f7fb4df878e829289848ff60e28462c949aa1 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 7 Dec 2021 01:06:09 +0000 Subject: [PATCH 122/273] [cron] Bump distribution date (2021-12-07) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index be5594a14881b..dd14eeff4f747 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 "2021-12-06" +//#define STRING_DISTRIBUTION_DATE "2021-12-07" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 134cacc336750..36e2488f9e9a5 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 "2021-12-06" + #define STRING_DISTRIBUTION_DATE "2021-12-07" #endif /** From a16a059312b0ddb822da2769b5ba5372f9857c48 Mon Sep 17 00:00:00 2001 From: Giuseppe499 Date: Tue, 7 Dec 2021 02:53:51 +0100 Subject: [PATCH 123/273] =?UTF-8?q?=E2=9C=A8=20X=20Twist=20Compensation=20?= =?UTF-8?q?&=20Calibration=20(#23238)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 16 ++ Marlin/src/feature/bedlevel/abl/x_twist.cpp | 59 ++++++ Marlin/src/feature/bedlevel/abl/x_twist.h | 37 ++++ Marlin/src/feature/bedlevel/bedlevel.h | 3 + Marlin/src/gcode/bedlevel/abl/G29.cpp | 2 +- Marlin/src/inc/SanityCheck.h | 4 + Marlin/src/lcd/language/language_en.h | 4 + Marlin/src/lcd/marlinui.h | 2 +- Marlin/src/lcd/menu/menu.cpp | 12 +- Marlin/src/lcd/menu/menu.h | 13 ++ Marlin/src/lcd/menu/menu_advanced.cpp | 4 + Marlin/src/lcd/menu/menu_bed_corners.cpp | 4 - Marlin/src/lcd/menu/menu_bed_leveling.cpp | 2 - Marlin/src/lcd/menu/menu_motion.cpp | 9 + Marlin/src/lcd/menu/menu_probe_offset.cpp | 11 +- Marlin/src/lcd/menu/menu_x_twist.cpp | 224 ++++++++++++++++++++ Marlin/src/module/settings.cpp | 24 +++ buildroot/tests/rambo | 7 +- ini/features.ini | 1 + platformio.ini | 2 + 20 files changed, 417 insertions(+), 23 deletions(-) create mode 100644 Marlin/src/feature/bedlevel/abl/x_twist.cpp create mode 100644 Marlin/src/feature/bedlevel/abl/x_twist.h create mode 100644 Marlin/src/lcd/menu/menu_x_twist.cpp diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 5f02d25cc4803..4e10ce557765d 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1270,6 +1270,22 @@ // Set a convenient position to do the calibration (probing point and nozzle/bed-distance) //#define PROBE_OFFSET_WIZARD_XY_POS { X_CENTER, Y_CENTER } #endif + + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + // Add a calibration procedure in the Probe Offsets menu + // to compensate for twist in the X-axis. + //#define X_AXIS_TWIST_COMPENSATION + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + /** + * Enable to init the Probe Z-Offset when starting the Wizard. + * Use a height slightly above the estimated nozzle-to-probe Z offset. + * For example, with an offset of -5, consider a starting height of -4. + */ + #define XATC_START_Z 0.0 + #define XATC_MAX_POINTS 3 // Number of points to probe in the wizard + #define XATC_Y_POSITION Y_CENTER // (mm) Y position to probe + #endif + #endif #endif // Include a page of printer information in the LCD Main Menu diff --git a/Marlin/src/feature/bedlevel/abl/x_twist.cpp b/Marlin/src/feature/bedlevel/abl/x_twist.cpp new file mode 100644 index 0000000000000..c4a62c35953f5 --- /dev/null +++ b/Marlin/src/feature/bedlevel/abl/x_twist.cpp @@ -0,0 +1,59 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../inc/MarlinConfig.h" + +#if ENABLED(X_AXIS_TWIST_COMPENSATION) + +#include "../bedlevel.h" + +XATC xatc; + +float XATC::spacing, XATC::start; +xatc_points_t XATC::z_values; + +void XATC::print_points() { + SERIAL_ECHOLNPGM(" X-Twist Correction:"); + LOOP_L_N(x, XATC_MAX_POINTS) { + SERIAL_CHAR(' '); + if (!isnan(z_values[x])) { + if (z_values[x] >= 0) SERIAL_CHAR('+'); + SERIAL_ECHO_F(z_values[x], 3); + } + else { + LOOP_L_N(i, 6) + SERIAL_CHAR(i ? '=' : ' '); + } + } + SERIAL_EOL(); +} + +float lerp(const_float_t t, const_float_t a, const_float_t b) { return a + t * (b - a); } + +float XATC::compensation(const xy_pos_t &raw) { + float t = (raw.x - start) / spacing; + int i = FLOOR(t); + LIMIT(i, 0, XATC_MAX_POINTS - 2); + t -= i; + return lerp(t, z_values[i], z_values[i + 1]); +} + +#endif // X_AXIS_TWIST_COMPENSATION diff --git a/Marlin/src/feature/bedlevel/abl/x_twist.h b/Marlin/src/feature/bedlevel/abl/x_twist.h new file mode 100644 index 0000000000000..bbad9e73efac6 --- /dev/null +++ b/Marlin/src/feature/bedlevel/abl/x_twist.h @@ -0,0 +1,37 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "../../../inc/MarlinConfigPre.h" + +typedef float xatc_points_t[XATC_MAX_POINTS]; + +class XATC { +public: + static float spacing, start; + static xatc_points_t z_values; + + static float compensation(const xy_pos_t &raw); + static void print_points(); +}; + +extern XATC xatc; diff --git a/Marlin/src/feature/bedlevel/bedlevel.h b/Marlin/src/feature/bedlevel/bedlevel.h index 63f032eee87bc..c623c99b5c521 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.h +++ b/Marlin/src/feature/bedlevel/bedlevel.h @@ -63,6 +63,9 @@ class TemporaryBedLevelingState { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) #include "abl/abl.h" + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + #include "abl/x_twist.h" + #endif #elif ENABLED(AUTO_BED_LEVELING_UBL) #include "ubl/ubl.h" #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 14da38c8fe2bb..6765ec86a6ec7 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -662,7 +662,7 @@ G29_TYPE GcodeSuite::G29() { #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) const float z = abl.measured_z + abl.Z_offset; - z_values[abl.meshCount.x][abl.meshCount.y] = z; + z_values[abl.meshCount.x][abl.meshCount.y] = z PLUS_TERN0(X_AXIS_TWIST_COMPENSATION, xatc.compensation(abl.probePos)); TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(abl.meshCount, z)); #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 1442b9219fb22..a809fad132b30 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3391,6 +3391,10 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #endif #endif +#if BOTH(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." diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 907faa143620e..9f60632152675 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -734,6 +734,10 @@ namespace Language_en { LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Probing Z Reference"); LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Moving to Probing Pos"); + LSTR MSG_XATC = _UxGT("X-Twist Wizard"); + LSTR MSG_XATC_DONE = _UxGT("X-Twist Wizard Done!"); + LSTR MSG_XATC_UPDATE_Z_OFFSET = _UxGT("Update Probe Z-Offset to "); + LSTR MSG_SOUND = _UxGT("Sound"); LSTR MSG_TOP_LEFT = _UxGT("Top Left"); diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index ed5b539eaf8f6..7014040097c44 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -640,7 +640,7 @@ class MarlinUI { // // Special handling if a move is underway // - #if ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION, PROBE_OFFSET_WIZARD) || (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) && EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)) #define LCD_HAS_WAIT_FOR_MOVE 1 static bool wait_for_move; #else diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index a24ad883f7884..c566e9b2a63df 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -38,7 +38,7 @@ #include "../../module/probe.h" #endif -#if EITHER(ENABLE_LEVELING_FADE_HEIGHT, AUTO_BED_LEVELING_UBL) +#if HAS_LEVELING #include "../../feature/bedlevel/bedlevel.h" #endif @@ -46,6 +46,13 @@ ///////////// Global Variables ///////////// //////////////////////////////////////////// +#if HAS_LEVELING && ANY(LEVEL_BED_CORNERS, PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) + bool leveling_was_active; // = false +#endif +#if ANY(PROBE_MANUALLY, MESH_BED_LEVELING, X_AXIS_TWIST_COMPENSATION) + uint8_t manual_probe_index; // = 0 +#endif + // Menu Navigation int8_t encoderTopLine, encoderLine, screen_items; @@ -338,8 +345,7 @@ void _lcd_draw_homing() { } } -#if ENABLED(LCD_BED_LEVELING) || (HAS_LEVELING && DISABLED(SLIM_LCD_MENUS)) - #include "../../feature/bedlevel/bedlevel.h" +#if HAS_LEVELING && DISABLED(SLIM_LCD_MENUS) void _lcd_toggle_bed_leveling() { set_bed_leveling_enabled(!planner.leveling_active); } #endif diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 44b0e89aca36f..048dab9b73158 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -218,6 +218,11 @@ void _lcd_draw_homing(); void goto_probe_offset_wizard(); #endif +#if ENABLED(X_AXIS_TWIST_COMPENSATION) + void xatc_wizard_continue(); + void menu_advanced_settings(); +#endif + #if ENABLED(LCD_BED_LEVELING) || (HAS_LEVELING && DISABLED(SLIM_LCD_MENUS)) void _lcd_toggle_bed_leveling(); #endif @@ -249,3 +254,11 @@ extern uint8_t screen_history_depth; inline void clear_menu_history() { screen_history_depth = 0; } #define STICKY_SCREEN(S) []{ ui.defer_status_screen(); ui.goto_screen(S); } + +#if HAS_LEVELING && ANY(LEVEL_BED_CORNERS, PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) + extern bool leveling_was_active; +#endif + +#if ANY(PROBE_MANUALLY, MESH_BED_LEVELING, X_AXIS_TWIST_COMPENSATION) + extern uint8_t manual_probe_index; +#endif diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 8b688ab2ab960..a5b4455d6f6d9 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -508,6 +508,10 @@ void menu_backlash(); SUBMENU(MSG_PROBE_WIZARD, goto_probe_offset_wizard); #endif + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + SUBMENU(MSG_XATC, xatc_wizard_continue); + #endif + END_MENU(); } #endif diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 872b9b3840d89..7bf247f40be29 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -66,10 +66,6 @@ static_assert(LEVEL_CORNERS_Z_HOP >= 0, "LEVEL_CORNERS_Z_HOP must be >= 0. Please update your configuration."); -#if HAS_LEVELING - static bool leveling_was_active = false; -#endif - #ifndef LEVEL_CORNERS_LEVELING_ORDER #define LEVEL_CORNERS_LEVELING_ORDER { LF, RF, LB, RB } // Default //#define LEVEL_CORNERS_LEVELING_ORDER { LF, LB, RF } // 3 hard-coded points diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index eb286f96b9eac..a47e2517aedfa 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -52,8 +52,6 @@ // Motion > Level Bed handlers // - static uint8_t manual_probe_index; - // LCD probed points are from defaults constexpr uint8_t total_probe_points = TERN(AUTO_BED_LEVELING_3POINT, 3, GRID_MAX_POINTS); diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index cddb7ede744d5..29a908ac334df 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -134,6 +134,15 @@ void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); } #endif // E_MANUAL +#if EITHER(PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) + + void _goto_manual_move_z(const_float_t scale) { + ui.manual_move.menu_scale = scale; + ui.goto_screen(lcd_move_z); + } + +#endif + // // "Motion" > "Move Xmm" > "Move XYZ" submenu // diff --git a/Marlin/src/lcd/menu/menu_probe_offset.cpp b/Marlin/src/lcd/menu/menu_probe_offset.cpp index 12b55969a39bf..add7395533801 100644 --- a/Marlin/src/lcd/menu/menu_probe_offset.cpp +++ b/Marlin/src/lcd/menu/menu_probe_offset.cpp @@ -39,13 +39,11 @@ #include "../../feature/bedlevel/bedlevel.h" #endif +void _goto_manual_move_z(const_float_t); + // Global storage float z_offset_backup, calculated_z_offset, z_offset_ref; -#if HAS_LEVELING - bool leveling_was_active; -#endif - inline void z_clearance_move() { do_z_clearance( #ifdef Z_AFTER_HOMING @@ -65,11 +63,6 @@ void set_offset_and_go_back(const_float_t z) { ui.goto_previous_screen_no_defer(); } -void _goto_manual_move_z(const_float_t scale) { - ui.manual_move.menu_scale = scale; - ui.goto_screen(lcd_move_z); -} - void probe_offset_wizard_menu() { START_MENU(); calculated_z_offset = probe.offset.z + current_position.z - z_offset_ref; diff --git a/Marlin/src/lcd/menu/menu_x_twist.cpp b/Marlin/src/lcd/menu/menu_x_twist.cpp new file mode 100644 index 0000000000000..288f16603a886 --- /dev/null +++ b/Marlin/src/lcd/menu/menu_x_twist.cpp @@ -0,0 +1,224 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../inc/MarlinConfigPre.h" + +#if ENABLED(X_AXIS_TWIST_COMPENSATION) + +#include "menu_item.h" +#include "menu_addon.h" +#include "../../module/planner.h" +#include "../../feature/bedlevel/bedlevel.h" +#include "../../module/motion.h" +#include "../../gcode/queue.h" +#include "../../module/probe.h" + +#ifndef XATC_Y_POSITION + #define XATC_Y_POSITION ((probe.max_y() - probe.min_y())/2) +#endif + +void _goto_manual_move_z(const_float_t); + +float measured_z, z_offset; + +// +// Step 9: X Axis Twist Compensation Wizard is finished. +// +void xatc_wizard_done() { + if (!ui.wait_for_move) { + xatc.print_points(); + set_bed_leveling_enabled(leveling_was_active); + SET_SOFT_ENDSTOP_LOOSE(false); + ui.goto_screen(menu_advanced_settings); + } + if (ui.should_draw()) + MenuItem_static::draw(LCD_HEIGHT >= 4, GET_TEXT(MSG_XATC_DONE)); + ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); +} + +void xatc_wizard_goto_next_point(); + +// +// Step 8: Ask the user if he wants to update the z-offset of the probe +// +void xatc_wizard_update_z_offset() { + MenuItem_confirm::select_screen( + GET_TEXT(MSG_YES), GET_TEXT(MSG_NO) + , []{ + probe.offset.z = z_offset; + ui.goto_screen(xatc_wizard_done); + } + , xatc_wizard_done + , GET_TEXT(MSG_XATC_UPDATE_Z_OFFSET) + , ftostr42_52(z_offset), PSTR("?") + ); +} + +// +// Step 7: Set the Z-offset for this point and go to the next one. +// +void xatc_wizard_set_offset_and_go_to_next_point() { + // Set Z-offset at probed point + xatc.z_values[manual_probe_index++] = probe.offset.z + current_position.z - measured_z; + // Go to next point + ui.goto_screen(xatc_wizard_goto_next_point); +} + +// +// Step 6: Wizard Menu. Move the nozzle down until it touches the bed. +// +void xatc_wizard_menu() { + START_MENU(); + float calculated_z_offset = probe.offset.z + current_position.z - measured_z; + + if (LCD_HEIGHT >= 4) + STATIC_ITEM(MSG_MOVE_NOZZLE_TO_BED, SS_CENTER|SS_INVERT); + + STATIC_ITEM_P(PSTR("Z="), SS_CENTER, ftostr42_52(current_position.z)); + STATIC_ITEM(MSG_ZPROBE_ZOFFSET, SS_LEFT, ftostr42_52(calculated_z_offset)); + + SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move_z( 1); }); + SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move_z( 0.1f); }); + + if ((FINE_MANUAL_MOVE) > 0.0f && (FINE_MANUAL_MOVE) < 0.1f) { + char tmp[20], numstr[10]; + // Determine digits needed right of decimal + const uint8_t digs = !UNEAR_ZERO((FINE_MANUAL_MOVE) * 1000 - int((FINE_MANUAL_MOVE) * 1000)) ? 4 : + !UNEAR_ZERO((FINE_MANUAL_MOVE) * 100 - int((FINE_MANUAL_MOVE) * 100)) ? 3 : 2; + sprintf_P(tmp, GET_TEXT(MSG_MOVE_N_MM), dtostrf(FINE_MANUAL_MOVE, 1, digs, numstr)); + #if DISABLED(HAS_GRAPHICAL_TFT) + SUBMENU_P(NUL_STR, []{ _goto_manual_move_z(float(FINE_MANUAL_MOVE)); }); + MENU_ITEM_ADDON_START(0 + ENABLED(HAS_MARLINUI_HD44780)); + lcd_put_u8str(tmp); + MENU_ITEM_ADDON_END(); + #else + SUBMENU_P(tmp, []{ _goto_manual_move_z(float(FINE_MANUAL_MOVE)); }); + #endif + } + + ACTION_ITEM(MSG_BUTTON_DONE, xatc_wizard_set_offset_and_go_to_next_point); + + END_MENU(); +} + +// +// Step 5: Display "Next point: 1 / 9" while waiting for move to finish +// +void xatc_wizard_moving() { + if (ui.should_draw()) { + char msg[10]; + sprintf_P(msg, PSTR("%i / %u"), manual_probe_index + 1, XATC_MAX_POINTS); + MenuEditItemBase::draw_edit_screen(GET_TEXT(MSG_LEVEL_BED_NEXT_POINT), msg); + } + ui.refresh(LCDVIEW_CALL_NO_REDRAW); + if (!ui.wait_for_move) ui.goto_screen(xatc_wizard_menu); +} + +// +// Step 4: Initiate a move to the next point +// +void xatc_wizard_goto_next_point() { + if (manual_probe_index < XATC_MAX_POINTS) { + + const float x = xatc.start + manual_probe_index * xatc.spacing; + + // Avoid probing outside the round or hexagonal area + if (!TERN0(IS_KINEMATIC, !probe.can_reach(x, XATC_Y_POSITION))) { + ui.wait_for_move = true; + ui.goto_screen(xatc_wizard_moving); + + // Deploy certain probes before starting probing + TERN_(BLTOUCH, do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE)); + + measured_z = probe.probe_at_point(x, XATC_Y_POSITION, PROBE_PT_STOW); + current_position += probe.offset_xy; + current_position.z = XATC_START_Z - probe.offset.z + measured_z; + line_to_current_position(MMM_TO_MMS(XY_PROBE_FEEDRATE)); + ui.wait_for_move = false; + } + else + manual_probe_index++; // Go to next point + } + else { + // Compute the z-offset by averaging the values found with this wizard + z_offset = 0; + LOOP_L_N(i, XATC_MAX_POINTS) z_offset += xatc.z_values[i]; + z_offset /= XATC_MAX_POINTS; + + // Subtract the average from the values found with this wizard. + // This way they are indipendent from the z-offset + LOOP_L_N(i, XATC_MAX_POINTS) xatc.z_values[i] -= z_offset; + + ui.goto_screen(xatc_wizard_update_z_offset); + } +} + +// +// Step 3: Display "Click to Begin", wait for click +// Move to the first probe position +// +void xatc_wizard_homing_done() { + if (ui.should_draw()) { + MenuItem_static::draw(1, GET_TEXT(MSG_LEVEL_BED_WAITING)); + + // Color UI needs a control to detect a touch + #if BOTH(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) + touch.add_control(CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT); + #endif + } + + if (ui.use_click()) { + xatc.spacing = (probe.max_x() - probe.min_x()) / (XATC_MAX_POINTS - 1); + xatc.start = probe.min_x(); + + SET_SOFT_ENDSTOP_LOOSE(true); // Disable soft endstops for free Z movement + + ui.goto_screen(xatc_wizard_goto_next_point); + } +} + +// +// Step 2: Display "Homing XYZ" - Wait for homing to finish +// +void xatc_wizard_homing() { + _lcd_draw_homing(); + if (all_axes_homed()) + ui.goto_screen(xatc_wizard_homing_done); +} + +// +// Step 1: Prepare for the wizard... +// +void xatc_wizard_continue() { + // Store Bed-Leveling-State and disable + #if HAS_LEVELING + leveling_was_active = planner.leveling_active; + set_bed_leveling_enabled(false); + #endif + + // Home all axes + ui.defer_status_screen(); + set_all_unhomed(); + ui.goto_screen(xatc_wizard_homing); + queue.inject_P(G28_STR); +} + +#endif // X_AXIS_TWIST_COMPENSATION diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 4057d339dc7d2..8ccf773adc287 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -63,6 +63,9 @@ #if HAS_LEVELING #include "../feature/bedlevel/bedlevel.h" + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + #include "../feature/bedlevel/abl/x_twist.h" + #endif #endif #if ENABLED(Z_STEPPER_AUTO_ALIGN) @@ -250,6 +253,9 @@ typedef struct SettingsDataStruct { xy_pos_t bilinear_grid_spacing, bilinear_start; // G29 L F #if ENABLED(AUTO_BED_LEVELING_BILINEAR) bed_mesh_t z_values; // G29 + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + XATC xatc; // TBD + #endif #else float z_values[3][3]; #endif @@ -814,6 +820,12 @@ void MarlinSettings::postprocess() { sizeof(z_values) == (GRID_MAX_POINTS) * sizeof(z_values[0][0]), "Bilinear Z array is the wrong size." ); + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + static_assert( + sizeof(xatc.z_values) == (XATC_MAX_POINTS) * sizeof(xatc.z_values[0]), + "Z-offset mesh is the wrong size." + ); + #endif #else const xy_pos_t bilinear_start{0}, bilinear_grid_spacing{0}; #endif @@ -827,6 +839,9 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) EEPROM_WRITE(z_values); // 9-256 floats + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + EEPROM_WRITE(xatc); + #endif #else dummyf = 0; for (uint16_t q = grid_max_x * grid_max_y; q--;) EEPROM_WRITE(dummyf); @@ -1691,6 +1706,9 @@ void MarlinSettings::postprocess() { EEPROM_READ(bilinear_grid_spacing); // 2 ints EEPROM_READ(bilinear_start); // 2 ints EEPROM_READ(z_values); // 9 to 256 floats + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + EEPROM_READ(xatc); + #endif } else // EEPROM data is stale #endif // AUTO_BED_LEVELING_BILINEAR @@ -3197,6 +3215,12 @@ void MarlinSettings::reset() { } } + // TODO: Create G-code for settings + //#if ENABLED(X_AXIS_TWIST_COMPENSATION) + // CONFIG_ECHO_START(); + // xatc.print_points(); + //#endif + #endif #endif // HAS_LEVELING diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index b7136e445ed66..a54c04eeb21c5 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -91,7 +91,7 @@ opt_set MOTHERBOARD BOARD_MINIRAMBO \ I2C_SLAVE_ADDRESS 63 opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER \ SDSUPPORT PCA9632 SOUND_MENU_ITEM GCODE_REPEAT_MARKERS \ - AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY LCD_BED_LEVELING G26_MESH_VALIDATION MESH_EDIT_MENU \ + AUTO_BED_LEVELING_LINEAR PROBE_MANUALLY LCD_BED_LEVELING \ LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT EXPERIMENTAL_I2CBUS M100_FREE_MEMORY_WATCHER \ NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE \ @@ -99,7 +99,7 @@ opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CO PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 M114_DETAIL opt_add M100_FREE_MEMORY_DUMPER opt_add M100_FREE_MEMORY_CORRUPTOR -exec_test $1 $2 "MINIRAMBO | RRDGFSC | ABL Bilinear Manual | M100 | PWM_MOTOR_CURRENT | M600..." "$3" +exec_test $1 $2 "MINIRAMBO | RRDGFSC | ABL Linear Manual | M100 | PWM_MOTOR_CURRENT | M600..." "$3" # # Test many less common options @@ -118,7 +118,8 @@ opt_enable COREYX USE_XMAX_PLUG MIXING_EXTRUDER GRADIENT_MIX \ BABYSTEPPING BABYSTEP_DISPLAY_TOTAL FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR \ REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER MENU_ADDAUTOSTART SDSUPPORT SDCARD_SORT_ALPHA \ ENDSTOP_NOISE_THRESHOLD FAN_SOFT_PWM \ - FIX_MOUNTED_PROBE PROBING_ESTEPPERS_OFF AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE PROBE_OFFSET_WIZARD \ + FIX_MOUNTED_PROBE PROBING_ESTEPPERS_OFF PROBE_OFFSET_WIZARD \ + AUTO_BED_LEVELING_BILINEAR X_AXIS_TWIST_COMPENSATION MESH_EDIT_MENU DEBUG_LEVELING_FEATURE G26_MESH_VALIDATION \ Z_SAFE_HOMING SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER \ SD_ABORT_ON_ENDSTOP_HIT HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_PAUSE_M76 ADVANCED_OK M114_DETAIL \ VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS EXTRA_FAN_SPEED FWRETRACT \ diff --git a/ini/features.ini b/ini/features.ini index b56565b154ab9..5f69fcca25d50 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -97,6 +97,7 @@ USB_FLASH_DRIVE_SUPPORT = src_filter=+ + AUTO_BED_LEVELING_BILINEAR = src_filter=+ AUTO_BED_LEVELING_(3POINT|(BI)?LINEAR) = src_filter=+ +X_AXIS_TWIST_COMPENSATION = src_filter=+ + MESH_BED_LEVELING = src_filter=+ + AUTO_BED_LEVELING_UBL = src_filter=+ + UBL_HILBERT_CURVE = src_filter=+ diff --git a/platformio.ini b/platformio.ini index 1b4effcf25624..55a2bd24571c1 100644 --- a/platformio.ini +++ b/platformio.ini @@ -74,6 +74,7 @@ default_src_filter = + - - + - - - + - - - - - - - - @@ -97,6 +98,7 @@ default_src_filter = + - - + - - - - - + - - - - - - From 63d73bfafc8c146a0f230ad1a45c97f0ba23168b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 6 Dec 2021 20:18:50 -0600 Subject: [PATCH 124/273] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20MAX31856=20=3D>=20?= =?UTF-8?q?MAX31865?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/libs/MAX31865.cpp | 28 ++++++++++++++-------------- Marlin/src/libs/MAX31865.h | 36 ++++++++++++++++++------------------ 2 files changed, 32 insertions(+), 32 deletions(-) diff --git a/Marlin/src/libs/MAX31865.cpp b/Marlin/src/libs/MAX31865.cpp index 94048af2089cd..54103074f75b8 100644 --- a/Marlin/src/libs/MAX31865.cpp +++ b/Marlin/src/libs/MAX31865.cpp @@ -166,7 +166,7 @@ void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { " _miso: ", _miso, " _sclk: ", _sclk, " _mosi: ", _mosi, - " config: ", readRegister8(MAX31856_CONFIG_REG) + " config: ", readRegister8(MAX31865_CONFIG_REG) ); #endif } @@ -177,14 +177,14 @@ void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { * @return The raw unsigned 8-bit FAULT status register */ uint8_t MAX31865::readFault() { - return readRegister8(MAX31856_FAULTSTAT_REG); + return readRegister8(MAX31865_FAULTSTAT_REG); } /** * Clear all faults in FAULTSTAT. */ void MAX31865::clearFault() { - setConfig(MAX31856_CONFIG_FAULTSTAT, 1); + setConfig(MAX31865_CONFIG_FAULTSTAT, 1); } /** @@ -193,7 +193,7 @@ void MAX31865::clearFault() { * @param b If true, auto conversion is enabled */ void MAX31865::autoConvert(bool b) { - setConfig(MAX31856_CONFIG_MODEAUTO, b); + setConfig(MAX31865_CONFIG_MODEAUTO, b); } /** @@ -202,7 +202,7 @@ void MAX31865::autoConvert(bool b) { * @param b If true, 50Hz noise is filtered, else 60Hz(default) */ void MAX31865::enable50HzFilter(bool b) { - setConfig(MAX31856_CONFIG_FILT50HZ, b); + setConfig(MAX31865_CONFIG_FILT50HZ, b); } /** @@ -211,7 +211,7 @@ void MAX31865::enable50HzFilter(bool b) { * @param b If true bias is enabled, else disabled */ void MAX31865::enableBias(bool b) { - setConfig(MAX31856_CONFIG_BIAS, b); + setConfig(MAX31865_CONFIG_BIAS, b); // From the datasheet: // Note that if VBIAS is off (to reduce supply current between conversions), any filter @@ -226,7 +226,7 @@ void MAX31865::enableBias(bool b) { * Start a one-shot temperature reading. */ void MAX31865::oneShot() { - setConfig(MAX31856_CONFIG_1SHOT, 1); + setConfig(MAX31865_CONFIG_1SHOT, 1); // From the datasheet: // Note that a single conversion requires approximately 52ms in 60Hz filter @@ -242,12 +242,12 @@ void MAX31865::oneShot() { * @param wires The number of wires in enum format */ void MAX31865::setWires(max31865_numwires_t wires) { - uint8_t t = readRegister8(MAX31856_CONFIG_REG); + uint8_t t = readRegister8(MAX31865_CONFIG_REG); if (wires == MAX31865_3WIRE) - t |= MAX31856_CONFIG_3WIRE; + t |= MAX31865_CONFIG_3WIRE; else // 2 or 4 wire - t &= ~MAX31856_CONFIG_3WIRE; - writeRegister8(MAX31856_CONFIG_REG, t); + t &= ~MAX31865_CONFIG_3WIRE; + writeRegister8(MAX31865_CONFIG_REG, t); } /** @@ -261,7 +261,7 @@ uint16_t MAX31865::readRaw() { enableBias(true); oneShot(); - uint16_t rtd = readRegister16(MAX31856_RTDMSB_REG); + uint16_t rtd = readRegister16(MAX31865_RTDMSB_REG); #ifdef MAX31865_DEBUG SERIAL_ECHOLNPGM("RTD MSB:", (rtd >> 8), " RTD LSB:", (rtd & 0x00FF)); @@ -352,12 +352,12 @@ float MAX31865::temperature(float Rrtd) { * @param enable whether to enable or disable the value */ void MAX31865::setConfig(uint8_t config, bool enable) { - uint8_t t = readRegister8(MAX31856_CONFIG_REG); + uint8_t t = readRegister8(MAX31865_CONFIG_REG); if (enable) t |= config; else t &= ~config; // disable - writeRegister8(MAX31856_CONFIG_REG, t); + writeRegister8(MAX31865_CONFIG_REG, t); } /** diff --git a/Marlin/src/libs/MAX31865.h b/Marlin/src/libs/MAX31865.h index 7610924c2313c..25a69b32dbcf0 100644 --- a/Marlin/src/libs/MAX31865.h +++ b/Marlin/src/libs/MAX31865.h @@ -45,24 +45,24 @@ #include "../HAL/shared/Delay.h" #include HAL_PATH(../HAL, MarlinSPI.h) -#define MAX31856_CONFIG_REG 0x00 -#define MAX31856_CONFIG_BIAS 0x80 -#define MAX31856_CONFIG_MODEAUTO 0x40 -#define MAX31856_CONFIG_MODEOFF 0x00 -#define MAX31856_CONFIG_1SHOT 0x20 -#define MAX31856_CONFIG_3WIRE 0x10 -#define MAX31856_CONFIG_24WIRE 0x00 -#define MAX31856_CONFIG_FAULTSTAT 0x02 -#define MAX31856_CONFIG_FILT50HZ 0x01 -#define MAX31856_CONFIG_FILT60HZ 0x00 - -#define MAX31856_RTDMSB_REG 0x01 -#define MAX31856_RTDLSB_REG 0x02 -#define MAX31856_HFAULTMSB_REG 0x03 -#define MAX31856_HFAULTLSB_REG 0x04 -#define MAX31856_LFAULTMSB_REG 0x05 -#define MAX31856_LFAULTLSB_REG 0x06 -#define MAX31856_FAULTSTAT_REG 0x07 +#define MAX31865_CONFIG_REG 0x00 +#define MAX31865_CONFIG_BIAS 0x80 +#define MAX31865_CONFIG_MODEAUTO 0x40 +#define MAX31865_CONFIG_MODEOFF 0x00 +#define MAX31865_CONFIG_1SHOT 0x20 +#define MAX31865_CONFIG_3WIRE 0x10 +#define MAX31865_CONFIG_24WIRE 0x00 +#define MAX31865_CONFIG_FAULTSTAT 0x02 +#define MAX31865_CONFIG_FILT50HZ 0x01 +#define MAX31865_CONFIG_FILT60HZ 0x00 + +#define MAX31865_RTDMSB_REG 0x01 +#define MAX31865_RTDLSB_REG 0x02 +#define MAX31865_HFAULTMSB_REG 0x03 +#define MAX31865_HFAULTLSB_REG 0x04 +#define MAX31865_LFAULTMSB_REG 0x05 +#define MAX31865_LFAULTLSB_REG 0x06 +#define MAX31865_FAULTSTAT_REG 0x07 #define MAX31865_FAULT_HIGHTHRESH 0x80 // D7 #define MAX31865_FAULT_LOWTHRESH 0x40 // D6 From 5d45aba550598f63b4f0ded99205b40c29275b26 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 8 Dec 2021 01:05:41 +0000 Subject: [PATCH 125/273] [cron] Bump distribution date (2021-12-08) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index dd14eeff4f747..258fd248817c7 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 "2021-12-07" +//#define STRING_DISTRIBUTION_DATE "2021-12-08" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 36e2488f9e9a5..7139fe4c18a24 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 "2021-12-07" + #define STRING_DISTRIBUTION_DATE "2021-12-08" #endif /** From 0a64209305ea32e85a7b786604ae0c11fd4f1fcb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 8 Dec 2021 12:40:23 -0600 Subject: [PATCH 126/273] =?UTF-8?q?=F0=9F=8E=A8=20Rename=20MAX31865=20elem?= =?UTF-8?q?ents?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/libs/MAX31865.cpp | 116 +++++++++++++++++------------------ Marlin/src/libs/MAX31865.h | 12 ++-- 2 files changed, 64 insertions(+), 64 deletions(-) diff --git a/Marlin/src/libs/MAX31865.cpp b/Marlin/src/libs/MAX31865.cpp index 54103074f75b8..40c65300c009e 100644 --- a/Marlin/src/libs/MAX31865.cpp +++ b/Marlin/src/libs/MAX31865.cpp @@ -73,10 +73,10 @@ SPISettings MAX31865::spiConfig = SPISettings( * @param spi_clk the SPI clock pin to use */ MAX31865::MAX31865(int8_t spi_cs, int8_t spi_mosi, int8_t spi_miso, int8_t spi_clk) { - _cs = spi_cs; - _mosi = spi_mosi; - _miso = spi_miso; - _sclk = spi_clk; + cselPin = spi_cs; + mosiPin = spi_mosi; + misoPin = spi_miso; + sclkPin = spi_clk; } /** @@ -86,8 +86,8 @@ SPISettings MAX31865::spiConfig = SPISettings( * @param spi_cs the SPI CS pin to use along with the default SPI device */ MAX31865::MAX31865(int8_t spi_cs) { - _cs = spi_cs; - _sclk = _miso = _mosi = -1; + cselPin = spi_cs; + sclkPin = misoPin = mosiPin = -1; } #else // LARGE_PINMAP @@ -104,10 +104,10 @@ SPISettings MAX31865::spiConfig = SPISettings( * @param pin_mapping set to 1 for positive pin values */ MAX31865::MAX31865(uint32_t spi_cs, uint32_t spi_mosi, uint32_t spi_miso, uint32_t spi_clk, uint8_t pin_mapping) { - _cs = spi_cs; - _mosi = spi_mosi; - _miso = spi_miso; - _sclk = spi_clk; + cselPin = spi_cs; + mosiPin = spi_mosi; + misoPin = spi_miso; + sclkPin = spi_clk; } /** @@ -119,8 +119,8 @@ SPISettings MAX31865::spiConfig = SPISettings( * @param pin_mapping set to 1 for positive pin values */ MAX31865::MAX31865(uint32_t spi_cs, uint8_t pin_mapping) { - _cs = spi_cs; - _sclk = _miso = _mosi = -1UL; //-1UL or 0xFFFFFFFF or 4294967295 + cselPin = spi_cs; + sclkPin = misoPin = mosiPin = -1UL; //-1UL or 0xFFFFFFFF or 4294967295 } #endif // LARGE_PINMAP @@ -139,12 +139,12 @@ SPISettings MAX31865::spiConfig = SPISettings( * @param ref The resistance of the reference resistor, in ohms. */ void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { - Rzero = zero; - Rref = ref; + zeroRes = zero; + refRes = ref; - OUT_WRITE(_cs, HIGH); + OUT_WRITE(cselPin, HIGH); - if (_sclk != TERN(LARGE_PINMAP, -1UL, -1)) { + if (sclkPin != TERN(LARGE_PINMAP, -1UL, -1)) { softSpiBegin(SPI_QUARTER_SPEED); // Define pin modes for Software SPI } else { @@ -162,10 +162,10 @@ void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { #ifdef MAX31865_DEBUG_SPI SERIAL_ECHOLNPGM( TERN(LARGE_PINMAP, "LARGE_PINMAP", "Regular") - " begin call with _cs: ", _cs, - " _miso: ", _miso, - " _sclk: ", _sclk, - " _mosi: ", _mosi, + " begin call with cselPin: ", cselPin, + " misoPin: ", misoPin, + " sclkPin: ", sclkPin, + " mosiPin: ", mosiPin, " config: ", readRegister8(MAX31865_CONFIG_REG) ); #endif @@ -282,8 +282,8 @@ uint16_t MAX31865::readRaw() { */ float MAX31865::readResistance() { // Strip the error bit (D0) and convert to a float ratio. - // less precise method: (readRaw() * Rref) >> 16 - return (((readRaw() >> 1) / 32768.0f) * Rref); + // less precise method: (readRaw() * refRes) >> 16 + return (((readRaw() >> 1) / 32768.0f) * refRes); } /** @@ -300,8 +300,8 @@ float MAX31865::temperature() { * * @return Temperature in C */ -float MAX31865::temperature(uint16_t adcVal) { - return temperature(((adcVal) / 32768.0f) * Rref); +float MAX31865::temperature(uint16_t adc_val) { + return temperature(((adc_val) / 32768.0f) * refRes); } /** @@ -309,11 +309,11 @@ float MAX31865::temperature(uint16_t adcVal) { * Uses the technique outlined in this PDF: * http://www.analog.com/media/en/technical-documentation/application-notes/AN709_0.pdf * - * @param Rrtd the resistance value in ohms - * @return the temperature in degC + * @param rtd_res the resistance value in ohms + * @return the temperature in degC */ -float MAX31865::temperature(float Rrtd) { - float temp = (RTD_Z1 + sqrt(RTD_Z2 + (RTD_Z3 * Rrtd))) / RTD_Z4; +float MAX31865::temperature(float rtd_res) { + float temp = (RTD_Z1 + sqrt(RTD_Z2 + (RTD_Z3 * rtd_res))) * RECIPROCAL(RTD_Z4); // From the PDF... // @@ -324,17 +324,17 @@ float MAX31865::temperature(float Rrtd) { // of resistance. // if (temp < 0) { - Rrtd = (Rrtd / Rzero) * 100; // normalize to 100 ohm - float rpoly = Rrtd; + rtd_res = (rtd_res / zeroRes) * 100; // normalize to 100 ohm + float rpoly = rtd_res; temp = -242.02 + (2.2228 * rpoly); - rpoly *= Rrtd; // square + rpoly *= rtd_res; // square temp += 2.5859e-3 * rpoly; - rpoly *= Rrtd; // ^3 + rpoly *= rtd_res; // ^3 temp -= 4.8260e-6 * rpoly; - rpoly *= Rrtd; // ^4 + rpoly *= rtd_res; // ^4 temp -= 2.8183e-8 * rpoly; - rpoly *= Rrtd; // ^5 + rpoly *= rtd_res; // ^5 temp += 1.5243e-10 * rpoly; } @@ -399,15 +399,15 @@ uint16_t MAX31865::readRegister16(uint8_t addr) { */ void MAX31865::readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n) { addr &= 0x7F; // make sure top bit is not set - if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + if (sclkPin == TERN(LARGE_PINMAP, -1UL, -1)) SPI.beginTransaction(spiConfig); else - WRITE(_sclk, LOW); + WRITE(sclkPin, LOW); - WRITE(_cs, LOW); + WRITE(cselPin, LOW); #ifdef TARGET_LPC1768 - DELAY_CYCLES(_spi_speed); + DELAY_CYCLES(spiSpeed); #endif spiTransfer(addr); @@ -420,10 +420,10 @@ void MAX31865::readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n) { buffer++; } - if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + if (sclkPin == TERN(LARGE_PINMAP, -1UL, -1)) SPI.endTransaction(); - WRITE(_cs, HIGH); + WRITE(cselPin, HIGH); } /** @@ -433,24 +433,24 @@ void MAX31865::readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n) { * @param data the data to write */ void MAX31865::writeRegister8(uint8_t addr, uint8_t data) { - if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + if (sclkPin == TERN(LARGE_PINMAP, -1UL, -1)) SPI.beginTransaction(spiConfig); else - WRITE(_sclk, LOW); + WRITE(sclkPin, LOW); - WRITE(_cs, LOW); + WRITE(cselPin, LOW); #ifdef TARGET_LPC1768 - DELAY_CYCLES(_spi_speed); + DELAY_CYCLES(spiSpeed); #endif spiTransfer(addr | 0x80); // make sure top bit is set spiTransfer(data); - if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + if (sclkPin == TERN(LARGE_PINMAP, -1UL, -1)) SPI.endTransaction(); - WRITE(_cs, HIGH); + WRITE(cselPin, HIGH); } /** @@ -463,19 +463,19 @@ void MAX31865::writeRegister8(uint8_t addr, uint8_t data) { * @return the 8-bit response */ uint8_t MAX31865::spiTransfer(uint8_t x) { - if (_sclk == TERN(LARGE_PINMAP, -1UL, -1)) + if (sclkPin == TERN(LARGE_PINMAP, -1UL, -1)) return SPI.transfer(x); #ifdef TARGET_LPC1768 - return swSpiTransfer(x, _spi_speed, _sclk, _miso, _mosi); + return swSpiTransfer(x, spiSpeed, sclkPin, misoPin, mosiPin); #else uint8_t reply = 0; for (int i = 7; i >= 0; i--) { - WRITE(_sclk, HIGH); DELAY_NS_VAR(_spi_delay); + WRITE(sclkPin, HIGH); DELAY_NS_VAR(spiDelay); reply <<= 1; - WRITE(_mosi, x & _BV(i)); DELAY_NS_VAR(_spi_delay); - if (READ(_miso)) reply |= 1; - WRITE(_sclk, LOW); DELAY_NS_VAR(_spi_delay); + WRITE(mosiPin, x & _BV(i)); DELAY_NS_VAR(spiDelay); + if (READ(misoPin)) reply |= 1; + WRITE(sclkPin, LOW); DELAY_NS_VAR(spiDelay); } return reply; #endif @@ -486,13 +486,13 @@ void MAX31865::softSpiBegin(const uint8_t spi_speed) { SERIAL_ECHOLNPGM("Initializing MAX31865 Software SPI"); #endif #ifdef TARGET_LPC1768 - swSpiBegin(_sclk, _miso, _mosi); - _spi_speed = swSpiInit(spi_speed, _sclk, _mosi); + swSpiBegin(sclkPin, misoPin, mosiPin); + spiSpeed = swSpiInit(spi_speed, sclkPin, mosiPin); #else - _spi_delay = (100UL << spi_speed) / 3; // Calculate delay in ns. Top speed is ~10MHz, or 100ns delay between bits. - OUT_WRITE(_sclk, LOW); - SET_OUTPUT(_mosi); - SET_INPUT(_miso); + spiDelay = (100UL << spi_speed) / 3; // Calculate delay in ns. Top speed is ~10MHz, or 100ns delay between bits. + OUT_WRITE(sclkPin, LOW); + SET_OUTPUT(mosiPin); + SET_INPUT(misoPin); #endif } diff --git a/Marlin/src/libs/MAX31865.h b/Marlin/src/libs/MAX31865.h index 25a69b32dbcf0..7cd1f25c984e2 100644 --- a/Marlin/src/libs/MAX31865.h +++ b/Marlin/src/libs/MAX31865.h @@ -89,15 +89,15 @@ class MAX31865 { private: static SPISettings spiConfig; - TERN(LARGE_PINMAP, uint32_t, uint8_t) _sclk, _miso, _mosi, _cs; + TERN(LARGE_PINMAP, uint32_t, uint8_t) sclkPin, misoPin, mosiPin, cselPin; #ifdef TARGET_LPC1768 - uint8_t _spi_speed; + uint8_t spiSpeed; #else - uint16_t _spi_delay; + uint16_t spiDelay; #endif - float Rzero, Rref; + float zeroRes, refRes; void setConfig(uint8_t config, bool enable); @@ -135,6 +135,6 @@ class MAX31865 { uint16_t readRaw(); float readResistance(); float temperature(); - float temperature(uint16_t adcVal); - float temperature(float Rrtd); + float temperature(uint16_t adc_val); + float temperature(float rtd_res); }; From 9e6ded3cdfb362fb6b0f44ade6baca562708ee1c Mon Sep 17 00:00:00 2001 From: John Lagonikas <39417467+zeleps@users.noreply.github.com> Date: Wed, 8 Dec 2021 20:55:09 +0200 Subject: [PATCH 127/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20and=20improve=20MA?= =?UTF-8?q?X31865=20(#23215)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 9 + Marlin/src/inc/Conditionals_adv.h | 6 + Marlin/src/libs/MAX31865.cpp | 313 ++++++++++++++++++------------ Marlin/src/libs/MAX31865.h | 43 +++- Marlin/src/module/temperature.cpp | 10 +- 5 files changed, 239 insertions(+), 142 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 4e10ce557765d..0d848f260b95c 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -142,11 +142,20 @@ * FORCE_HW_SPI: Ignore SCK/MOSI/MISO pins and just use the CS pin & default SPI bus. * MAX31865_WIRES: Set the number of wires for the probe connected to a MAX31865 board, 2-4. Default: 2 * MAX31865_50HZ: Enable 50Hz filter instead of the default 60Hz. + * MAX31865_USE_READ_ERROR_DETECTION: Detects random read errors from value spikes (a 20°C difference in less than 1sec) + * MAX31865_USE_AUTO_MODE: Faster and more frequent reads than 1-shot, but bias voltage always on, slightly affecting RTD temperature. + * MAX31865_MIN_SAMPLING_TIME_MSEC: in 1-shot mode, the minimum time between subsequent reads. This reduces the effect of bias voltage by leaving the sensor unpowered for longer intervals. + * MAX31865_WIRE_OHMS: In 2-wire configurations, manually set the wire resistance for more accurate readings */ //#define TEMP_SENSOR_FORCE_HW_SPI //#define MAX31865_SENSOR_WIRES_0 2 //#define MAX31865_SENSOR_WIRES_1 2 //#define MAX31865_50HZ_FILTER +//#define MAX31865_USE_READ_ERROR_DETECTION +//#define MAX31865_USE_AUTO_MODE +//#define MAX31865_MIN_SAMPLING_TIME_MSEC 100 +//#define MAX31865_WIRE_OHMS_0 0.0f +//#define MAX31865_WIRE_OHMS_1 0.0f /** * Hephestos 2 24V heated bed upgrade kit. diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 49067a5606763..22f1591d68261 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -159,6 +159,9 @@ #ifndef MAX31865_SENSOR_WIRES_0 #define MAX31865_SENSOR_WIRES_0 2 #endif + #ifndef MAX31865_WIRE_OHMS_0 + #define MAX31865_WIRE_OHMS_0 0.0f + #endif #elif TEMP_SENSOR_0 == -3 #define TEMP_SENSOR_0_IS_MAX31855 1 #define TEMP_SENSOR_0_MAX_TC_TMIN -270 @@ -193,6 +196,9 @@ #ifndef MAX31865_SENSOR_WIRES_1 #define MAX31865_SENSOR_WIRES_1 2 #endif + #ifndef MAX31865_WIRE_OHMS_1 + #define MAX31865_WIRE_OHMS_1 0.0f + #endif #elif TEMP_SENSOR_1 == -3 #define TEMP_SENSOR_1_IS_MAX31855 1 #define TEMP_SENSOR_1_MAX_TC_TMIN -270 diff --git a/Marlin/src/libs/MAX31865.cpp b/Marlin/src/libs/MAX31865.cpp index 40c65300c009e..6cc8ffca39903 100644 --- a/Marlin/src/libs/MAX31865.cpp +++ b/Marlin/src/libs/MAX31865.cpp @@ -40,20 +40,23 @@ * All rights reserved. */ -// Useful for RTD debugging. -//#define MAX31865_DEBUG -//#define MAX31865_DEBUG_SPI - #include "../inc/MarlinConfig.h" #if HAS_MAX31865 && !USE_ADAFRUIT_MAX31865 #include "MAX31865.h" +#ifndef MAX31865_MIN_SAMPLING_TIME_MSEC + #define MAX31865_MIN_SAMPLING_TIME_MSEC 0 +#endif + #ifdef TARGET_LPC1768 #include #endif +#define DEBUG_OUT ENABLED(DEBUG_MAX31865) +#include "../core/debug_out.h" + // The maximum speed the MAX31865 can do is 5 MHz SPISettings MAX31865::spiConfig = SPISettings( TERN(TARGET_LPC1768, SPI_QUARTER_SPEED, TERN(ARDUINO_ARCH_STM32, SPI_CLOCK_DIV4, 500000)), @@ -61,7 +64,7 @@ SPISettings MAX31865::spiConfig = SPISettings( SPI_MODE1 // CPOL0 CPHA1 ); -#ifndef LARGE_PINMAP +#if DISABLED(LARGE_PINMAP) /** * Create the interface object using software (bitbang) SPI for PIN values @@ -137,117 +140,121 @@ SPISettings MAX31865::spiConfig = SPISettings( * @param wires The number of wires in enum format. Can be MAX31865_2WIRE, MAX31865_3WIRE, or MAX31865_4WIRE. * @param zero The resistance of the RTD at 0 degC, in ohms. * @param ref The resistance of the reference resistor, in ohms. + * @param wire The resistance of the wire connecting the sensor to the RTD, in ohms. */ -void MAX31865::begin(max31865_numwires_t wires, float zero, float ref) { - zeroRes = zero; - refRes = ref; +void MAX31865::begin(max31865_numwires_t wires, float zero_res, float ref_res, float wire_res) { + zeroRes = zero_res; + refRes = ref_res; + wireRes = wire_res; - OUT_WRITE(cselPin, HIGH); + pinMode(cselPin, OUTPUT); + digitalWrite(cselPin, HIGH); - if (sclkPin != TERN(LARGE_PINMAP, -1UL, -1)) { + if (sclkPin != TERN(LARGE_PINMAP, -1UL, 255)) softSpiBegin(SPI_QUARTER_SPEED); // Define pin modes for Software SPI - } else { - #ifdef MAX31865_DEBUG - SERIAL_ECHOLNPGM("Initializing MAX31865 Hardware SPI"); - #endif + DEBUG_ECHOLNPGM("Initializing MAX31865 Hardware SPI"); SPI.begin(); // Start and configure hardware SPI } - setWires(wires); - enableBias(false); - autoConvert(false); - clearFault(); - - #ifdef MAX31865_DEBUG_SPI - SERIAL_ECHOLNPGM( - TERN(LARGE_PINMAP, "LARGE_PINMAP", "Regular") - " begin call with cselPin: ", cselPin, - " misoPin: ", misoPin, - " sclkPin: ", sclkPin, - " mosiPin: ", mosiPin, - " config: ", readRegister8(MAX31865_CONFIG_REG) - ); - #endif + initFixedFlags(wires); + + clearFault(); // also initializes flags + + #if DISABLED(MAX31865_USE_AUTO_MODE) // make a proper first 1 shot read to initialize _lastRead + + enableBias(); + DELAY_US(11500); + oneShot(); + DELAY_US(65000); + uint16_t rtd = readRegister16(MAX31865_RTDMSB_REG); + + if (rtd & 1) { + lastRead = 0xFFFF; // some invalid value + lastFault = readRegister8(MAX31865_FAULTSTAT_REG); + clearFault(); // also clears the bias voltage flag, so no further action is required + + DEBUG_ECHOLNPGM("MAX31865 read fault: ", rtd); + } + else { + DEBUG_ECHOLNPGM("RTD MSB:", (rtd >> 8), " RTD LSB:", (rtd & 0x00FF)); + + resetFlags(); + + lastRead = rtd; + nextEvent = SETUP_BIAS_VOLTAGE; + millis_t now = millis(); + nextEventStamp = now + MAX31865_MIN_SAMPLING_TIME_MSEC; + + TERN_(MAX31865_USE_READ_ERROR_DETECTION, lastReadStamp = now); + } + + #endif // !MAX31865_USE_AUTO_MODE + + DEBUG_ECHOLNPGM( + TERN(LARGE_PINMAP, "LARGE_PINMAP", "Regular") + " begin call with cselPin: ", cselPin, + " misoPin: ", misoPin, + " sclkPin: ", sclkPin, + " mosiPin: ", mosiPin, + " config: ", readRegister8(MAX31865_CONFIG_REG) + ); } /** - * Read the raw 8-bit FAULTSTAT register + * Return and clear the last fault value * - * @return The raw unsigned 8-bit FAULT status register + * @return The raw unsigned 8-bit FAULT status register or spike fault */ uint8_t MAX31865::readFault() { - return readRegister8(MAX31865_FAULTSTAT_REG); + uint8_t r = lastFault; + lastFault = 0; + return r; } /** - * Clear all faults in FAULTSTAT. + * Clear last fault */ void MAX31865::clearFault() { setConfig(MAX31865_CONFIG_FAULTSTAT, 1); } /** - * Whether we want to have continuous conversions (50/60 Hz) - * - * @param b If true, auto conversion is enabled - */ -void MAX31865::autoConvert(bool b) { - setConfig(MAX31865_CONFIG_MODEAUTO, b); -} - -/** - * Whether we want filter out 50Hz noise or 60Hz noise - * - * @param b If true, 50Hz noise is filtered, else 60Hz(default) + * Reset flags */ -void MAX31865::enable50HzFilter(bool b) { - setConfig(MAX31865_CONFIG_FILT50HZ, b); +void MAX31865::resetFlags() { + writeRegister8(MAX31865_CONFIG_REG, stdFlags); } /** * Enable the bias voltage on the RTD sensor - * - * @param b If true bias is enabled, else disabled */ -void MAX31865::enableBias(bool b) { - setConfig(MAX31865_CONFIG_BIAS, b); - - // From the datasheet: - // Note that if VBIAS is off (to reduce supply current between conversions), any filter - // capacitors at the RTDIN inputs need to charge before an accurate conversion can be - // performed. Therefore, enable VBIAS and wait at least 10.5 time constants of the input - // RC network plus an additional 1ms before initiating the conversion. - if (b) - DELAY_US(11500); //11.5ms +void MAX31865::enableBias() { + setConfig(MAX31865_CONFIG_BIAS, 1); } /** * Start a one-shot temperature reading. */ void MAX31865::oneShot() { - setConfig(MAX31865_CONFIG_1SHOT, 1); - - // From the datasheet: - // Note that a single conversion requires approximately 52ms in 60Hz filter - // mode or 62.5ms in 50Hz filter mode to complete. 1-Shot is a self-clearing bit. - // TODO: switch this out depending on the filter mode. - DELAY_US(65000); // 65ms + setConfig(MAX31865_CONFIG_1SHOT | MAX31865_CONFIG_BIAS, 1); } /** - * How many wires we have in our RTD setup, can be MAX31865_2WIRE, - * MAX31865_3WIRE, or MAX31865_4WIRE + * Initialize standard flags with flags that will not change during operation (Hz, polling mode and no. of wires) * * @param wires The number of wires in enum format */ -void MAX31865::setWires(max31865_numwires_t wires) { - uint8_t t = readRegister8(MAX31865_CONFIG_REG); +void MAX31865::initFixedFlags(max31865_numwires_t wires) { + + // set config-defined flags (same for all sensors) + stdFlags = TERN(MAX31865_50HZ_FILTER, MAX31865_CONFIG_FILT50HZ, MAX31865_CONFIG_FILT60HZ) | + TERN(MAX31865_USE_AUTO_MODE, MAX31865_CONFIG_MODEAUTO | MAX31865_CONFIG_BIAS, MAX31865_CONFIG_MODEOFF); + if (wires == MAX31865_3WIRE) - t |= MAX31865_CONFIG_3WIRE; - else // 2 or 4 wire - t &= ~MAX31865_CONFIG_3WIRE; - writeRegister8(MAX31865_CONFIG_REG, t); + stdFlags |= MAX31865_CONFIG_3WIRE; + else // 2 or 4 wire + stdFlags &= ~MAX31865_CONFIG_3WIRE; } /** @@ -257,33 +264,96 @@ void MAX31865::setWires(max31865_numwires_t wires) { * @return The raw unsigned 16-bit register value with ERROR bit attached, NOT temperature! */ uint16_t MAX31865::readRaw() { - clearFault(); - enableBias(true); - oneShot(); - uint16_t rtd = readRegister16(MAX31865_RTDMSB_REG); + #if ENABLED(MAX31865_USE_AUTO_MODE) - #ifdef MAX31865_DEBUG - SERIAL_ECHOLNPGM("RTD MSB:", (rtd >> 8), " RTD LSB:", (rtd & 0x00FF)); - #endif + const uint16_t rtd = readRegister16(MAX31865_RTDMSB_REG); + DEBUG_ECHOLNPGM("MAX31865 RTD MSB:", (rtd >> 8), " LSB:", (rtd & 0x00FF)); + + if (rtd & 1) { + lastFault = readRegister8(MAX31865_FAULTSTAT_REG); + lastRead |= 1; + clearFault(); // also clears the bias voltage flag, so no further action is required + DEBUG_ECHOLNPGM("MAX31865 read fault: ", rtd); + } + #if ENABLED(MAX31865_USE_READ_ERROR_DETECTION) + else if (ABS(lastRead - rtd) > 500 && PENDING(millis(), lastReadStamp + 1000)) { // if two readings within a second differ too much (~20°C), consider it a read error. + lastFault = 0x01; + lastRead |= 1; + DEBUG_ECHOLNPGM("MAX31865 read error: ", rtd); + } + #endif + else { + lastRead = rtd; + TERN_(MAX31865_USE_READ_ERROR_DETECTION, lastReadStamp = millis()); + } - // Disable the bias to lower power dissipation between reads. - // If the ref resistor heats up, the temperature reading will be skewed. - enableBias(false); + #else + + if (PENDING(millis(), nextEventStamp)) { + DEBUG_ECHOLNPGM("MAX31865 waiting for event ", nextEvent); + return lastRead; + } + + switch (nextEvent) { + case SETUP_BIAS_VOLTAGE: + enableBias(); + nextEventStamp = millis() + 11; // wait at least 11msec before enabling 1shot + nextEvent = SETUP_1_SHOT_MODE; + DEBUG_ECHOLN("MAX31865 bias voltage enabled"); + break; + + case SETUP_1_SHOT_MODE: + oneShot(); + nextEventStamp = millis() + 65; // wait at least 65msec before reading RTD register + nextEvent = READ_RTD_REG; + DEBUG_ECHOLN("MAX31865 1 shot mode enabled"); + break; + + case READ_RTD_REG: { + const uint16_t rtd = readRegister16(MAX31865_RTDMSB_REG); + DEBUG_ECHOLNPGM("MAX31865 RTD MSB:", (rtd >> 8), " LSB:", (rtd & 0x00FF)); + + if (rtd & 1) { + lastFault = readRegister8(MAX31865_FAULTSTAT_REG); + lastRead |= 1; + clearFault(); // also clears the bias voltage flag, so no further action is required + DEBUG_ECHOLNPGM("MAX31865 read fault: ", rtd); + } + #if ENABLED(MAX31865_USE_READ_ERROR_DETECTION) + else if (ABS(lastRead - rtd) > 500 && PENDING(millis(), lastReadStamp + 1000)) { // if two readings within a second differ too much (~20°C), consider it a read error. + lastFault = 0x01; + lastRead |= 1; + DEBUG_ECHOLNPGM("MAX31865 read error: ", rtd); + } + #endif + else { + lastRead = rtd; + TERN_(MAX31865_USE_READ_ERROR_DETECTION, lastReadStamp = millis()); + } + + if (!(rtd & 1)) // if clearFault() was not invoked, need to clear the bias voltage and 1-shot flags + resetFlags(); + + nextEvent = SETUP_BIAS_VOLTAGE; + nextEventStamp = millis() + MAX31865_MIN_SAMPLING_TIME_MSEC; // next step should not occur within less than MAX31865_MIN_SAMPLING_TIME_MSEC from the last one + } break; + } + + #endif - return rtd; + return lastRead; } /** * Calculate and return the resistance value of the connected RTD. * - * @param refResistor The value of the matching reference resistor, usually 430 or 4300 * @return The raw RTD resistance value, NOT temperature! */ float MAX31865::readResistance() { // Strip the error bit (D0) and convert to a float ratio. // less precise method: (readRaw() * refRes) >> 16 - return (((readRaw() >> 1) / 32768.0f) * refRes); + return ((readRaw() * RECIPROCAL(65536.0f)) * refRes - wireRes); } /** @@ -301,7 +371,7 @@ float MAX31865::temperature() { * @return Temperature in C */ float MAX31865::temperature(uint16_t adc_val) { - return temperature(((adc_val) / 32768.0f) * refRes); + return temperature(((adc_val) * RECIPROCAL(32768.0f)) * refRes - wireRes); } /** @@ -352,11 +422,8 @@ float MAX31865::temperature(float rtd_res) { * @param enable whether to enable or disable the value */ void MAX31865::setConfig(uint8_t config, bool enable) { - uint8_t t = readRegister8(MAX31865_CONFIG_REG); - if (enable) - t |= config; - else - t &= ~config; // disable + uint8_t t = stdFlags; + if (enable) t |= config; else t &= ~config; writeRegister8(MAX31865_CONFIG_REG, t); } @@ -369,7 +436,6 @@ void MAX31865::setConfig(uint8_t config, bool enable) { uint8_t MAX31865::readRegister8(uint8_t addr) { uint8_t ret = 0; readRegisterN(addr, &ret, 1); - return ret; } @@ -380,14 +446,9 @@ uint8_t MAX31865::readRegister8(uint8_t addr) { * @return both register contents as a single 16-bit int */ uint16_t MAX31865::readRegister16(uint8_t addr) { - uint8_t buffer[2] = {0, 0}; + uint8_t buffer[2] = { 0 }; readRegisterN(addr, buffer, 2); - - uint16_t ret = buffer[0]; - ret <<= 8; - ret |= buffer[1]; - - return ret; + return uint16_t(buffer[0]) << 8 | buffer[1]; } /** @@ -399,12 +460,12 @@ uint16_t MAX31865::readRegister16(uint8_t addr) { */ void MAX31865::readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n) { addr &= 0x7F; // make sure top bit is not set - if (sclkPin == TERN(LARGE_PINMAP, -1UL, -1)) + if (sclkPin == TERN(LARGE_PINMAP, -1UL, 255)) SPI.beginTransaction(spiConfig); else - WRITE(sclkPin, LOW); + digitalWrite(sclkPin, LOW); - WRITE(cselPin, LOW); + digitalWrite(cselPin, LOW); #ifdef TARGET_LPC1768 DELAY_CYCLES(spiSpeed); @@ -414,16 +475,13 @@ void MAX31865::readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n) { while (n--) { buffer[0] = spiTransfer(0xFF); - #ifdef MAX31865_DEBUG_SPI - SERIAL_ECHOLNPGM("buffer read ", n, " data: ", buffer[0]); - #endif buffer++; } - if (sclkPin == TERN(LARGE_PINMAP, -1UL, -1)) + if (sclkPin == TERN(LARGE_PINMAP, -1UL, 255)) SPI.endTransaction(); - WRITE(cselPin, HIGH); + digitalWrite(cselPin, HIGH); } /** @@ -433,12 +491,12 @@ void MAX31865::readRegisterN(uint8_t addr, uint8_t buffer[], uint8_t n) { * @param data the data to write */ void MAX31865::writeRegister8(uint8_t addr, uint8_t data) { - if (sclkPin == TERN(LARGE_PINMAP, -1UL, -1)) + if (sclkPin == TERN(LARGE_PINMAP, -1UL, 255)) SPI.beginTransaction(spiConfig); else - WRITE(sclkPin, LOW); + digitalWrite(sclkPin, LOW); - WRITE(cselPin, LOW); + digitalWrite(cselPin, LOW); #ifdef TARGET_LPC1768 DELAY_CYCLES(spiSpeed); @@ -447,10 +505,10 @@ void MAX31865::writeRegister8(uint8_t addr, uint8_t data) { spiTransfer(addr | 0x80); // make sure top bit is set spiTransfer(data); - if (sclkPin == TERN(LARGE_PINMAP, -1UL, -1)) + if (sclkPin == TERN(LARGE_PINMAP, -1UL, 255)) SPI.endTransaction(); - WRITE(cselPin, HIGH); + digitalWrite(cselPin, HIGH); } /** @@ -463,36 +521,41 @@ void MAX31865::writeRegister8(uint8_t addr, uint8_t data) { * @return the 8-bit response */ uint8_t MAX31865::spiTransfer(uint8_t x) { - if (sclkPin == TERN(LARGE_PINMAP, -1UL, -1)) + + if (sclkPin == TERN(LARGE_PINMAP, -1UL, 255)) return SPI.transfer(x); #ifdef TARGET_LPC1768 + return swSpiTransfer(x, spiSpeed, sclkPin, misoPin, mosiPin); + #else + uint8_t reply = 0; for (int i = 7; i >= 0; i--) { - WRITE(sclkPin, HIGH); DELAY_NS_VAR(spiDelay); + digitalWrite(sclkPin, HIGH); DELAY_NS_VAR(spiDelay); reply <<= 1; - WRITE(mosiPin, x & _BV(i)); DELAY_NS_VAR(spiDelay); - if (READ(misoPin)) reply |= 1; - WRITE(sclkPin, LOW); DELAY_NS_VAR(spiDelay); + digitalWrite(mosiPin, x & _BV(i)); DELAY_NS_VAR(spiDelay); + if (digitalRead(misoPin)) reply |= 1; + digitalWrite(sclkPin, LOW); DELAY_NS_VAR(spiDelay); } return reply; + #endif } void MAX31865::softSpiBegin(const uint8_t spi_speed) { - #ifdef MAX31865_DEBUG - SERIAL_ECHOLNPGM("Initializing MAX31865 Software SPI"); - #endif + DEBUG_ECHOLNPGM("Initializing MAX31865 Software SPI"); + #ifdef TARGET_LPC1768 swSpiBegin(sclkPin, misoPin, mosiPin); spiSpeed = swSpiInit(spi_speed, sclkPin, mosiPin); #else spiDelay = (100UL << spi_speed) / 3; // Calculate delay in ns. Top speed is ~10MHz, or 100ns delay between bits. - OUT_WRITE(sclkPin, LOW); - SET_OUTPUT(mosiPin); - SET_INPUT(misoPin); + pinMode(sclkPin, OUTPUT); + digitalWrite(sclkPin, LOW); + pinMode(mosiPin, OUTPUT); + pinMode(misoPin, INPUT); #endif } diff --git a/Marlin/src/libs/MAX31865.h b/Marlin/src/libs/MAX31865.h index 7cd1f25c984e2..bc7733b835ecd 100644 --- a/Marlin/src/libs/MAX31865.h +++ b/Marlin/src/libs/MAX31865.h @@ -41,6 +41,8 @@ */ #pragma once +//#define DEBUG_MAX31865 + #include "../inc/MarlinConfig.h" #include "../HAL/shared/Delay.h" #include HAL_PATH(../HAL, MarlinSPI.h) @@ -84,6 +86,14 @@ typedef enum max31865_numwires { MAX31865_4WIRE = 0 } max31865_numwires_t; +#if DISABLED(MAX31865_USE_AUTO_MODE) + typedef enum one_shot_event : uint8_t { + SETUP_BIAS_VOLTAGE, + SETUP_1_SHOT_MODE, + READ_RTD_REG + } one_shot_event_t; +#endif + /* Interface class for the MAX31865 RTD Sensor reader */ class MAX31865 { private: @@ -97,7 +107,21 @@ class MAX31865 { uint16_t spiDelay; #endif - float zeroRes, refRes; + float zeroRes, refRes, wireRes; + + #if ENABLED(MAX31865_USE_READ_ERROR_DETECTION) + millis_t lastReadStamp = 0; + #endif + + uint16_t lastRead = 0; + uint8_t lastFault = 0; + + #if DISABLED(MAX31865_USE_AUTO_MODE) + millis_t nextEventStamp; + one_shot_event_t nextEvent; + #endif + + uint8_t stdFlags = 0; void setConfig(uint8_t config, bool enable); @@ -110,8 +134,15 @@ class MAX31865 { void softSpiBegin(const uint8_t spi_speed); + void initFixedFlags(max31865_numwires_t wires); + + void enable50HzFilter(bool b); + void enableBias(); + void oneShot(); + void resetFlags(); + public: - #ifdef LARGE_PINMAP + #if ENABLED(LARGE_PINMAP) MAX31865(uint32_t spi_cs, uint8_t pin_mapping); MAX31865(uint32_t spi_cs, uint32_t spi_mosi, uint32_t spi_miso, uint32_t spi_clk, uint8_t pin_mapping); @@ -121,17 +152,11 @@ class MAX31865 { int8_t spi_clk); #endif - void begin(max31865_numwires_t wires, float zero, float ref); + void begin(max31865_numwires_t wires, float zero_res, float ref_res, float wire_res); uint8_t readFault(); void clearFault(); - void setWires(max31865_numwires_t wires); - void autoConvert(bool b); - void enable50HzFilter(bool b); - void enableBias(bool b); - void oneShot(); - uint16_t readRaw(); float readResistance(); float temperature(); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 9d6c566ba0804..e068d4fca025b 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2202,11 +2202,8 @@ void Temperature::init() { #elif TEMP_SENSOR_IS_MAX(0, 31865) max31865_0.begin( MAX31865_WIRES(MAX31865_SENSOR_WIRES_0) // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE - OPTARG(LIB_INTERNAL_MAX31865, MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0) + OPTARG(LIB_INTERNAL_MAX31865, MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0, MAX31865_WIRE_OHMS_0) ); - #if defined(LIB_INTERNAL_MAX31865) && ENABLED(MAX31865_50HZ_FILTER) - max31865_0.enable50HzFilter(1); - #endif #endif #if TEMP_SENSOR_IS_MAX(1, 6675) && HAS_MAX6675_LIBRARY @@ -2216,11 +2213,8 @@ void Temperature::init() { #elif TEMP_SENSOR_IS_MAX(1, 31865) max31865_1.begin( MAX31865_WIRES(MAX31865_SENSOR_WIRES_1) // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE - OPTARG(LIB_INTERNAL_MAX31865, MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1) + OPTARG(LIB_INTERNAL_MAX31865, MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1, MAX31865_WIRE_OHMS_1) ); - #if defined(LIB_INTERNAL_MAX31865) && ENABLED(MAX31865_50HZ_FILTER) - max31865_1.enable50HzFilter(1); - #endif #endif #undef MAX31865_WIRES #undef _MAX31865_WIRES From a84e0404e019de905edfd9bbe61d35176c51c3c7 Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Thu, 9 Dec 2021 01:57:50 +0700 Subject: [PATCH 128/273] =?UTF-8?q?=F0=9F=9A=B8=20Onboard=20SD=20for=20SKR?= =?UTF-8?q?=202.0=20/=20SKR=20PRO=20(#23274)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h | 2 +- Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) 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 ac049baa2122b..1a1ac4ec2171a 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -309,7 +309,7 @@ // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION LCD + #define SDCARD_CONNECTION ONBOARD #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 bf3409210e0f2..d4e07bb8b782c 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 @@ -329,7 +329,7 @@ // SD Connection // #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION LCD + #define SDCARD_CONNECTION ONBOARD #endif /** From 65e52c1150b461f6458378c3f00bc3683c1bff62 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Wed, 8 Dec 2021 11:10:37 -0800 Subject: [PATCH 129/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20ACTION=5FITEM=20wi?= =?UTF-8?q?th=20nullptr=20(#23195)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/lcd/menu/menu_item.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index 56138a15bd6bb..624b9b303d080 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -55,7 +55,7 @@ class MenuItem_button : public MenuItemBase { class MenuItem_function : public MenuItem_button { public: //static inline void action(PGM_P const, const uint8_t, const menuAction_t func) { (*func)(); }; - static inline void action(PGM_P const, const menuAction_t func) { (*func)(); }; + static inline void action(PGM_P const, const menuAction_t func) { if (func) (*func)(); }; }; // GCODES_ITEM(LABEL, GCODES) From dfa1c26471f27e0fa81f1e7f7655a54efc50f77c Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Thu, 9 Dec 2021 02:15:31 +0700 Subject: [PATCH 130/273] =?UTF-8?q?=F0=9F=A9=B9=20Coerce=20pin=5Ft=20in=20?= =?UTF-8?q?set=5Fpwm=5Fduty=20macros=20(#23273)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/planner.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index cd8729edace94..0c62b11f5cf38 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1263,8 +1263,6 @@ void Planner::recalculate() { #if ENABLED(FAN_SOFT_PWM) #define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F); - #elif ENABLED(FAST_PWM_FAN) - #define _FAN_SET(F) set_pwm_duty(FAN##F##_PIN, CALC_FAN_SPEED(F)); #else #define _FAN_SET(F) set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); #endif From 135683010ac348c77f7a49202314b35f9aa8228d Mon Sep 17 00:00:00 2001 From: Sola <42537573+solawc@users.noreply.github.com> Date: Thu, 9 Dec 2021 03:37:45 +0800 Subject: [PATCH 131/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20MKS=20LVGL=20UI=20?= =?UTF-8?q?retraction=20(#23267)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp index 85894a5e9255a..0cacf90f36bd7 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_extrusion.cpp @@ -55,7 +55,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { if (event != LV_EVENT_RELEASED) return; switch (obj->mks_obj_id) { case ID_E_ADD: - if (thermalManager.degHotend(uiCfg.extruderIndex) >= EXTRUDE_MINTEMP) { + if (thermalManager.hotEnoughToExtrude(uiCfg.extruderIndex)) { sprintf_P((char *)public_buf_l, PSTR("G91\nG1 E%d F%d\nG90"), uiCfg.extruStep, 60 * uiCfg.extruSpeed); queue.inject(public_buf_l); extrudeAmount += uiCfg.extruStep; @@ -63,9 +63,9 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { } break; case ID_E_DEC: - if (thermalManager.degHotend(uiCfg.extruderIndex) >= EXTRUDE_MINTEMP) { + if (thermalManager.hotEnoughToExtrude(uiCfg.extruderIndex)) { sprintf_P((char *)public_buf_l, PSTR("G91\nG1 E%d F%d\nG90"), 0 - uiCfg.extruStep, 60 * uiCfg.extruSpeed); - queue.enqueue_one_now(public_buf_l); + queue.inject(public_buf_l); extrudeAmount -= uiCfg.extruStep; disp_extru_amount(); } From 4d45fdf0eb605629960d06abb86704cfbd62db49 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 8 Dec 2021 18:36:08 -0600 Subject: [PATCH 132/273] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20probe=20/=20ends?= =?UTF-8?q?top=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/endstops.cpp | 2 +- Marlin/src/module/probe.cpp | 12 ++++++------ 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 06cbb839cd38f..7c08456fa5fd0 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -564,7 +564,7 @@ void _O2 Endstops::report_states() { #if HAS_K_MAX ES_REPORT(K_MAX); #endif - #if BOTH(MARLIN_DEV_MODE, PROBE_ACTIVATION_SWITCH) + #if BOTH(PROBE_ACTIVATION_SWITCH) print_es_state(probe_switch_activated(), F(STR_PROBE_EN)); #endif #if USES_Z_MIN_PROBE_PIN diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 89a043d0f508e..7e08db7a5b6e3 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -496,10 +496,10 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { #if ENABLED(SENSORLESS_PROBING) sensorless_t stealth_states { false }; #if HAS_DELTA_SENSORLESS_PROBING - if (probe.test_sensitivity.x) stealth_states.x = tmc_enable_stallguard(stepperX); // Delta watches all DIAG pins for a stall - if (probe.test_sensitivity.y) stealth_states.y = tmc_enable_stallguard(stepperY); + if (test_sensitivity.x) stealth_states.x = tmc_enable_stallguard(stepperX); // Delta watches all DIAG pins for a stall + if (test_sensitivity.y) stealth_states.y = tmc_enable_stallguard(stepperY); #endif - if (probe.test_sensitivity.z) stealth_states.z = tmc_enable_stallguard(stepperZ); // All machines will check Z-DIAG for stall + if (test_sensitivity.z) stealth_states.z = tmc_enable_stallguard(stepperZ); // All machines will check Z-DIAG for stall endstops.enable(true); set_homing_current(true); // The "homing" current also applies to probing #endif @@ -524,10 +524,10 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { #if ENABLED(SENSORLESS_PROBING) endstops.not_homing(); #if HAS_DELTA_SENSORLESS_PROBING - if (probe.test_sensitivity.x) tmc_disable_stallguard(stepperX, stealth_states.x); - if (probe.test_sensitivity.y) tmc_disable_stallguard(stepperY, stealth_states.y); + if (test_sensitivity.x) tmc_disable_stallguard(stepperX, stealth_states.x); + if (test_sensitivity.y) tmc_disable_stallguard(stepperY, stealth_states.y); #endif - if (probe.test_sensitivity.z) tmc_disable_stallguard(stepperZ, stealth_states.z); + if (test_sensitivity.z) tmc_disable_stallguard(stepperZ, stealth_states.z); set_homing_current(false); #endif From 1ccaad7a9bc98b1afbb864ad50730a96fa944d17 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 9 Dec 2021 01:03:55 +0000 Subject: [PATCH 133/273] [cron] Bump distribution date (2021-12-09) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 258fd248817c7..efd25d331ca99 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 "2021-12-08" +//#define STRING_DISTRIBUTION_DATE "2021-12-09" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7139fe4c18a24..b1f459df2a7d0 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 "2021-12-08" + #define STRING_DISTRIBUTION_DATE "2021-12-09" #endif /** From c3af6bd8ce731737d0812a0e554e37dc0779127f Mon Sep 17 00:00:00 2001 From: Scott Alfter Date: Wed, 8 Dec 2021 23:18:04 -0800 Subject: [PATCH 134/273] Fix Endstops::report_states (#23280) Fix regression 4d45fdf0eb --- Marlin/src/module/endstops.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 7c08456fa5fd0..7a2cefdd4cea3 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -564,7 +564,7 @@ void _O2 Endstops::report_states() { #if HAS_K_MAX ES_REPORT(K_MAX); #endif - #if BOTH(PROBE_ACTIVATION_SWITCH) + #if ENABLED(PROBE_ACTIVATION_SWITCH) print_es_state(probe_switch_activated(), F(STR_PROBE_EN)); #endif #if USES_Z_MIN_PROBE_PIN From 1e637a8de2d2785e869d54897b0b2122410a0370 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 10 Dec 2021 01:04:24 +0000 Subject: [PATCH 135/273] [cron] Bump distribution date (2021-12-10) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index efd25d331ca99..3966933d3c54a 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 "2021-12-09" +//#define STRING_DISTRIBUTION_DATE "2021-12-10" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b1f459df2a7d0..a0e443bff42be 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 "2021-12-09" + #define STRING_DISTRIBUTION_DATE "2021-12-10" #endif /** From 0077d982cdbc414c60b2be8c7800317883ce6413 Mon Sep 17 00:00:00 2001 From: BigTreeTech <38851044+bigtreetech@users.noreply.github.com> Date: Sat, 11 Dec 2021 03:38:03 +0800 Subject: [PATCH 136/273] =?UTF-8?q?=E2=9C=A8=20BigTreeTech=20SKR=20mini=20?= =?UTF-8?q?E3=20V3.0=20(STM32G0B1RET6)=20(#23283)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/STM32/HAL.h | 6 +- Marlin/src/HAL/STM32/HAL_MinSerial.cpp | 2 +- Marlin/src/HAL/STM32/timers.cpp | 2 +- .../src/HAL/shared/backtrace/unwmemaccess.cpp | 2 +- .../shared/cpu_exception/exception_arm.cpp | 2 +- Marlin/src/core/boards.h | 67 +-- Marlin/src/module/stepper.cpp | 2 +- Marlin/src/pins/pins.h | 2 + .../stm32f1/pins_BTT_SKR_MINI_E3_common.h | 4 +- .../pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h | 332 ++++++++++++++ .../PlatformIO/boards/marlin_STM32G0B1RE.json | 47 ++ .../scripts/generic_create_variant.py | 2 +- .../STM32G0xx/MARLIN_G0B1RE/PeripheralPins.c | 428 ++++++++++++++++++ .../STM32G0xx/MARLIN_G0B1RE/PinNamesVar.h | 90 ++++ .../STM32G0xx/MARLIN_G0B1RE/ldscript.ld | 177 ++++++++ .../variant_MARLIN_STM32G0B1RE.cpp | 177 ++++++++ .../variant_MARLIN_STM32G0B1RE.h | 199 ++++++++ ini/stm32g0.ini | 39 ++ platformio.ini | 1 + 19 files changed, 1539 insertions(+), 42 deletions(-) create mode 100644 Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h create mode 100644 buildroot/share/PlatformIO/boards/marlin_STM32G0B1RE.json create mode 100644 buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/PeripheralPins.c create mode 100644 buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/PinNamesVar.h create mode 100644 buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/ldscript.ld create mode 100644 buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/variant_MARLIN_STM32G0B1RE.cpp create mode 100644 buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/variant_MARLIN_STM32G0B1RE.h create mode 100644 ini/stm32g0.ini diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index a68e8a8c0e4af..adaf14223f324 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -130,7 +130,11 @@ // Types // ------------------------ -typedef int16_t pin_t; +#ifdef STM32G0B1xx + typedef int32_t pin_t; +#else + typedef int16_t pin_t; +#endif #define HAL_SERVO_LIB libServo #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() diff --git a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp index 29826a890de41..b6e86b72daa91 100644 --- a/Marlin/src/HAL/STM32/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/STM32/HAL_MinSerial.cpp @@ -135,7 +135,7 @@ void install_min_serial() { HAL_min_serial_out = &TX; } -#if DISABLED(DYNAMIC_VECTORTABLE) && DISABLED(STM32F0xx) // Cortex M0 can't jump to a symbol that's too far from the current function, so we work around this in exception_arm.cpp +#if NONE(DYNAMIC_VECTORTABLE, STM32F0xx, STM32G0xx) // Cortex M0 can't jump to a symbol that's too far from the current function, so we work around this in exception_arm.cpp extern "C" { __attribute__((naked)) void JumpHandler_ASM() { __asm__ __volatile__ ( diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index 53a1f2a8e97be..fe27ca101677e 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -67,7 +67,7 @@ #endif #endif -#ifdef STM32F0xx +#if defined(STM32F0xx) || defined(STM32G0xx) #define MCU_STEP_TIMER 16 #define MCU_TEMP_TIMER 17 #elif defined(STM32F1xx) diff --git a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp index 2bde1e208d956..a4151b38c20e2 100644 --- a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp @@ -41,7 +41,7 @@ #define START_FLASH_ADDR 0x00000000 #define END_FLASH_ADDR 0x00080000 -#elif defined(__STM32F1__) || defined(STM32F1xx) || defined(STM32F0xx) +#elif defined(__STM32F1__) || defined(STM32F1xx) || defined(STM32F0xx) || defined(STM32G0xx) // For STM32F103ZET6/STM32F103VET6/STM32F0xx // SRAM (0x20000000 - 0x20010000) (64kb) diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp index 0f0f7c4807273..a106ed2b05e55 100644 --- a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp +++ b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp @@ -101,7 +101,7 @@ struct __attribute__((packed)) ContextSavedFrame { uint32_t ELR; }; -#if DISABLED(STM32F0xx) +#if NONE(STM32F0xx, STM32G0xx) extern "C" __attribute__((naked)) void CommonHandler_ASM() { __asm__ __volatile__ ( diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 9483d6322aeea..2fc08c8cc7c40 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -324,39 +324,40 @@ #define BOARD_BTT_SKR_MINI_E3_V1_0 4024 // BigTreeTech SKR Mini E3 (STM32F103RC) #define BOARD_BTT_SKR_MINI_E3_V1_2 4025 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) #define BOARD_BTT_SKR_MINI_E3_V2_0 4026 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC / STM32F103RE) -#define BOARD_BTT_SKR_MINI_MZ_V1_0 4027 // BigTreeTech SKR Mini MZ V1.0 (STM32F103RC) -#define BOARD_BTT_SKR_E3_DIP 4028 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) -#define BOARD_BTT_SKR_CR6 4029 // BigTreeTech SKR CR6 v1.0 (STM32F103RE) -#define BOARD_JGAURORA_A5S_A1 4030 // JGAurora A5S A1 (STM32F103ZET6) -#define BOARD_FYSETC_AIO_II 4031 // FYSETC AIO_II -#define BOARD_FYSETC_CHEETAH 4032 // FYSETC Cheetah -#define BOARD_FYSETC_CHEETAH_V12 4033 // FYSETC Cheetah V1.2 -#define BOARD_LONGER3D_LK 4034 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6 -#define BOARD_CCROBOT_MEEB_3DP 4035 // ccrobot-online.com MEEB_3DP (STM32F103RC) -#define BOARD_CHITU3D_V5 4036 // Chitu3D TronXY X5SA V5 Board -#define BOARD_CHITU3D_V6 4037 // Chitu3D TronXY X5SA V6 Board -#define BOARD_CHITU3D_V9 4038 // Chitu3D TronXY X5SA V9 Board -#define BOARD_CREALITY_V4 4039 // Creality v4.x (STM32F103RE) -#define BOARD_CREALITY_V427 4040 // Creality v4.2.7 (STM32F103RE) -#define BOARD_CREALITY_V4210 4041 // Creality v4.2.10 (STM32F103RE) as found in the CR-30 -#define BOARD_CREALITY_V431 4042 // Creality v4.3.1 (STM32F103RE) -#define BOARD_CREALITY_V431_A 4043 // Creality v4.3.1a (STM32F103RE) -#define BOARD_CREALITY_V431_B 4044 // Creality v4.3.1b (STM32F103RE) -#define BOARD_CREALITY_V431_C 4045 // Creality v4.3.1c (STM32F103RE) -#define BOARD_CREALITY_V431_D 4046 // Creality v4.3.1d (STM32F103RE) -#define BOARD_CREALITY_V452 4047 // Creality v4.5.2 (STM32F103RE) -#define BOARD_CREALITY_V453 4048 // Creality v4.5.3 (STM32F103RE) -#define BOARD_CREALITY_V24S1 4049 // Creality v2.4.S1 (STM32F103RE) v101 as found in the Ender 7 -#define BOARD_TRIGORILLA_PRO 4050 // Trigorilla Pro (STM32F103ZET6) -#define BOARD_FLY_MINI 4051 // FLYmaker FLY MINI (STM32F103RCT6) -#define BOARD_FLSUN_HISPEED 4052 // FLSUN HiSpeedV1 (STM32F103VET6) -#define BOARD_BEAST 4053 // STM32F103RET6 Libmaple-based controller -#define BOARD_MINGDA_MPX_ARM_MINI 4054 // STM32F103ZET6 Mingda MD-16 -#define BOARD_GTM32_PRO_VD 4055 // STM32F103VET6 controller -#define BOARD_ZONESTAR_ZM3E2 4056 // Zonestar ZM3E2 (STM32F103RCT6) -#define BOARD_ZONESTAR_ZM3E4 4057 // Zonestar ZM3E4 V1 (STM32F103VCT6) -#define BOARD_ZONESTAR_ZM3E4V2 4058 // Zonestar ZM3E4 V2 (STM32F103VCT6) -#define BOARD_ERYONE_ERY32_MINI 4059 // Eryone Ery32 mini (STM32F103VET6) +#define BOARD_BTT_SKR_MINI_E3_V3_0 4027 // BigTreeTech SKR Mini E3 V3.0 (STM32G0B1RE) +#define BOARD_BTT_SKR_MINI_MZ_V1_0 4028 // BigTreeTech SKR Mini MZ V1.0 (STM32F103RC) +#define BOARD_BTT_SKR_E3_DIP 4029 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) +#define BOARD_BTT_SKR_CR6 4030 // BigTreeTech SKR CR6 v1.0 (STM32F103RE) +#define BOARD_JGAURORA_A5S_A1 4031 // JGAurora A5S A1 (STM32F103ZET6) +#define BOARD_FYSETC_AIO_II 4032 // FYSETC AIO_II +#define BOARD_FYSETC_CHEETAH 4033 // FYSETC Cheetah +#define BOARD_FYSETC_CHEETAH_V12 4034 // FYSETC Cheetah V1.2 +#define BOARD_LONGER3D_LK 4035 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6 +#define BOARD_CCROBOT_MEEB_3DP 4036 // ccrobot-online.com MEEB_3DP (STM32F103RC) +#define BOARD_CHITU3D_V5 4037 // Chitu3D TronXY X5SA V5 Board +#define BOARD_CHITU3D_V6 4038 // Chitu3D TronXY X5SA V6 Board +#define BOARD_CHITU3D_V9 4039 // Chitu3D TronXY X5SA V9 Board +#define BOARD_CREALITY_V4 4040 // Creality v4.x (STM32F103RE) +#define BOARD_CREALITY_V427 4041 // Creality v4.2.7 (STM32F103RE) +#define BOARD_CREALITY_V4210 4042 // Creality v4.2.10 (STM32F103RE) as found in the CR-30 +#define BOARD_CREALITY_V431 4043 // Creality v4.3.1 (STM32F103RE) +#define BOARD_CREALITY_V431_A 4044 // Creality v4.3.1a (STM32F103RE) +#define BOARD_CREALITY_V431_B 4045 // Creality v4.3.1b (STM32F103RE) +#define BOARD_CREALITY_V431_C 4046 // Creality v4.3.1c (STM32F103RE) +#define BOARD_CREALITY_V431_D 4047 // Creality v4.3.1d (STM32F103RE) +#define BOARD_CREALITY_V452 4048 // Creality v4.5.2 (STM32F103RE) +#define BOARD_CREALITY_V453 4049 // Creality v4.5.3 (STM32F103RE) +#define BOARD_CREALITY_V24S1 4050 // Creality v2.4.S1 (STM32F103RE) v101 as found in the Ender 7 +#define BOARD_TRIGORILLA_PRO 4051 // Trigorilla Pro (STM32F103ZET6) +#define BOARD_FLY_MINI 4052 // FLYmaker FLY MINI (STM32F103RCT6) +#define BOARD_FLSUN_HISPEED 4053 // FLSUN HiSpeedV1 (STM32F103VET6) +#define BOARD_BEAST 4054 // STM32F103RET6 Libmaple-based controller +#define BOARD_MINGDA_MPX_ARM_MINI 4055 // STM32F103ZET6 Mingda MD-16 +#define BOARD_GTM32_PRO_VD 4056 // STM32F103VET6 controller +#define BOARD_ZONESTAR_ZM3E2 4057 // Zonestar ZM3E2 (STM32F103RCT6) +#define BOARD_ZONESTAR_ZM3E4 4058 // Zonestar ZM3E4 V1 (STM32F103VCT6) +#define BOARD_ZONESTAR_ZM3E4V2 4059 // Zonestar ZM3E4 V2 (STM32F103VCT6) +#define BOARD_ERYONE_ERY32_MINI 4060 // Eryone Ery32 mini (STM32F103VET6) // // ARM Cortex-M4F diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index b93dd21198d92..c100051f98087 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1380,7 +1380,7 @@ void Stepper::set_directions() { } FORCE_INLINE int32_t Stepper::_eval_bezier_curve(const uint32_t curr_step) { - #if defined(__arm__) || defined(__thumb__) + #if (defined(__arm__) || defined(__thumb__)) && !defined(STM32G0B1xx) // TODO: Test define STM32G0xx versus STM32G0B1xx // For ARM Cortex M3/M4 CPUs, we have the optimized assembler version, that takes 43 cycles to execute uint32_t flo = 0; diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 59e06333078ec..3ffb2d26b7c26 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -527,6 +527,8 @@ #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_MINI_E3_V2_0) #include "stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple +#elif MB(BTT_SKR_MINI_E3_V3_0) + #include "stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h" // STM32G0 env:STM32G0B1RE_btt #elif MB(BTT_SKR_MINI_MZ_V1_0) #include "stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_E3_DIP) 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 c132691c2090f..8c8043be8b2ad 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 @@ -206,7 +206,7 @@ /** * TFTGLCD_PANEL_SPI display pinout * - * Board Display + * Board Display * ------ ------ * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) LCD_CS | 3 4 | SD_CS (PA10) @@ -249,7 +249,7 @@ /** * FYSETC TFT TFT81050 display pinout * - * Board Display + * Board Display * ------ ------ * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) 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 new file mode 100644 index 0000000000000..2fda0fb2c0c26 --- /dev/null +++ b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h @@ -0,0 +1,332 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +//#define BOARD_CUSTOM_BUILD_FLAGS -DTONE_CHANNEL=4 -DTONE_TIMER=4 -DTIMER_TONE=4 + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "BTT SKR Mini E3 V3.0" +#endif + +#define USES_DIAG_JUMPERS + +// Ignore temp readings during development. +//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 + +#define LED_PIN PD8 + +// Onboard I2C EEPROM +#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) + #undef NO_EEPROM_SELECTED + #define I2C_EEPROM + #define SOFT_I2C_EEPROM // Force the use of Software I2C + #define I2C_SCL_PIN PB6 + #define I2C_SDA_PIN PB7 + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif + +// +// Servos +// +#define SERVO0_PIN PA1 // SERVOS + +// +// Limit Switches +// +#define X_STOP_PIN PC0 // X-STOP +#define Y_STOP_PIN PC1 // Y-STOP +#define Z_STOP_PIN PC2 // Z-STOP + +// +// Z Probe must be this pin +// +#define Z_MIN_PROBE_PIN PC14 // PROBE + +// +// Filament Runout Sensor +// +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PC15 // E0-STOP +#endif + +// +// Power-loss Detection +// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PC12 // Power Loss Detection: PWR-DET +#endif + +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PA8 // LED driving pin +#endif + +#ifndef PS_ON_PIN + #define PS_ON_PIN PC13 // Power Supply Control +#endif + +// +// Steppers +// +#define X_ENABLE_PIN PB14 +#define X_STEP_PIN PB13 +#define X_DIR_PIN PB12 + +#define Y_ENABLE_PIN PB11 +#define Y_STEP_PIN PB10 +#define Y_DIR_PIN PB2 + +#define Z_ENABLE_PIN PB1 +#define Z_STEP_PIN PB0 +#define Z_DIR_PIN PC5 + +#define E0_ENABLE_PIN PD1 +#define E0_STEP_PIN PB3 +#define E0_DIR_PIN PB4 + +#if HAS_TMC_UART + /** + * TMC220x stepper drivers + * Hardware serial communication ports + */ + #define X_HARDWARE_SERIAL MSerial4 + #define Y_HARDWARE_SERIAL MSerial4 + #define Z_HARDWARE_SERIAL MSerial4 + #define E0_HARDWARE_SERIAL MSerial4 + + // Default TMC slave addresses + #ifndef X_SLAVE_ADDRESS + #define X_SLAVE_ADDRESS 0 + #endif + #ifndef Y_SLAVE_ADDRESS + #define Y_SLAVE_ADDRESS 2 + #endif + #ifndef Z_SLAVE_ADDRESS + #define Z_SLAVE_ADDRESS 1 + #endif + #ifndef E0_SLAVE_ADDRESS + #define E0_SLAVE_ADDRESS 3 + #endif +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN PA0 // Analog Input "TH0" +#define TEMP_BED_PIN PC4 // Analog Input "TB0" + +// +// Heaters / Fans +// +#define HEATER_0_PIN PC8 // "HE" +#define HEATER_BED_PIN PC9 // "HB" +#define FAN_PIN PC6 // "FAN0" +#define FAN1_PIN PC7 // "FAN1" +#define FAN2_PIN PB15 // "FAN2" + +/** + * SKR Mini E3 V3.0 + * ------ + * 5V | 1 2 | GND + * (LCD_EN) PD6 | 3 4 | PB8 (LCD_RS) + * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) + * RESET | 7 8 | PA9 (BTN_EN1) + * (BTN_ENC) PA15 | 9 10 | PB5 (BEEPER) + * ------ + * EXP1 + */ +#define EXP1_09_PIN PA15 +#define EXP1_03_PIN PD6 + +#if EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) + /** + * ------ ------ ------ + * VCC | 1 2 | GND VCC | 1 2 | GND GND | 2 1 | VCC + * A | 3 4 | B A | 3 4 | B B | 4 3 | A + * | 5 6 TX BEEP | 5 6 ENT ENT | 6 5 | BEEP + * | 7 8 | RX TX | 7 8 | RX RX | 8 7 | TX + * BEEP | 9 10 | ENT | 9 10 | | 10 9 | + * ------ ------ ------ + * EXP1 DWIN DWIN (plug) + * + * All pins are labeled as printed on DWIN PCB. Connect TX-TX, A-A and so on. + */ + + #error "DWIN_CREALITY_LCD requires a custom cable, see diagram above this line. Comment out this line to continue." + + #define BEEPER_PIN EXP1_09_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 PB8 + #define BTN_ENC PB5 + +#elif HAS_WIRED_LCD + + #if ENABLED(CR10_STOCKDISPLAY) + + #define BEEPER_PIN PB5 + #define BTN_ENC EXP1_09_PIN + + #define BTN_EN1 PA9 + #define BTN_EN2 PA10 + + #define LCD_PINS_RS PB8 + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 PB9 + + #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! + + #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + + #define LCD_PINS_RS PB9 + #define LCD_PINS_ENABLE EXP1_09_PIN + #define LCD_PINS_D4 PB8 + #define LCD_PINS_D5 PA10 + #define LCD_PINS_D6 PA9 + #define LCD_PINS_D7 PB5 + #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! + + #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + + #define BTN_ENC EXP1_09_PIN + #define BTN_EN1 PA9 + #define BTN_EN2 PA10 + + #define DOGLCD_CS PB8 + #define DOGLCD_A0 PB9 + #define DOGLCD_SCK PB5 + #define DOGLCD_MOSI EXP1_03_PIN + + #define FORCE_SOFT_SPI + #define LCD_BACKLIGHT_PIN -1 + + #elif IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + + #error "CAUTION! TFTGLCD_PANEL_SPI requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + + /** + * TFTGLCD_PANEL_SPI display pinout + * + * Board Display + * ------ ------ + * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) + * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) LCD_CS | 3 4 | SD_CS (PA10) + * (FREE) PB9 | 5 6 | PA10 (SD_CS) (FREE) | 5 6 | MOSI (SPI1-MOSI) + * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | (FREE) + * (BEEPER) PB6 | 9 10 | PB5 (SD_DET) GND | 9 10 | 5V + * ------ ------ + * EXP1 EXP1 + * + * Needs custom cable: + * + * Board Display + * + * EXP1-1 ----------- EXP1-10 + * EXP1-2 ----------- EXP1-9 + * SPI1-4 ----------- EXP1-6 + * EXP1-4 ----------- FREE + * SPI1-3 ----------- EXP1-2 + * EXP1-6 ----------- EXP1-4 + * EXP1-7 ----------- FREE + * EXP1-8 ----------- EXP1-3 + * SPI1-1 ----------- EXP1-1 + * EXP1-10 ----------- EXP1-7 + */ + + #define TFTGLCD_CS PA9 + + #endif + + #else + #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, and TFTGLCD_PANEL_(SPI|I2C) are currently supported on the BIGTREE_SKR_MINI_E3." + #endif + +#endif // HAS_WIRED_LCD + +#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) + + #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + + /** + * FYSETC TFT TFT81050 display pinout + * + * Board Display + * ------ ------ + * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) + * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) + * (FREE) PB9 | 5 6 | PA10 (SD_CS) (PB8) LCD_CS | 5 6 | MOSI (SPI1-MOSI) + * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | RESET + * (BEEPER) PB6 | 9 10 | PB5 (SD_DET) GND | 9 10 | 5V + * ------ ------ + * EXP1 EXP1 + * + * Needs custom cable: + * + * Board Adapter Display + * _________ + * EXP1-1 ----------- EXP1-10 + * EXP1-2 ----------- EXP1-9 + * SPI1-4 ----------- EXP1-6 + * EXP1-4 ----------- EXP1-5 + * SPI1-3 ----------- EXP1-2 + * EXP1-6 ----------- EXP1-4 + * EXP1-7 ----------- EXP1-8 + * EXP1-8 ----------- EXP1-3 + * SPI1-1 ----------- EXP1-1 + * EXP1-10 ----------- EXP1-7 + */ + + #define CLCD_SPI_BUS 1 // SPI1 connector + + #define BEEPER_PIN EXP1_09_PIN + + #define CLCD_MOD_RESET PA9 + #define CLCD_SPI_CS PB8 + +#endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 + +// +// SD Support +// + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#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) + #define SD_DETECT_PIN PB5 + #define SD_SS_PIN PA10 +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "SD CUSTOM_CABLE is not compatible with SKR Mini E3." +#endif + +#define ONBOARD_SPI_DEVICE 1 // SPI1 -> used only by HAL/STM32F1... +#define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card + +#define ENABLE_SPI1 +#define SDSS ONBOARD_SD_CS_PIN +#define SD_SS_PIN ONBOARD_SD_CS_PIN +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32G0B1RE.json b/buildroot/share/PlatformIO/boards/marlin_STM32G0B1RE.json new file mode 100644 index 0000000000000..86f632f53b8d8 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_STM32G0B1RE.json @@ -0,0 +1,47 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m0plus", + "extra_flags": "-DSTM32G0xx -DSTM32G0B1xx", + "f_cpu": "64000000L", + "framework_extra_flags": { + "arduino": "-D__CORTEX_SC=0" + }, + "mcu": "stm32g0b1ret6", + "product_line": "STM32G0B1xx", + "variant": "STM32G0xx/MARLIN_G0B1RE" + }, + "debug": { + "default_tools": [ + "stlink" + ], + "jlink_device": "STM32G0B1RE", + "onboard_tools": [ + "stlink" + ], + "openocd_target": "stm32g0x", + "svd_path": "STM32G0B1.svd" + }, + "frameworks": [ + "arduino", + "cmsis", + "libopencm3", + "stm32cube", + "zephyr" + ], + "name": "STM32G0B1RE", + "upload": { + "maximum_ram_size": 147456, + "maximum_size": 524288, + "protocol": "stlink", + "protocols": [ + "stlink", + "jlink", + "cmsis-dap", + "blackmagic", + "mbed" + ] + }, + "url": "https://www.st.com/content/st_com/en/products/microcontrollers-microprocessors/stm32-32-bit-arm-cortex-mcus/stm32-mainstream-mcus/stm32g0-series/stm32g0x1.html", + "vendor": "ST" +} diff --git a/buildroot/share/PlatformIO/scripts/generic_create_variant.py b/buildroot/share/PlatformIO/scripts/generic_create_variant.py index 06929e0504e9d..d572873ad7649 100644 --- a/buildroot/share/PlatformIO/scripts/generic_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -30,7 +30,7 @@ else: platform_name = PackageSpec(platform_packages[0]).name - if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "usb-host-msc-cdc-msc-2", "usb-host-msc-cdc-msc-3", "tool-stm32duino", "biqu-bx-workaround" ]: + if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "usb-host-msc-cdc-msc-2", "usb-host-msc-cdc-msc-3", "tool-stm32duino", "biqu-bx-workaround", "main" ]: platform_name = "framework-arduinoststm32" FRAMEWORK_DIR = platform.get_package_dir(platform_name) diff --git a/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/PeripheralPins.c b/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/PeripheralPins.c new file mode 100644 index 0000000000000..0abfc70700d84 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/PeripheralPins.c @@ -0,0 +1,428 @@ +/* + ******************************************************************************* + * 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 + * + ******************************************************************************* + */ +/* + * Automatically generated from STM32G0B1R(B-C-E)IxN.xml, STM32G0B1R(B-C-E)TxN.xml + * STM32G0C1R(C-E)IxN.xml, STM32G0C1R(C-E)TxN.xml + * CubeMX DB release 6.0.30 + */ +#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, 0, 0)}, // ADC1_IN0 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 + {PB_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 + {PB_10, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 + {PB_11, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 + {PB_12, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 16, 0)}, // ADC1_IN16 + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 17, 0)}, // ADC1_IN17 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 18, 0)}, // ADC1_IN18 + {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[] = { + {PA_6, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)}, + {PA_6_ALT1, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF9_I2C3)}, + {PA_10, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)}, + {PA_10_ALT1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)}, + {PA_10_R, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)}, + {PA_10_R_ALT1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)}, + {PA_12, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C2)}, + {PB_4, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)}, + {PB_4_ALT1, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C3)}, + {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)}, + {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)}, + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C2)}, + {PB_14, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C2)}, + {PC_1, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C3)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SCL[] = { + {PA_7, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)}, + {PA_7_ALT1, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF9_I2C3)}, + {PA_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)}, + {PA_9_ALT1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)}, + {PA_9_R, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)}, + {PA_9_R_ALT1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)}, + {PA_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C2)}, + {PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF8_I2C2)}, + {PB_3_ALT1, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C3)}, + {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)}, + {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C1)}, + {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C2)}, + {PB_13, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C2)}, + {PC_0, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C3)}, + {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_AF2_TIM2, 1, 0)}, // TIM2_CH1 + {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 2, 0)}, // TIM2_CH2 + {PA_1_ALT1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 1, 1)}, // TIM15_CH1N + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 3, 0)}, // TIM2_CH3 + {PA_2_ALT1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 1, 0)}, // TIM15_CH1 + {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 4, 0)}, // TIM2_CH4 + {PA_3_ALT1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 2, 0)}, // TIM15_CH2 + {PA_4, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM14, 1, 0)}, // TIM14_CH1 + {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 1, 0)}, // TIM2_CH1 + {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 1, 0)}, // TIM3_CH1 + {PA_6_ALT1, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM16, 1, 0)}, // TIM16_CH1 + {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 1, 1)}, // TIM1_CH1N + {PA_7_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 2, 0)}, // TIM3_CH2 + {PA_7_ALT2, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM14, 1, 0)}, // TIM14_CH1 + {PA_7_ALT3, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM17, 1, 0)}, // TIM17_CH1 + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 2, 0)}, // TIM1_CH2 + {PA_9_R, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 3, 0)}, // TIM1_CH3 + {PA_10_R, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 3, 0)}, // TIM1_CH3 + {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 4, 0)}, // TIM1_CH4 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 1, 0)}, // TIM2_CH1 + {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 2, 1)}, // TIM1_CH2N + {PB_0_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 3, 0)}, // TIM3_CH3 + {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 3, 1)}, // TIM1_CH3N + {PB_1_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 4, 0)}, // TIM3_CH4 + {PB_1_ALT2, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_TIM14, 1, 0)}, // TIM14_CH1 + {PB_3, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PB_3_ALT1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 2, 0)}, // TIM2_CH2 + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 1, 0)}, // TIM3_CH1 + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 2, 0)}, // TIM3_CH2 + {PB_6, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PB_6_ALT1, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM4, 1, 0)}, // TIM4_CH1 + {PB_6_ALT2, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM16, 1, 1)}, // TIM16_CH1N + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM4, 2, 0)}, // TIM4_CH2 + {PB_7_ALT1, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM17, 1, 1)}, // TIM17_CH1N + {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM4, 3, 0)}, // TIM4_CH3 + {PB_8_ALT1, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM16, 1, 0)}, // TIM16_CH1 + {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM4, 4, 0)}, // TIM4_CH4 + {PB_9_ALT1, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM17, 1, 0)}, // TIM17_CH1 + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 3, 0)}, // TIM2_CH3 + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 4, 0)}, // TIM2_CH4 + {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 1, 1)}, // TIM1_CH1N + {PB_13_ALT1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 1, 1)}, // TIM15_CH1N + {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 2, 1)}, // TIM1_CH2N + {PB_14_ALT1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 1, 0)}, // TIM15_CH1 + {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 3, 1)}, // TIM1_CH3N + {PB_15_ALT1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 1)}, // TIM15_CH1N + {PB_15_ALT2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 2, 0)}, // TIM15_CH2 + {PC_1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM15, 1, 0)}, // TIM15_CH1 + {PC_2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM15, 2, 0)}, // TIM15_CH2 + {PC_4, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 1, 0)}, // TIM2_CH1 + {PC_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 2, 0)}, // TIM2_CH2 + {PC_6, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 3, 0)}, // TIM2_CH3 + {PC_6_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 1, 0)}, // TIM3_CH1 + {PC_7, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 4, 0)}, // TIM2_CH4 + {PC_7_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 2, 0)}, // TIM3_CH2 + {PC_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 1, 0)}, // TIM1_CH1 + {PC_8_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 3, 0)}, // TIM3_CH3 + {PC_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 2, 0)}, // TIM1_CH2 + {PC_9_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 4, 0)}, // TIM3_CH4 + {PC_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 3, 0)}, // TIM1_CH3 + {PC_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 4, 0)}, // TIM1_CH4 + {PC_12, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM14, 1, 0)}, // TIM14_CH1 + {PD_0, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM16, 1, 0)}, // TIM16_CH1 + {PD_1, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM17, 1, 0)}, // TIM17_CH1 + {PD_2, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 1, 1)}, // TIM1_CH1N + {PD_3, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 2, 1)}, // TIM1_CH2N + {PD_4, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 3, 1)}, // TIM1_CH3N + {PF_0, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM14, 1, 0)}, // TIM14_CH1 + {PF_1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM15, 1, 1)}, // TIM15_CH1N + {NC, NP, 0} +}; +#endif + +//*** UART *** + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_TX[] = { + {PA_0, USART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART4)}, + {PA_2, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_LPUART1)}, + {PA_2_ALT1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART2)}, + {PA_4, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART6)}, + {PA_5, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)}, + {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)}, + {PA_9_R, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)}, + {PA_14, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_LPUART2)}, + {PA_14_ALT1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART2)}, + {PB_0, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART5)}, + {PB_2, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)}, + {PB_3, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART5)}, + {PB_6, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_LPUART2)}, + {PB_6_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART1)}, + {PB_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)}, + {PB_8_ALT1, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)}, + {PB_11, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_LPUART1)}, + {PC_0, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART2)}, + {PC_0_ALT1, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART6)}, + {PC_1, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_LPUART1)}, + {PC_4, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)}, + {PC_4_ALT1, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART3)}, + {PC_6, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART2)}, + {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART3)}, + {PC_10_ALT1, USART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART4)}, + {PC_12, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART5)}, + {PD_3, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART5)}, + {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART2)}, + {PF_2, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_LPUART2)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_RX[] = { + {PA_1, USART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART4)}, + {PA_3, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_LPUART1)}, + {PA_3_ALT1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART2)}, + {PA_5, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART6)}, + {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)}, + {PA_10_R, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)}, + {PA_13, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_LPUART2)}, + {PA_15, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART2)}, + {PB_0, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)}, + {PB_1, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART5)}, + {PB_4, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART5)}, + {PB_7, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_LPUART2)}, + {PB_7_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART1)}, + {PB_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)}, + {PB_9_ALT1, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PB_10, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_LPUART1)}, + {PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)}, + {PC_0, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_LPUART1)}, + {PC_1, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART2)}, + {PC_1_ALT1, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART6)}, + {PC_5, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)}, + {PC_5_ALT1, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART3)}, + {PC_7, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART2)}, + {PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART3)}, + {PC_11_ALT1, USART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART4)}, + {PD_2, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART5)}, + {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART2)}, + {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_AF1_USART2)}, + {PA_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART6)}, + {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)}, + {PA_15, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_USART3)}, + {PA_15_ALT1, USART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART4)}, + {PB_1, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_LPUART1)}, + {PB_1_ALT1, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_LPUART2)}, + {PB_1_ALT2, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)}, + {PB_3, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART1)}, + {PB_5, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART5)}, + {PB_12, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_LPUART1)}, + {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)}, + {PB_14_ALT1, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PC_9, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART2)}, + {PD_2, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART3)}, + {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART2)}, + {PD_4_ALT1, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART5)}, + {PF_2, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART2)}, + {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_AF1_USART2)}, + {PA_6, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_LPUART1)}, + {PA_6_ALT1, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)}, + {PA_6_ALT2, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART6)}, + {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_USART1)}, + {PB_0, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_LPUART2)}, + {PB_4, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART1)}, + {PB_6, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART5)}, + {PB_7, USART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART4)}, + {PB_13, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_LPUART1)}, + {PB_13_ALT1, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART3)}, + {PB_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, + {PC_8, LPUART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART2)}, + {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_USART2)}, + {PD_5, USART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_USART5)}, + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MOSI[] = { + {PA_2, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {PA_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)}, + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {PA_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)}, + {PA_10_R, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)}, + {PA_12, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {PB_5_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SPI3)}, + {PB_7, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)}, + {PB_11, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)}, + {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)}, + {PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)}, + {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_SPI3)}, + {PD_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)}, + {PD_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI1)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MISO[] = { + {PA_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)}, + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_SPI2)}, + {PA_9_R, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_SPI2)}, + {PA_11, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {PB_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)}, + {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {PB_4_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SPI3)}, + {PB_6, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_SPI2)}, + {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)}, + {PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)}, + {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_SPI3)}, + {PD_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)}, + {PD_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI1)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_SCLK[] = { + {PA_0, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)}, + {PA_1, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {PB_3_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SPI3)}, + {PB_8, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)}, + {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_AF0_SPI2)}, + {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_SPI3)}, + {PD_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_SSEL[] = { + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {PA_4_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SPI3)}, + {PA_8, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)}, + {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {PA_15_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SPI3)}, + {PB_0, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, + {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_AF0_SPI2)}, + {PD_0, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_SPI2)}, + {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_AF3_FDCAN1)}, + {PB_0, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)}, + {PB_5, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)}, + {PB_8, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN1)}, + {PB_12, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)}, + {PC_2, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)}, + {PC_4, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN1)}, + {PD_0, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN1)}, + {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_AF3_FDCAN1)}, + {PB_1, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)}, + {PB_6, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)}, + {PB_9, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN1)}, + {PB_13, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)}, + {PC_3, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN2)}, + {PC_5, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN1)}, + {PD_1, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF3_FDCAN1)}, + {NC, NP, 0} +}; +#endif + +//*** No ETHERNET *** + +//*** No QUADSPI *** + +//*** USB *** + +#if defined(HAL_PCD_MODULE_ENABLED) || defined(HAL_HCD_MODULE_ENABLED) +WEAK const PinMap PinMap_USB_DRD_FS[] = { + // {PA_4, USB_DRD_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_USB)}, // USB_NOE + {PA_11, USB_DRD_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_DM + {PA_12, USB_DRD_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_DP + // {PA_13, USB_DRD_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_USB)}, // USB_NOE + // {PA_15, USB_DRD_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_USB)}, // USB_NOE + // {PC_9, USB_DRD_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_USB)}, // USB_NOE + {NC, NP, 0} +}; +#endif + +//*** No SD *** + +#endif /* !CUSTOM_PERIPHERAL_PINS */ diff --git a/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/PinNamesVar.h b/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/PinNamesVar.h new file mode 100644 index 0000000000000..9fc0b87c9015d --- /dev/null +++ b/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/PinNamesVar.h @@ -0,0 +1,90 @@ +/* Remap pin name */ +PA_9_R = PA_9 | PREMAP, +PA_10_R = PA_10 | PREMAP, + +/* Alternate pin name */ +PA_1_ALT1 = PA_1 | ALT1, +PA_2_ALT1 = PA_2 | ALT1, +PA_3_ALT1 = PA_3 | ALT1, +PA_4_ALT1 = PA_4 | ALT1, +PA_6_ALT1 = PA_6 | ALT1, +PA_6_ALT2 = PA_6 | ALT2, +PA_7_ALT1 = PA_7 | ALT1, +PA_7_ALT2 = PA_7 | ALT2, +PA_7_ALT3 = PA_7 | ALT3, +PA_9_ALT1 = PA_9 | ALT1, +PA_9_R_ALT1 = PA_9_R | ALT1, +PA_10_ALT1 = PA_10 | ALT1, +PA_10_R_ALT1 = PA_10_R | ALT1, +PA_14_ALT1 = PA_14 | ALT1, +PA_15_ALT1 = PA_15 | ALT1, +PB_0_ALT1 = PB_0 | ALT1, +PB_1_ALT1 = PB_1 | ALT1, +PB_1_ALT2 = PB_1 | ALT2, +PB_3_ALT1 = PB_3 | ALT1, +PB_4_ALT1 = PB_4 | ALT1, +PB_5_ALT1 = PB_5 | ALT1, +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_9_ALT1 = PB_9 | ALT1, +PB_13_ALT1 = PB_13 | ALT1, +PB_14_ALT1 = PB_14 | ALT1, +PB_15_ALT1 = PB_15 | ALT1, +PB_15_ALT2 = PB_15 | ALT2, +PC_0_ALT1 = PC_0 | ALT1, +PC_1_ALT1 = PC_1 | ALT1, +PC_4_ALT1 = PC_4 | ALT1, +PC_5_ALT1 = PC_5 | ALT1, +PC_6_ALT1 = PC_6 | ALT1, +PC_7_ALT1 = PC_7 | ALT1, +PC_8_ALT1 = PC_8 | ALT1, +PC_9_ALT1 = PC_9 | ALT1, +PC_10_ALT1 = PC_10 | ALT1, +PC_11_ALT1 = PC_11 | ALT1, +PD_4_ALT1 = PD_4 | ALT1, + +/* SYS_WKUP */ +#ifdef PWR_WAKEUP_PIN1 + SYS_WKUP1 = PA_0, +#endif +#ifdef PWR_WAKEUP_PIN2 + SYS_WKUP2 = PC_13, +#endif +#ifdef PWR_WAKEUP_PIN3 + SYS_WKUP3 = NC, +#endif +#ifdef PWR_WAKEUP_PIN4 + SYS_WKUP4 = PA_2, +#endif +#ifdef PWR_WAKEUP_PIN5 + SYS_WKUP5 = PC_5, +#endif +#ifdef PWR_WAKEUP_PIN6 + SYS_WKUP6 = PB_5, +#endif +#ifdef PWR_WAKEUP_PIN7 + SYS_WKUP7 = NC, +#endif +#ifdef PWR_WAKEUP_PIN8 + SYS_WKUP8 = NC, +#endif + +/* USB */ +#ifdef USBCON + USB_DM = PA_11, + USB_DP = PA_12, + #ifdef USB_NOE_PA_4 + USB_NOE = PA_4, + #endif + #ifdef USB_NOE_PA_13 + USB_NOE = PA_13, + #endif + #ifdef USB_NOE_PA_15 + USB_NOE = PA_15, + #endif + #ifdef USB_NOE_PC_9 + USB_NOE = PC_9, + #endif +#endif diff --git a/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/ldscript.ld b/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/ldscript.ld new file mode 100644 index 0000000000000..3b619b6a97e85 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/ldscript.ld @@ -0,0 +1,177 @@ +/** + ****************************************************************************** + * @file LinkerScript.ld + * @author Auto-generated by STM32CubeIDE + * @brief Linker script for STM32G0B1RETx Device from STM32G0 series + * 512Kbytes FLASH + * 144Kbytes RAM + * + * Set heap size, stack size and stack location according + * to application requirements. + * + * Set memory bank area and size if external memory is used + ****************************************************************************** + * @attention + * + *

© 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 + * + ****************************************************************************** + */ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */ + +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Memories definition */ +MEMORY +{ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE + FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET +} + +/* Sections */ +SECTIONS +{ + /* The startup code into "FLASH" Rom type memory */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data into "FLASH" Rom type memory */ + .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 into "FLASH" Rom type memory */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { + . = ALIGN(4); + *(.ARM.extab* .gnu.linkonce.armextab.*) + . = ALIGN(4); + } >FLASH + + .ARM : { + . = ALIGN(4); + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + . = ALIGN(4); + } >FLASH + + .preinit_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + . = ALIGN(4); + } >FLASH + + .init_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + . = ALIGN(4); + } >FLASH + + .fini_array : + { + . = ALIGN(4); + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + . = ALIGN(4); + } >FLASH + + /* Used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections into "RAM" Ram type memory */ + .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 AT> FLASH + + /* Uninitialized data section into "RAM" Ram type memory */ + . = 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 + + /* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + /* Remove information from the compiler libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/variant_MARLIN_STM32G0B1RE.cpp b/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/variant_MARLIN_STM32G0B1RE.cpp new file mode 100644 index 0000000000000..e53fb4182c2ed --- /dev/null +++ b/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/variant_MARLIN_STM32G0B1RE.cpp @@ -0,0 +1,177 @@ +/* + ******************************************************************************* + * 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 + * + ******************************************************************************* + */ + +#if defined(STM32G0B1xx) +#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/A10 + PB_3, // D19 + PB_4, // D20 + PB_5, // D21 + PB_6, // D22 + PB_7, // D23 + PB_8, // D24 + PB_9, // D25 + PB_10, // D26/A11 + PB_11, // D27/A12 + PB_12, // D28/A13 + PB_13, // D29 + PB_14, // D30 + PB_15, // D31 + PC_0, // D32 + PC_1, // D33 + PC_2, // D34 + PC_3, // D35 + PC_4, // D36/A14 + PC_5, // D37/A15 + PC_6, // D38 + PC_7, // D39 + PC_8, // D40 + PC_9, // D41 + PC_10, // D42 + PC_11, // D43 + PC_12, // D44 + PC_13, // D45 + PC_14, // D46 + PC_15, // D47 + PD_0, // D48 + PD_1, // D49 + PD_2, // D50 + PD_3, // D51 + PD_4, // D52 + PD_5, // D53 + PD_6, // D54 + PD_8, // D55 + PD_9, // D56 + PF_0, // D57 + PF_1, // D58 + PF_2, // D59 + PA_9_R, // D60 + PA_10_R // D61 +}; + +// 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 + 18, // A10, PB2 + 26, // A11, PB10 + 27, // A12, PB11 + 28, // A13, PB12 + 36, // A14, PC4 + 37 // A15, PC5 +}; + +// ---------------------------------------------------------------------------- + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief System Clock Configuration + * The system Clock is configured as follows : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 64000000 + * HCLK(Hz) = 64000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 1 + * PLL_M = 1 + * PLL_N = 16 + * PLL_R = 2 + * PLL_P = 2 + * PLL_Q = 2 + * USB(Hz) = 48000000 (HSI48M) + * @param None + * @retval None + */ +WEAK void SystemClock_Config(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {0}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; + RCC_PeriphCLKInitTypeDef PeriphClkInit = {0}; + + /** Configure the main internal regulator output voltage + */ + HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1); + /** Initializes the RCC Oscillators according to the specified parameters + * in the RCC_OscInitTypeDef structure. + */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE|RCC_OSCILLATORTYPE_HSI48; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.HSI48State = RCC_HSI48_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV1; + RCC_OscInitStruct.PLL.PLLN = 16; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2; + RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2; + 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_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) + { + Error_Handler(); + } + /** Initializes the peripherals clocks + */ + PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB; + PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_HSI48; + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) + { + Error_Handler(); + } +} + +#ifdef __cplusplus +} +#endif +#endif /* STM32G0B1xx */ diff --git a/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/variant_MARLIN_STM32G0B1RE.h b/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/variant_MARLIN_STM32G0B1RE.h new file mode 100644 index 0000000000000..65aff2ce27b1d --- /dev/null +++ b/buildroot/share/PlatformIO/variants/STM32G0xx/MARLIN_G0B1RE/variant_MARLIN_STM32G0B1RE.h @@ -0,0 +1,199 @@ +/* + ******************************************************************************* + * 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 + * + ******************************************************************************* + */ +#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 PIN_A10 +#define PB3 19 +#define PB4 20 +#define PB5 21 +#define PB6 22 +#define PB7 23 +#define PB8 24 +#define PB9 25 +#define PB10 PIN_A11 +#define PB11 PIN_A12 +#define PB12 PIN_A13 +#define PB13 29 +#define PB14 30 +#define PB15 31 +#define PC0 32 +#define PC1 33 +#define PC2 34 +#define PC3 35 +#define PC4 PIN_A14 +#define PC5 PIN_A15 +#define PC6 38 +#define PC7 39 +#define PC8 40 +#define PC9 41 +#define PC10 42 +#define PC11 43 +#define PC12 44 +#define PC13 45 +#define PC14 46 +#define PC15 47 +#define PD0 48 +#define PD1 49 +#define PD2 50 +#define PD3 51 +#define PD4 52 +#define PD5 53 +#define PD6 54 +#define PD8 55 +#define PD9 56 +#define PF0 57 +#define PF1 58 +#define PF2 59 +#define PA9_R 60 +#define PA10_R 61 + +// Alternate pins number +#define PA1_ALT1 (PA1 | ALT1) +#define PA2_ALT1 (PA2 | ALT1) +#define PA3_ALT1 (PA3 | ALT1) +#define PA4_ALT1 (PA4 | ALT1) +#define PA6_ALT1 (PA6 | ALT1) +#define PA6_ALT2 (PA6 | ALT2) +#define PA7_ALT1 (PA7 | ALT1) +#define PA7_ALT2 (PA7 | ALT2) +#define PA7_ALT3 (PA7 | ALT3) +#define PA9_ALT1 (PA9 | ALT1) +#define PA9_R_ALT1 (PA9_R | ALT1) +#define PA10_ALT1 (PA10 | ALT1) +#define PA10_R_ALT1 (PA10_R | ALT1) +#define PA14_ALT1 (PA14 | ALT1) +#define PA15_ALT1 (PA15 | ALT1) +#define PB0_ALT1 (PB0 | ALT1) +#define PB1_ALT1 (PB1 | ALT1) +#define PB1_ALT2 (PB1 | ALT2) +#define PB3_ALT1 (PB3 | ALT1) +#define PB4_ALT1 (PB4 | ALT1) +#define PB5_ALT1 (PB5 | ALT1) +#define PB6_ALT1 (PB6 | ALT1) +#define PB6_ALT2 (PB6 | ALT2) +#define PB7_ALT1 (PB7 | ALT1) +#define PB8_ALT1 (PB8 | ALT1) +#define PB9_ALT1 (PB9 | ALT1) +#define PB13_ALT1 (PB13 | ALT1) +#define PB14_ALT1 (PB14 | ALT1) +#define PB15_ALT1 (PB15 | ALT1) +#define PB15_ALT2 (PB15 | ALT2) +#define PC0_ALT1 (PC0 | ALT1) +#define PC1_ALT1 (PC1 | ALT1) +#define PC4_ALT1 (PC4 | ALT1) +#define PC5_ALT1 (PC5 | ALT1) +#define PC6_ALT1 (PC6 | ALT1) +#define PC7_ALT1 (PC7 | ALT1) +#define PC8_ALT1 (PC8 | ALT1) +#define PC9_ALT1 (PC9 | ALT1) +#define PC10_ALT1 (PC10 | ALT1) +#define PC11_ALT1 (PC11 | ALT1) +#define PD4_ALT1 (PD4 | ALT1) + +#define NUM_DIGITAL_PINS 62 +#define NUM_REMAP_PINS 2 +#define NUM_ANALOG_INPUTS 16 + +// SPI definitions +#ifndef PIN_SPI_SS + #define PIN_SPI_SS PA4 +#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 PB6 +#endif +#ifndef PIN_WIRE_SCL + #define PIN_WIRE_SCL PB7 +#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 2 +#endif + +// Default pin used for generic 'Serial' instance +// Mandatory for Firmata +#ifndef PIN_SERIAL_RX + #define PIN_SERIAL_RX PA3 +#endif +#ifndef PIN_SERIAL_TX + #define PIN_SERIAL_TX PA2 +#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 Serial2 + #endif +#endif diff --git a/ini/stm32g0.ini b/ini/stm32g0.ini new file mode 100644 index 0000000000000..99f167a4df329 --- /dev/null +++ b/ini/stm32g0.ini @@ -0,0 +1,39 @@ +# +# Marlin Firmware +# PlatformIO Configuration File +# + +################################# +# +# STM32G0 Architecture +# +# Naming Example: STM32G0B1RET6 +# +# G : Foundation +# 0 : Cortex M0+ core (0:M0, 1-2:M3, 3-4:M4, 7:M7) +# B1 : Line/Features +# R : 64 pins (R:64 or 66, F:20) +# E : 512KB Flash-memory (C:256KB, D:384KB, E:512KB, G:1024KB) +# T : LQFP package +# 6 : -40...85°C (7: ...105°C) +# +################################# + +# +# BigTree SKR mini E3 V3.0 (STM32G0B1RET6 ARM Cortex-M0+) +# +[env:STM32G0B1RE_btt] +platform = ststm32@~14.1.0 +platform_packages = framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32/archive/main.zip +extends = stm32_variant +board = marlin_STM32G0B1RE +board_build.offset = 0x2000 +board_upload.offset_address = 0x08002000 +build_flags = ${stm32_variant.build_flags} + -DADC_RESOLUTION=12 + -DPIN_SERIAL4_RX=PC_11 -DPIN_SERIAL4_TX=PC_10 + -DSERIAL_RX_BUFFER_SIZE=1024 -DSERIAL_TX_BUFFER_SIZE=1024 + -DTIMER_SERVO=TIM3 -DTIMER_TONE=TIM4 + -DSTEP_TIMER_IRQ_PRIO=0 +upload_protocol = stlink +debug_tool = stlink diff --git a/platformio.ini b/platformio.ini index 55a2bd24571c1..74ac012f19761 100644 --- a/platformio.ini +++ b/platformio.ini @@ -30,6 +30,7 @@ extra_configs = ini/stm32f4.ini ini/stm32f7.ini ini/stm32h7.ini + ini/stm32g0.ini ini/teensy.ini # From aebf70cdae0683ed067a9d5aa0f3c93883f0d55a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 11 Dec 2021 01:03:00 +0000 Subject: [PATCH 137/273] [cron] Bump distribution date (2021-12-11) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 3966933d3c54a..fdfa9e17477d0 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 "2021-12-10" +//#define STRING_DISTRIBUTION_DATE "2021-12-11" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a0e443bff42be..7db79cab2a497 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 "2021-12-10" + #define STRING_DISTRIBUTION_DATE "2021-12-11" #endif /** From 5528927d7127a176d107e8c1adc4906214142adf Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sun, 12 Dec 2021 11:06:45 +1300 Subject: [PATCH 138/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20MARLIN=5FF103Rx=20?= =?UTF-8?q?variant=20SCK=20/=20MOSI=20pins=20(#23282)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../share/PlatformIO/variants/MARLIN_F103Rx/variant.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h index 41b194abe031f..333bb02e5a225 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h @@ -105,14 +105,14 @@ extern "C" { // SPI Definitions #if DEFAULT_SPI == 3 #define PIN_SPI_SS PA15 - #define PIN_SPI_MOSI PB3 + #define PIN_SPI_MOSI PB5 #define PIN_SPI_MISO PB4 - #define PIN_SPI_SCK PB5 + #define PIN_SPI_SCK PB3 #elif DEFAULT_SPI == 2 #define PIN_SPI_SS PB12 - #define PIN_SPI_MOSI PB13 + #define PIN_SPI_MOSI PB15 #define PIN_SPI_MISO PB14 - #define PIN_SPI_SCK PB15 + #define PIN_SPI_SCK PB13 #else #define PIN_SPI_SS PA4 #define PIN_SPI_MOSI PA7 From 60717927acc227e9ab71946b653d7e8eb8839fef Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 12 Dec 2021 01:06:58 +0000 Subject: [PATCH 139/273] [cron] Bump distribution date (2021-12-12) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index fdfa9e17477d0..4f1744ec3621a 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 "2021-12-11" +//#define STRING_DISTRIBUTION_DATE "2021-12-12" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7db79cab2a497..18f2f79992323 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 "2021-12-11" + #define STRING_DISTRIBUTION_DATE "2021-12-12" #endif /** From 1cff4fdb3670e0d04d865fe699763073149d4acd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 12 Dec 2021 16:16:40 -0600 Subject: [PATCH 140/273] =?UTF-8?q?=F0=9F=A9=B9=20SD=20abort=20requires=20?= =?UTF-8?q?open=20file?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit See #22566 --- Marlin/src/sd/cardreader.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 97003e1d13766..53e1a7ffc3cbd 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -163,7 +163,7 @@ class CardReader { static void endFilePrintNow(TERN_(SD_RESORT, const bool re_sort=false)); static void abortFilePrintNow(TERN_(SD_RESORT, const bool re_sort=false)); static void fileHasFinished(); - static inline void abortFilePrintSoon() { flag.abort_sd_printing = true; } + static inline void abortFilePrintSoon() { flag.abort_sd_printing = isFileOpen(); } static inline void pauseSDPrint() { flag.sdprinting = false; } static inline bool isPrinting() { return flag.sdprinting; } static inline bool isPaused() { return isFileOpen() && !isPrinting(); } From 82d569faa09f4e427679502b88f1faa08dade217 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 13 Dec 2021 01:04:05 +0000 Subject: [PATCH 141/273] [cron] Bump distribution date (2021-12-13) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 4f1744ec3621a..0c775449b687f 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 "2021-12-12" +//#define STRING_DISTRIBUTION_DATE "2021-12-13" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 18f2f79992323..565faed73dd53 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 "2021-12-12" + #define STRING_DISTRIBUTION_DATE "2021-12-13" #endif /** From 9eb2a5f62c4c98a6f681735da66ca22ac08550e7 Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Tue, 14 Dec 2021 05:07:44 +0700 Subject: [PATCH 142/273] =?UTF-8?q?=F0=9F=A9=B9=20Use=20EXTRUDER=5FAUTO=5F?= =?UTF-8?q?FAN=5FSPEED=20for=20=5FAUTOFAN=5FSPEED=20(#23180)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/temperature.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index e068d4fca025b..59d80e0ea8e77 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -938,7 +938,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #if BOTH(HAS_FANCHECK, HAS_PWMFANCHECK) #define _AUTOFAN_SPEED() fan_check.is_measuring() ? 255 : EXTRUDER_AUTO_FAN_SPEED #else - #define _AUTOFAN_SPEED() 255 + #define _AUTOFAN_SPEED() EXTRUDER_AUTO_FAN_SPEED #endif #define _AUTOFAN_CASE(N) case N: _UPDATE_AUTO_FAN(E##N, fan_on, _AUTOFAN_SPEED()); break From afce7d6dd50273e9ee397cbe42ad9c4986a55fe4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 13 Dec 2021 16:15:46 -0600 Subject: [PATCH 143/273] =?UTF-8?q?=F0=9F=94=A7=20Fix=20unknown=20board=20?= =?UTF-8?q?test?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 48 +++++++++++++++++++++--------------------- 1 file changed, 24 insertions(+), 24 deletions(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 3ffb2d26b7c26..7759aeb7b7d12 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -737,30 +737,30 @@ // Obsolete or unknown board // - #define BOARD_MKS_13 -1000 - #define BOARD_TRIGORILLA -1001 - #define BOARD_RURAMPS4D -1002 - #define BOARD_FORMBOT_TREX2 -1003 - #define BOARD_BIQU_SKR_V1_1 -1004 - #define BOARD_STM32F1R -1005 - #define BOARD_STM32F103R -1006 - #define BOARD_ESP32 -1007 - #define BOARD_STEVAL -1008 - #define BOARD_BIGTREE_SKR_V1_1 -1009 - #define BOARD_BIGTREE_SKR_V1_3 -1010 - #define BOARD_BIGTREE_SKR_V1_4 -1011 - #define BOARD_BIGTREE_SKR_V1_4_TURBO -1012 - #define BOARD_BIGTREE_BTT002_V1_0 -1013 - #define BOARD_BIGTREE_SKR_PRO_V1_1 -1014 - #define BOARD_BIGTREE_SKR_MINI_V1_1 -1015 - #define BOARD_BIGTREE_SKR_MINI_E3 -1016 - #define BOARD_BIGTREE_SKR_E3_DIP -1017 - #define BOARD_RUMBA32 -1018 - #define BOARD_RUMBA32_AUS3D -1019 - #define BOARD_RAMPS_DAGOMA -1020 - #define BOARD_RAMPS_LONGER3D_LK4PRO -1021 - #define BOARD_BTT_SKR_V2_0 -1022 - #define BOARD_TH3D_EZBOARD_LITE_V2 -1023 + #define BOARD_MKS_13 99900 + #define BOARD_TRIGORILLA 99901 + #define BOARD_RURAMPS4D 99902 + #define BOARD_FORMBOT_TREX2 99903 + #define BOARD_BIQU_SKR_V1_1 99904 + #define BOARD_STM32F1R 99905 + #define BOARD_STM32F103R 99906 + #define BOARD_ESP32 99907 + #define BOARD_STEVAL 99908 + #define BOARD_BIGTREE_SKR_V1_1 99909 + #define BOARD_BIGTREE_SKR_V1_3 99910 + #define BOARD_BIGTREE_SKR_V1_4 99911 + #define BOARD_BIGTREE_SKR_V1_4_TURBO 99912 + #define BOARD_BIGTREE_BTT002_V1_0 99913 + #define BOARD_BIGTREE_SKR_PRO_V1_1 99914 + #define BOARD_BIGTREE_SKR_MINI_V1_1 99915 + #define BOARD_BIGTREE_SKR_MINI_E3 99916 + #define BOARD_BIGTREE_SKR_E3_DIP 99917 + #define BOARD_RUMBA32 99918 + #define BOARD_RUMBA32_AUS3D 99919 + #define BOARD_RAMPS_DAGOMA 99920 + #define BOARD_RAMPS_LONGER3D_LK4PRO 99921 + #define BOARD_BTT_SKR_V2_0 99922 + #define BOARD_TH3D_EZBOARD_LITE_V2 99923 #if MB(MKS_13) #error "BOARD_MKS_13 has been renamed BOARD_MKS_GEN_13. Please update your configuration." From 26689e1d85e5c210daa01548ae0b6c9118e35bd4 Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Tue, 14 Dec 2021 07:11:52 +0700 Subject: [PATCH 144/273] =?UTF-8?q?=F0=9F=A9=B9=20Init=20fan=20speed=20at?= =?UTF-8?q?=20boot=20(#23181)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/module/planner.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 0c62b11f5cf38..45ccdd1702ef8 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1309,7 +1309,7 @@ void Planner::check_axes_activity() { #endif #if HAS_TAIL_FAN_SPEED - static uint8_t tail_fan_speed[FAN_COUNT]; + static uint8_t tail_fan_speed[FAN_COUNT] = ARRAY_N_1(FAN_COUNT, 255); bool fans_need_update = false; #endif From dff18e2230eb07cfe7e6b9d9d3d288d2211b089e Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 14 Dec 2021 13:13:34 +1300 Subject: [PATCH 145/273] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20Clean=20up=20dupli?= =?UTF-8?q?cate=20defs=20(#23182)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp | 1 - Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h | 1 - 2 files changed, 2 deletions(-) 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 109814abf26d3..f2ee1e5639e4d 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 @@ -71,7 +71,6 @@ namespace ExtUI { } void onStatusChanged(const char *lcd_msg) { StatusScreen::setStatusMessage(lcd_msg); } - void onStatusChanged(FSTR_P lcd_msg) { StatusScreen::setStatusMessage(lcd_msg); } void onPrintTimerStarted() { InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_STARTED); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h index 2e2597aec4350..f79f788d8d3a5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h @@ -145,7 +145,6 @@ namespace Language_en { PROGMEM Language_Str MSG_LEVELING = u8"Leveling"; PROGMEM Language_Str MSG_AXIS_LEVELING = u8"Axis Leveling"; PROGMEM Language_Str MSG_PROBE_BED = u8"Probe Mesh"; - PROGMEM Language_Str MSG_MESH_VIEW = u8"View Mesh"; PROGMEM Language_Str MSG_PRINT_TEST = u8"Print Test (PLA)"; PROGMEM Language_Str MSG_MOVE_Z_TO_TOP = u8"Raise Z to Top"; From eef9e046904c382def0735c89dd3ea9961658554 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 14 Dec 2021 13:18:24 +1300 Subject: [PATCH 146/273] =?UTF-8?q?=E2=9C=A8=20M115=20flag=20EXTENDED=5FM2?= =?UTF-8?q?0=20(#22941)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/host/M115.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 8a9c409764c54..9a90acbf0a23a 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -143,6 +143,9 @@ void GcodeSuite::M115() { // LONG_FILENAME_HOST_SUPPORT (M33) cap_line(F("LONG_FILENAME"), ENABLED(LONG_FILENAME_HOST_SUPPORT)); + // EXTENDED_M20 (M20 L) + cap_line(F("EXTENDED_M20"), ENABLED(LONG_FILENAME_HOST_SUPPORT)); + // THERMAL_PROTECTION cap_line(F("THERMAL_PROTECTION"), ENABLED(THERMALLY_SAFE)); From 8277f3ca0db3fcfcade46e202d5c32c4908546ba Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Tue, 14 Dec 2021 01:41:21 +0100 Subject: [PATCH 147/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20TFT=5FCOLOR=5FUI?= =?UTF-8?q?=20Release=20Media=20issue=20(#23123)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/sd/M21_M22.cpp | 2 -- Marlin/src/lcd/menu/menu_main.cpp | 9 ++++++++- 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/Marlin/src/gcode/sd/M21_M22.cpp b/Marlin/src/gcode/sd/M21_M22.cpp index f42784d8eb436..c7f41f9c817e0 100644 --- a/Marlin/src/gcode/sd/M21_M22.cpp +++ b/Marlin/src/gcode/sd/M21_M22.cpp @@ -26,7 +26,6 @@ #include "../gcode.h" #include "../../sd/cardreader.h" -#include "../../lcd/marlinui.h" /** * M21: Init SD Card @@ -38,7 +37,6 @@ void GcodeSuite::M21() { card.mount(); } */ void GcodeSuite::M22() { if (!IS_SD_PRINTING()) card.release(); - IF_ENABLED(TFT_COLOR_UI, ui.refresh(LCDVIEW_CALL_REDRAW_NEXT)); } #endif // SDSUPPORT diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index aca10edc6a0c0..6e66188c02ce0 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -249,7 +249,14 @@ void menu_main() { #if PIN_EXISTS(SD_DETECT) GCODES_ITEM(MSG_CHANGE_MEDIA, PSTR("M21")); // M21 Change Media #else // - or - - GCODES_ITEM(MSG_RELEASE_MEDIA, PSTR("M22")); // M22 Release Media + ACTION_ITEM(MSG_RELEASE_MEDIA, []{ // M22 Release Media + queue.inject(PSTR("M22")); + #if ENABLED(TFT_COLOR_UI) + // Menu display issue on item removal with multi language selection menu + if (encoderTopLine > 0) encoderTopLine--; + ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); + #endif + }); #endif SUBMENU(MSG_MEDIA_MENU, MEDIA_MENU_GATEWAY); // Media Menu (or Password First) } From 1dd9adbfe40f0423181773a3370fbbab27d0a990 Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Tue, 14 Dec 2021 01:47:57 +0100 Subject: [PATCH 148/273] =?UTF-8?q?=F0=9F=9A=B8=20Use=20M600=20for=20disab?= =?UTF-8?q?led=20MMU=20(#21865)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 5 ++- Marlin/src/feature/pause.h | 15 +++------ Marlin/src/gcode/feature/pause/M600.cpp | 45 ++++++++++++++----------- 3 files changed, 34 insertions(+), 31 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 941903149f344..5132d07e8711f 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -784,7 +784,10 @@ void idle(bool no_stepper_sleep/*=false*/) { (void)check_tool_sensor_stats(active_extruder, true); // Handle filament runout sensors - TERN_(HAS_FILAMENT_SENSOR, runout.run()); + #if HAS_FILAMENT_SENSOR + if (TERN1(HAS_PRUSA_MMU2, !mmu2.enabled())) + runout.run(); + #endif // Run HAL idle tasks TERN_(HAL_IDLETASK, HAL_idletask()); diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index d2c45e44a5df1..134b1d1b3294d 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -73,17 +73,10 @@ extern fil_change_settings_t fc_settings[EXTRUDERS]; extern uint8_t did_pause_print; -#if ENABLED(DUAL_X_CARRIAGE) - #define DXC_PARAMS , const int8_t DXC_ext=-1 - #define DXC_ARGS , const int8_t DXC_ext - #define DXC_PASS , DXC_ext - #define DXC_SAY , " dxc:", int(DXC_ext) -#else - #define DXC_PARAMS - #define DXC_ARGS - #define DXC_PASS - #define DXC_SAY -#endif +#define DXC_PARAMS OPTARG(DUAL_X_CARRIAGE, const int8_t DXC_ext=-1) +#define DXC_ARGS OPTARG(DUAL_X_CARRIAGE, const int8_t DXC_ext) +#define DXC_PASS OPTARG(DUAL_X_CARRIAGE, DXC_ext) +#define DXC_SAY OPTARG(DUAL_X_CARRIAGE, " dxc:", int(DXC_ext)) // Pause the print. If unload_length is set, do a Filament Unload bool pause_print( diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index a95e3e02b49e4..665967ca564d4 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -34,8 +34,11 @@ #include "../../../module/tool_change.h" #endif -#if ENABLED(MMU2_MENUS) - #include "../../../lcd/menu/menu_mmu2.h" +#if ENABLED(HAS_PRUSA_MMU2) + #include "../../../feature/mmu/mmu2.h" + #if ENABLED(MMU2_MENUS) + #include "../../../lcd/menu/menu_mmu2.h" + #endif #endif #if ENABLED(MIXING_EXTRUDER) @@ -92,10 +95,11 @@ void GcodeSuite::M600() { } #endif + const bool standardM600 = TERN1(MMU2_MENUS, !mmu2.enabled()); + // Show initial "wait for start" message - #if DISABLED(MMU2_MENUS) + if (standardM600) ui.pause_show_message(PAUSE_MESSAGE_CHANGING, PAUSE_MODE_PAUSE_PRINT, target_extruder); - #endif #if ENABLED(HOME_BEFORE_FILAMENT_CHANGE) // If needed, home before parking for filament change @@ -126,17 +130,11 @@ void GcodeSuite::M600() { #endif #if ENABLED(MMU2_MENUS) - // For MMU2 reset retract and load/unload values so they don't mess with MMU filament handling - constexpr float unload_length = 0.5f, - slow_load_length = 0.0f, - fast_load_length = 0.0f; + // For MMU2, when enabled, reset retract value so it doesn't mess with MMU filament handling + const float unload_length = standardM600 ? -ABS(parser.axisunitsval('U', E_AXIS, fc_settings[active_extruder].unload_length)) : 0.5f; #else // Unload filament const float unload_length = -ABS(parser.axisunitsval('U', E_AXIS, fc_settings[active_extruder].unload_length)); - // Slow load filament - constexpr float slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH; - // Fast load filament - const float fast_load_length = ABS(parser.axisunitsval('L', E_AXIS, fc_settings[active_extruder].load_length)); #endif const int beep_count = parser.intval('B', -1 @@ -146,14 +144,23 @@ void GcodeSuite::M600() { ); if (pause_print(retract, park_point, true, unload_length DXC_PASS)) { - #if ENABLED(MMU2_MENUS) - mmu2_M600(); - resume_print(slow_load_length, fast_load_length, 0, beep_count DXC_PASS); - #else + if (standardM600) { wait_for_confirmation(true, beep_count DXC_PASS); - resume_print(slow_load_length, fast_load_length, ADVANCED_PAUSE_PURGE_LENGTH, - beep_count, (parser.seenval('R') ? parser.value_celsius() : 0) DXC_PASS); - #endif + resume_print( + FILAMENT_CHANGE_SLOW_LOAD_LENGTH, + ABS(parser.axisunitsval('L', E_AXIS, fc_settings[active_extruder].load_length)), + ADVANCED_PAUSE_PURGE_LENGTH, + beep_count, + parser.celsiusval('R') + DXC_PASS + ); + } + else { + #if ENABLED(MMU2_MENUS) + mmu2_M600(); + resume_print(0, 0, 0, beep_count, 0 DXC_PASS); + #endif + } } #if HAS_MULTI_EXTRUDER From bf21bc9ee53aa094a55dc76f5023b9988f31b166 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 14 Dec 2021 01:25:36 +0000 Subject: [PATCH 149/273] [cron] Bump distribution date (2021-12-14) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 0c775449b687f..6133fd7b08005 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 "2021-12-13" +//#define STRING_DISTRIBUTION_DATE "2021-12-14" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 565faed73dd53..2fab27fac8420 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 "2021-12-13" + #define STRING_DISTRIBUTION_DATE "2021-12-14" #endif /** From b464a4b1a4ea9cca914126c5f50c3e7384108a5e Mon Sep 17 00:00:00 2001 From: X-Ryl669 Date: Tue, 14 Dec 2021 07:22:06 +0100 Subject: [PATCH 150/273] =?UTF-8?q?=E2=9C=A8=20Configurations=20embed=20an?= =?UTF-8?q?d=20retrieve=20(#21321)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .gitignore | 3 + Marlin/Configuration_adv.h | 8 + Marlin/src/gcode/eeprom/M500-M504.cpp | 18 ++ Marlin/src/gcode/host/M115.cpp | 28 ++- Marlin/src/inc/Conditionals_adv.h | 6 + Marlin/src/inc/Warnings.cpp | 4 + buildroot/bin/restore_configs | 2 +- .../scripts/SAMD51_grandcentral_m4.py | 1 - .../share/PlatformIO/scripts/__init__.py | 0 .../PlatformIO/scripts/common-dependencies.py | 87 ++------- .../share/PlatformIO/scripts/mc-apply.py | 69 +++++++ .../share/PlatformIO/scripts/preprocessor.py | 99 ++++++++++ .../share/PlatformIO/scripts/signature.py | 176 ++++++++++++++++++ docs/ConfigEmbedding.md | 19 ++ 14 files changed, 435 insertions(+), 85 deletions(-) create mode 100644 buildroot/share/PlatformIO/scripts/__init__.py create mode 100755 buildroot/share/PlatformIO/scripts/mc-apply.py create mode 100644 buildroot/share/PlatformIO/scripts/preprocessor.py create mode 100644 buildroot/share/PlatformIO/scripts/signature.py create mode 100644 docs/ConfigEmbedding.md diff --git a/.gitignore b/.gitignore index fabe5445631f6..2b40149b5f50f 100755 --- a/.gitignore +++ b/.gitignore @@ -22,6 +22,9 @@ # Generated files _Version.h bdf2u8g +marlin_config.json +mczip.h +*.gen # # OS diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 0d848f260b95c..eea15c9651aee 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1593,6 +1593,14 @@ #define SD_FIRMWARE_UPDATE_INACTIVE_VALUE 0xFF #endif + /** + * Enable this option if you have more than ~3K of unused flash space. + * Marlin will embed all settings in the firmware binary as compressed data. + * Use 'M503 C' to write the settings out to the SD Card as 'mc.zip'. + * See docs/ConfigEmbedding.md for details on how to use 'mc-apply.py'. + */ + //#define CONFIGURATION_EMBEDDING + // Add an optimized binary file transfer mode, initiated with 'M28 B1' //#define BINARY_FILE_TRANSFER diff --git a/Marlin/src/gcode/eeprom/M500-M504.cpp b/Marlin/src/gcode/eeprom/M500-M504.cpp index a06e98ad1ea79..a1f295ebde063 100644 --- a/Marlin/src/gcode/eeprom/M500-M504.cpp +++ b/Marlin/src/gcode/eeprom/M500-M504.cpp @@ -25,6 +25,11 @@ #include "../../core/serial.h" #include "../../inc/MarlinConfig.h" +#if ENABLED(CONFIGURATION_EMBEDDING) + #include "../../sd/SdBaseFile.h" + #include "../../mczip.h" +#endif + /** * M500: Store settings in EEPROM */ @@ -50,9 +55,22 @@ void GcodeSuite::M502() { /** * M503: print settings currently in memory + * + * With CONFIGURATION_EMBEDDING: + * C : Save the full Marlin configuration to SD Card as "mc.zip" */ void GcodeSuite::M503() { (void)settings.report(!parser.boolval('S', true)); + + #if ENABLED(CONFIGURATION_EMBEDDING) + if (parser.seen_test('C')) { + SdBaseFile file; + const uint16_t size = sizeof(mc_zip); + // Need to create the config size on the SD card + if (file.open("mc.zip", O_WRITE|O_CREAT) && file.write(pgm_read_ptr(mc_zip), size) != -1 && file.close()) + SERIAL_ECHO_MSG("Configuration saved as 'mc.zip'"); + } + #endif } #endif // !DISABLE_M503 diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 9a90acbf0a23a..08943ed5f299d 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -24,7 +24,6 @@ #include "../../inc/MarlinConfig.h" #include "../queue.h" // for getting the command port - #if ENABLED(M115_GEOMETRY_REPORT) #include "../../module/motion.h" #endif @@ -33,13 +32,25 @@ #include "../../feature/caselight.h" #endif +//#define MINIMAL_CAP_LINES // Don't even mention the disabled capabilities + #if ENABLED(EXTENDED_CAPABILITIES_REPORT) - static void cap_line(FSTR_P const name, bool ena=false) { - SERIAL_ECHOPGM("Cap:"); - SERIAL_ECHOF(name); - SERIAL_CHAR(':', '0' + ena); - SERIAL_EOL(); - } + #if ENABLED(MINIMAL_CAP_LINES) + #define cap_line(S,C) if (C) _cap_line(S) + static void _cap_line(FSTR_P const name) { + SERIAL_ECHOPGM("Cap:"); + SERIAL_ECHOF(name); + SERIAL_ECHOLNPGM(":1"); + } + #else + #define cap_line(V...) _cap_line(V) + static void _cap_line(FSTR_P const name, bool ena=false) { + SERIAL_ECHOPGM("Cap:"); + SERIAL_ECHOF(name); + SERIAL_CHAR(':', '0' + ena); + SERIAL_EOL(); + } + #endif #endif /** @@ -167,6 +178,9 @@ void GcodeSuite::M115() { // MEATPACK Compression cap_line(F("MEATPACK"), SERIAL_IMPL.has_feature(port, SerialFeature::MeatPack)); + // CONFIG_EXPORT + cap_line(F("CONFIG_EXPORT"), ENABLED(CONFIG_EMBED_AND_SAVE_TO_SD)); + // Machine Geometry #if ENABLED(M115_GEOMETRY_REPORT) const xyz_pos_t bmin = { 0, 0, 0 }, diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 22f1591d68261..9864b8715c754 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -1004,3 +1004,9 @@ #if EITHER(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 !defined(FORCE_CONFIG_EMBED) && (defined(__AVR__) || DISABLED(SDSUPPORT) || EITHER(SDCARD_READONLY, DISABLE_M503)) + #undef CONFIGURATION_EMBEDDING + #define CANNOT_EMBED_CONFIGURATION defined(__AVR__) +#endif diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index b7eef9c49f530..c2fe42ae82e2c 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -549,3 +549,7 @@ #elif !USE_SENSORLESS && ENABLED(USES_DIAG_PINS) #warning "Driver DIAG pins must be physically removed unless SENSORLESS_HOMING is enabled. (See https://bit.ly/2ZPRlt0)" #endif + +#if CANNOT_EMBED_CONFIGURATION + #warning "Disabled CONFIGURATION_EMBEDDING because the target usually has less flash storage. Define FORCE_CONFIG_EMBED to override." +#endif diff --git a/buildroot/bin/restore_configs b/buildroot/bin/restore_configs index b2d0ea19ac8cd..61aa3f9ee18e8 100755 --- a/buildroot/bin/restore_configs +++ b/buildroot/bin/restore_configs @@ -2,4 +2,4 @@ git checkout Marlin/Configuration*.h 2>/dev/null git checkout Marlin/src/pins/ramps/pins_RAMPS.h 2>/dev/null -rm -f Marlin/_Bootscreen.h Marlin/_Statusscreen.h +rm -f Marlin/_Bootscreen.h Marlin/_Statusscreen.h marlin_config.json .pio/build/mc.zip diff --git a/buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py b/buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py index be2c87266acc6..e7442f2485b87 100644 --- a/buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py +++ b/buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py @@ -6,7 +6,6 @@ if pioutil.is_pio_build(): from os.path import join, isfile import shutil - from pprint import pprint Import("env") diff --git a/buildroot/share/PlatformIO/scripts/__init__.py b/buildroot/share/PlatformIO/scripts/__init__.py new file mode 100644 index 0000000000000..e69de29bb2d1d diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.py b/buildroot/share/PlatformIO/scripts/common-dependencies.py index 004f78f19b62e..24e780d9b6702 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.py +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.py @@ -192,63 +192,6 @@ def apply_features_config(): lib_ignore = env.GetProjectOption('lib_ignore') + [feat['lib_ignore']] set_env_field('lib_ignore', lib_ignore) - # - # Find a compiler, considering the OS - # - ENV_BUILD_PATH = os.path.join(env.Dictionary('PROJECT_BUILD_DIR'), env['PIOENV']) - GCC_PATH_CACHE = os.path.join(ENV_BUILD_PATH, ".gcc_path") - def search_compiler(): - try: - filepath = env.GetProjectOption('custom_gcc') - blab("Getting compiler from env") - return filepath - except: - pass - - if os.path.exists(GCC_PATH_CACHE): - with open(GCC_PATH_CACHE, 'r') as f: - return f.read() - - # Find the current platform compiler by searching the $PATH - # which will be in a platformio toolchain bin folder - path_regex = re.escape(env['PROJECT_PACKAGES_DIR']) - - # See if the environment provides a default compiler - try: - gcc = env.GetProjectOption('custom_deps_gcc') - except: - gcc = "g++" - - if env['PLATFORM'] == 'win32': - path_separator = ';' - path_regex += r'.*\\bin' - gcc += ".exe" - else: - path_separator = ':' - path_regex += r'/.+/bin' - - # Search for the compiler - for pathdir in env['ENV']['PATH'].split(path_separator): - if not re.search(path_regex, pathdir, re.IGNORECASE): - continue - for filepath in os.listdir(pathdir): - if not filepath.endswith(gcc): - continue - # Use entire path to not rely on env PATH - filepath = os.path.sep.join([pathdir, filepath]) - # Cache the g++ path to no search always - if os.path.exists(ENV_BUILD_PATH): - with open(GCC_PATH_CACHE, 'w+') as f: - f.write(filepath) - - return filepath - - filepath = env.get('CXX') - if filepath == 'CC': - filepath = gcc - blab("Couldn't find a compiler! Fallback to %s" % filepath) - return filepath - # # Use the compiler to get a list of all enabled features # @@ -257,25 +200,8 @@ def load_marlin_features(): return # Process defines - build_flags = env.get('BUILD_FLAGS') - build_flags = env.ParseFlagsExtended(build_flags) - - cxx = search_compiler() - cmd = ['"' + cxx + '"'] - - # Build flags from board.json - #if 'BOARD' in env: - # cmd += [env.BoardConfig().get("build.extra_flags")] - for s in build_flags['CPPDEFINES']: - if isinstance(s, tuple): - cmd += ['-D' + s[0] + '=' + str(s[1])] - else: - cmd += ['-D' + s] - - cmd += ['-D__MARLIN_DEPS__ -w -dM -E -x c++ buildroot/share/PlatformIO/scripts/common-dependencies.h'] - cmd = ' '.join(cmd) - blab(cmd, 4) - define_list = subprocess.check_output(cmd, shell=True).splitlines() + from preprocessor import run_preprocessor + define_list = run_preprocessor(env) marlin_features = {} for define in define_list: feature = define[8:].strip().decode().split(' ') @@ -310,9 +236,18 @@ def MarlinFeatureIsEnabled(env, feature): except: pass + # # Add a method for other PIO scripts to query enabled features + # env.AddMethod(MarlinFeatureIsEnabled) + # # Add dependencies for enabled Marlin features + # apply_features_config() force_ignore_unused_libs() + + #print(env.Dump()) + + from signature import compute_build_signature + compute_build_signature(env) diff --git a/buildroot/share/PlatformIO/scripts/mc-apply.py b/buildroot/share/PlatformIO/scripts/mc-apply.py new file mode 100755 index 0000000000000..f71d192679d31 --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/mc-apply.py @@ -0,0 +1,69 @@ +#!/usr/bin/env python +# +# Create a Configuration from marlin_config.json +# +import json +import sys +import shutil +import re + +opt_output = '--opt' in sys.argv +output_suffix = '.sh' if opt_output else '' if '--bare-output' in sys.argv else '.gen' + +try: + with open('marlin_config.json', 'r') as infile: + conf = json.load(infile) + for key in conf: + # We don't care about the hash when restoring here + if key == '__INITIAL_HASH': + continue + if key == 'VERSION': + for k, v in sorted(conf[key].items()): + print(k + ': ' + v) + continue + # The key is the file name, so let's build it now + outfile = open('Marlin/' + key + output_suffix, 'w') + for k, v in sorted(conf[key].items()): + # Make define line now + if opt_output: + if v != '': + if '"' in v: + v = "'%s'" % v + elif ' ' in v: + v = '"%s"' % v + define = 'opt_set ' + k + ' ' + v + '\n' + else: + define = 'opt_enable ' + k + '\n' + else: + define = '#define ' + k + ' ' + v + '\n' + outfile.write(define) + outfile.close() + + # Try to apply changes to the actual configuration file (in order to keep useful comments) + if output_suffix != '': + # Move the existing configuration so it doesn't interfere + shutil.move('Marlin/' + key, 'Marlin/' + key + '.orig') + infile_lines = open('Marlin/' + key + '.orig', 'r').read().split('\n') + outfile = open('Marlin/' + key, 'w') + for line in infile_lines: + sline = line.strip(" \t\n\r") + if sline[:7] == "#define": + # Extract the key here (we don't care about the value) + kv = sline[8:].strip().split(' ') + if kv[0] in conf[key]: + outfile.write('#define ' + kv[0] + ' ' + conf[key][kv[0]] + '\n') + # Remove the key from the dict, so we can still write all missing keys at the end of the file + del conf[key][kv[0]] + else: + outfile.write(line + '\n') + else: + outfile.write(line + '\n') + # Process any remaining defines here + for k, v in sorted(conf[key].items()): + define = '#define ' + k + ' ' + v + '\n' + outfile.write(define) + outfile.close() + + print('Output configuration written to: ' + 'Marlin/' + key + output_suffix) +except: + print('No marlin_config.json found.') diff --git a/buildroot/share/PlatformIO/scripts/preprocessor.py b/buildroot/share/PlatformIO/scripts/preprocessor.py new file mode 100644 index 0000000000000..6f4ed900cab18 --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/preprocessor.py @@ -0,0 +1,99 @@ +# +# preprocessor.py +# +import subprocess,os,re + +verbose = 0 + +def blab(str): + if verbose: + print(str) + +################################################################################ +# +# Invoke GCC to run the preprocessor and extract enabled features +# +preprocessor_cache = {} +def run_preprocessor(env, fn=None): + filename = fn or 'buildroot/share/PlatformIO/scripts/common-dependencies.h' + if filename in preprocessor_cache: + return preprocessor_cache[filename] + + # Process defines + build_flags = env.get('BUILD_FLAGS') + build_flags = env.ParseFlagsExtended(build_flags) + + cxx = search_compiler(env) + cmd = ['"' + cxx + '"'] + + # Build flags from board.json + #if 'BOARD' in env: + # cmd += [env.BoardConfig().get("build.extra_flags")] + for s in build_flags['CPPDEFINES']: + if isinstance(s, tuple): + cmd += ['-D' + s[0] + '=' + str(s[1])] + else: + cmd += ['-D' + s] + + cmd += ['-D__MARLIN_DEPS__ -w -dM -E -x c++'] + depcmd = cmd + [ filename ] + cmd = ' '.join(depcmd) + blab(cmd) + define_list = subprocess.check_output(cmd, shell=True).splitlines() + preprocessor_cache[filename] = define_list + return define_list + + +################################################################################ +# +# Find a compiler, considering the OS +# +def search_compiler(env): + + ENV_BUILD_PATH = os.path.join(env.Dictionary('PROJECT_BUILD_DIR'), env['PIOENV']) + GCC_PATH_CACHE = os.path.join(ENV_BUILD_PATH, ".gcc_path") + + try: + filepath = env.GetProjectOption('custom_gcc') + blab("Getting compiler from env") + return filepath + except: + pass + + if os.path.exists(GCC_PATH_CACHE): + blab("Getting g++ path from cache") + with open(GCC_PATH_CACHE, 'r') as f: + return f.read() + + # Find the current platform compiler by searching the $PATH + # which will be in a platformio toolchain bin folder + path_regex = re.escape(env['PROJECT_PACKAGES_DIR']) + gcc = "g++" + if env['PLATFORM'] == 'win32': + path_separator = ';' + path_regex += r'.*\\bin' + gcc += ".exe" + else: + path_separator = ':' + path_regex += r'/.+/bin' + + # Search for the compiler + for pathdir in env['ENV']['PATH'].split(path_separator): + if not re.search(path_regex, pathdir, re.IGNORECASE): + continue + for filepath in os.listdir(pathdir): + if not filepath.endswith(gcc): + continue + # Use entire path to not rely on env PATH + filepath = os.path.sep.join([pathdir, filepath]) + # Cache the g++ path to no search always + if os.path.exists(ENV_BUILD_PATH): + blab("Caching g++ for current env") + with open(GCC_PATH_CACHE, 'w+') as f: + f.write(filepath) + + return filepath + + filepath = env.get('CXX') + blab("Couldn't find a compiler! Fallback to %s" % filepath) + return filepath diff --git a/buildroot/share/PlatformIO/scripts/signature.py b/buildroot/share/PlatformIO/scripts/signature.py new file mode 100644 index 0000000000000..53cf347eaad9c --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/signature.py @@ -0,0 +1,176 @@ +# +# signature.py +# +import os,subprocess,re,json,hashlib + +# +# The dumbest preprocessor in the world +# Extract macro name from an header file and store them in an array +# No processing is done here, so they are raw values here and it does not match what actually enabled +# in the file (since you can have #if SOMETHING_UNDEFINED / #define BOB / #endif) +# But it's useful to filter the useful macro spit out by the preprocessor from noise from the system +# headers. +# +def extract_defines(filepath): + f = open(filepath).read().split("\n") + a = [] + for line in f: + sline = line.strip(" \t\n\r") + if sline[:7] == "#define": + # Extract the key here (we don't care about the value) + kv = sline[8:].strip().split(' ') + a.append(kv[0]) + return a + +# Compute the SHA256 hash of a file +def get_file_sha256sum(filepath): + sha256_hash = hashlib.sha256() + with open(filepath,"rb") as f: + # Read and update hash string value in blocks of 4K + for byte_block in iter(lambda: f.read(4096),b""): + sha256_hash.update(byte_block) + return sha256_hash.hexdigest() + +# +# Compress a JSON file into a zip file +# +import zipfile +def compress_file(filepath, outputbase): + with zipfile.ZipFile(outputbase + '.zip', 'w', compression=zipfile.ZIP_BZIP2, compresslevel=9) as zipf: + zipf.write(filepath, compress_type=zipfile.ZIP_BZIP2, compresslevel=9) + +# +# Compute the build signature. The idea is to extract all defines in the configuration headers +# to build a unique reversible signature from this build so it can be included in the binary +# We can reverse the signature to get a 1:1 equivalent configuration file +# +def compute_build_signature(env): + if 'BUILD_SIGNATURE' in env: + return + + # Definitions from these files will be kept + files_to_keep = [ 'Marlin/Configuration.h', 'Marlin/Configuration_adv.h' ] + + build_dir=os.path.join(env['PROJECT_BUILD_DIR'], env['PIOENV']) + + # Check if we can skip processing + hashes = '' + for header in files_to_keep: + hashes += get_file_sha256sum(header)[0:10] + + marlin_json = os.path.join(build_dir, 'marlin_config.json') + marlin_zip = os.path.join(build_dir, 'mc') + + # Read existing config file + try: + with open(marlin_json, 'r') as infile: + conf = json.load(infile) + if conf['__INITIAL_HASH'] == hashes: + # Same configuration, skip recomputing the building signature + compress_file(marlin_json, marlin_zip) + return + except: + pass + + # Get enabled config options based on preprocessor + from preprocessor import run_preprocessor + complete_cfg = run_preprocessor(env) + + # Dumb #define extraction from the configuration files + real_defines = {} + all_defines = [] + for header in files_to_keep: + defines = extract_defines(header) + # To filter only the define we want + all_defines = all_defines + defines + # To remember from which file it cames from + real_defines[header.split('/')[-1]] = defines + + r = re.compile(r"\(+(\s*-*\s*_.*)\)+") + + # First step is to collect all valid macros + defines = {} + for line in complete_cfg: + + # Split the define from the value + key_val = line[8:].strip().decode().split(' ') + key, value = key_val[0], ' '.join(key_val[1:]) + + # Ignore values starting with two underscore, since it's low level + if len(key) > 2 and key[0:2] == "__" : + continue + # Ignore values containing a parenthesis (likely a function macro) + if '(' in key and ')' in key: + continue + + # Then filter dumb values + if r.match(value): + continue + + defines[key] = value if len(value) else "" + + if not 'CONFIGURATION_EMBEDDING' in defines: + return + + # Second step is to filter useless macro + resolved_defines = {} + for key in defines: + # Remove all boards now + if key[0:6] == "BOARD_" and key != "BOARD_INFO_NAME": + continue + # Remove all keys ending by "_NAME" as it does not make a difference to the configuration + if key[-5:] == "_NAME" and key != "CUSTOM_MACHINE_NAME": + continue + # Remove all keys ending by "_T_DECLARED" as it's a copy of not important system stuff + if key[-11:] == "_T_DECLARED": + continue + # Remove keys that are not in the #define list in the Configuration list + if not (key in all_defines) and key != "DETAILED_BUILD_VERSION" and key != "STRING_DISTRIBUTION_DATE": + continue + + # Don't be that smart guy here + resolved_defines[key] = defines[key] + + # Generate a build signature now + # We are making an object that's a bit more complex than a basic dictionary here + data = {} + data['__INITIAL_HASH'] = hashes + # First create a key for each header here + for header in real_defines: + data[header] = {} + + # Then populate the object where each key is going to (that's a O(N^2) algorithm here...) + for key in resolved_defines: + for header in real_defines: + if key in real_defines[header]: + data[header][key] = resolved_defines[key] + + # Append the source code version and date + data['VERSION'] = {} + data['VERSION']['DETAILED_BUILD_VERSION'] = resolved_defines['DETAILED_BUILD_VERSION'] + data['VERSION']['STRING_DISTRIBUTION_DATE'] = resolved_defines['STRING_DISTRIBUTION_DATE'] + try: + curver = subprocess.check_output(["git", "describe", "--match=NeVeRmAtCh", "--always"]).strip() + data['VERSION']['GIT_REF'] = curver.decode() + except: + pass + + with open(marlin_json, 'w') as outfile: + json.dump(data, outfile, separators=(',', ':')) + + # Compress the JSON file as much as we can + compress_file(marlin_json, marlin_zip) + + # Generate a C source file for storing this array + with open('Marlin/src/mczip.h','wb') as result_file: + result_file.write(b'#warning "Generated file \'mc.zip\' is embedded"\n') + result_file.write(b'const unsigned char mc_zip[] PROGMEM = {\n ') + count = 0 + for b in open(os.path.join(build_dir, 'mc.zip'), 'rb').read(): + result_file.write(b' 0x%02X,' % b) + count += 1 + if (count % 16 == 0): + result_file.write(b'\n ') + if (count % 16): + result_file.write(b'\n') + result_file.write(b'};\n') diff --git a/docs/ConfigEmbedding.md b/docs/ConfigEmbedding.md new file mode 100644 index 0000000000000..38db06b3df397 --- /dev/null +++ b/docs/ConfigEmbedding.md @@ -0,0 +1,19 @@ +# Configuration Embedding + +Starting with version 2.0.9.3, Marlin automatically extracts the configuration used to generate the firmware and stores it in the firmware binary. This is enabled by defining `CONFIGURATION_EMBEDDING` in `Configuration_adv.h`. + +## How it's done +To create the embedded configuration, we do a compiler pass to process the Configuration files and extract all active options. The active options are parsed into key/value pairs, serialized to JSON format, and stored in a file called `marlin_config.json`, which also includes specific build information (like the git revision, the build date, and some version information. The JSON file is then compressed in a ZIP archive called `.pio/build/mc.zip` which is converted into a C array and stored in a C++ file called `mc.h` which is included in the build. + +## Extracting configurations from a Marlin binary +To get the configuration out of a binary firmware, you'll need a non-write-protected SD card inserted into the printer while running the firmware. +Send the command `M503 C` to write the file `mc.zip` to the SD card. Copy the file to your computer, ideally in the same folder as the Marlin repository. + +Run the following commands to extract and apply the configuration: +``` +$ git checkout -f +$ unzip mc.zip +$ python buildroot/share/PlatformIO/scripts/mc-apply.py +``` + +This will attempt to update the configuration files to match the settings used for the original build. It will also dump the git reference used to build the code (which may be accessible if the firmware was built from the main repository. As a fallback it also includes the `STRING_DISTRIBUTION_DATE` which is unlikely to be modified in a fork). From a4678d9e2798f203054ffa7c796f7b5b063c36d4 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 14 Dec 2021 19:25:28 +1300 Subject: [PATCH 151/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20LCD=5FBED=5FLEVELI?= =?UTF-8?q?NG=20compile=20(#23298)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index c566e9b2a63df..9337cf4774ff6 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -345,7 +345,7 @@ void _lcd_draw_homing() { } } -#if HAS_LEVELING && DISABLED(SLIM_LCD_MENUS) +#if ENABLED(LCD_BED_LEVELING) || (HAS_LEVELING && DISABLED(SLIM_LCD_MENUS)) void _lcd_toggle_bed_leveling() { set_bed_leveling_enabled(!planner.leveling_active); } #endif From e57b7d043cfe8b25aca5e67bcb15b19515bba7d8 Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Wed, 15 Dec 2021 07:51:19 +0700 Subject: [PATCH 152/273] =?UTF-8?q?=F0=9F=9A=B8=20Change=20"SD"=20to=20"Me?= =?UTF-8?q?dia"=20or=20"SD/FD"=20(#23297)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../extui/ftdi_eve_touch_ui/pin_mappings.h | 4 ++-- Marlin/src/lcd/language/language_de.h | 2 +- Marlin/src/lcd/language/language_el.h | 2 +- Marlin/src/lcd/language/language_en.h | 4 ++-- Marlin/src/lcd/language/language_es.h | 22 +++++++++---------- Marlin/src/lcd/language/language_gl.h | 12 +++++----- Marlin/src/lcd/language/language_hu.h | 2 +- Marlin/src/lcd/language/language_it.h | 2 +- Marlin/src/lcd/language/language_pl.h | 2 +- Marlin/src/lcd/language/language_ru.h | 4 ++-- Marlin/src/lcd/language/language_sk.h | 2 +- Marlin/src/lcd/language/language_sv.h | 2 +- Marlin/src/lcd/language/language_uk.h | 4 ++-- Marlin/src/sd/cardreader.cpp | 2 +- 14 files changed, 33 insertions(+), 33 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h index 7c0bdd88e9205..34026f4a26e62 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/pin_mappings.h @@ -123,12 +123,12 @@ * 10 5V 5V 5V --> KILL [3] * * [1] This configuration allows daisy-chaining of the - * display and SD/USB on EXP2, except for [2] + * display and SD/FD on EXP2, except for [2] * * [2] The Ultimachine Einsy boards have a level shifter * on MISO enabled by SD_CSEL chip select, hence it * is not possible to run both the display and the - * SD/USB on EXP2. + * SD/FD on EXP2. * * [3] Archim Rambo provides 5V on this pin. On any other * board, divert this wire from the ribbon cable and diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 613880caa65d5..00f759a83afc8 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -42,7 +42,7 @@ namespace Language_de { LSTR MSG_MEDIA_INSERTED = _UxGT("Medium erkannt"); LSTR MSG_MEDIA_REMOVED = _UxGT("Medium entfernt"); LSTR MSG_MEDIA_WAITING = _UxGT("Warten auf Medium"); - LSTR MSG_SD_INIT_FAIL = _UxGT("SD Init fehlgesch."); + LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Medium Init fehlgesch."); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Medium Lesefehler"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB Gerät entfernt"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB Start fehlge."); diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index 3d1a79ea922b7..567706180cb15 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -50,7 +50,7 @@ namespace Language_el { LSTR MSG_MEDIA_READ_ERROR = MEDIA_TYPE_EN _UxGT(" σφάλμα ανάγνωσης"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB αφαιρέθη"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("Αποτυχία εκκίνησης USB"); - LSTR MSG_SD_INIT_FAIL = _UxGT("Αποτυχία αρχικοποίησης SD"); + LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Αποτυχία αρχικοποίησης SD"); LSTR MSG_MAIN = _UxGT("Αρχική Οθόνη"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Αυτόματη εκκίνηση"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Απενεργοποίηση μοτέρ"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 9f60632152675..89b8fd7d77874 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -57,8 +57,8 @@ namespace Language_en { LSTR MSG_MEDIA_ABORTING = _UxGT("Aborting..."); LSTR MSG_MEDIA_INSERTED = MEDIA_TYPE_EN _UxGT(" Inserted"); LSTR MSG_MEDIA_REMOVED = MEDIA_TYPE_EN _UxGT(" Removed"); - LSTR MSG_MEDIA_WAITING = _UxGT("Waiting for card"); - LSTR MSG_SD_INIT_FAIL = _UxGT("SD Init Fail"); + LSTR MSG_MEDIA_WAITING = _UxGT("Waiting for ") MEDIA_TYPE_EN; + LSTR MSG_MEDIA_INIT_FAIL = MEDIA_TYPE_EN _UxGT(" Init Fail"); LSTR MSG_MEDIA_READ_ERROR = MEDIA_TYPE_EN _UxGT(" read error"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB device removed"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB start failed"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 38f21985ecc8d..9c593215bbd7f 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -39,11 +39,11 @@ namespace Language_es { LSTR MSG_NO = _UxGT("NO"); LSTR MSG_BACK = _UxGT("Atrás"); LSTR MSG_MEDIA_ABORTING = _UxGT("Cancelando..."); - LSTR MSG_MEDIA_INSERTED = _UxGT("SD/USB insertado"); - LSTR MSG_MEDIA_REMOVED = _UxGT("SD/USB retirado"); - LSTR MSG_MEDIA_WAITING = _UxGT("Esperando al SD/USB"); - LSTR MSG_SD_INIT_FAIL = _UxGT("Fallo al iniciar SD"); - LSTR MSG_MEDIA_READ_ERROR = _UxGT("Error lectura SD/USB"); + LSTR MSG_MEDIA_INSERTED = _UxGT("SD/FD insertado"); + LSTR MSG_MEDIA_REMOVED = _UxGT("SD/FD retirado"); + LSTR MSG_MEDIA_WAITING = _UxGT("Esperando al SD/FD"); + LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Fallo al iniciar SD/FD"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Error lectura SD/FD"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbordamiento de subllamada"); @@ -325,7 +325,7 @@ namespace Language_es { LSTR MSG_ERR_EEPROM_CRC = _UxGT("Err: EEPROM CRC"); LSTR MSG_ERR_EEPROM_INDEX = _UxGT("Err: Índice EEPROM"); LSTR MSG_ERR_EEPROM_VERSION = _UxGT("Err: Versión EEPROM"); - LSTR MSG_MEDIA_UPDATE = _UxGT("Actualizar SD/USB"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Actualizar SD/FD"); LSTR MSG_RESET_PRINTER = _UxGT("Resetear Impresora"); LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Recargar"); LSTR MSG_INFO_SCREEN = _UxGT("Pantalla de Inf."); @@ -348,8 +348,8 @@ namespace Language_es { LSTR MSG_CANCEL_OBJECT = _UxGT("Cancelar Objeto"); LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Objeto ="); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Rec. Fallo electrico"); - LSTR MSG_MEDIA_MENU = _UxGT("Imprim. desde SD/USB"); - LSTR MSG_NO_MEDIA = _UxGT("SD/USB no presente"); + LSTR MSG_MEDIA_MENU = _UxGT("Imprim. desde SD/FD"); + LSTR MSG_NO_MEDIA = _UxGT("SD/FD no presente"); LSTR MSG_DWELL = _UxGT("Reposo..."); LSTR MSG_USERWAIT = _UxGT("Pulsar para Reanudar"); LSTR MSG_PRINT_PAUSED = _UxGT("Impresión Pausada"); @@ -381,9 +381,9 @@ namespace Language_es { LSTR MSG_FILAMENTUNLOAD = _UxGT("Descargar filamento"); LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Descargar fil. *"); LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Descargar todo"); - LSTR MSG_ATTACH_MEDIA = _UxGT("Iniciar SD/USB"); - LSTR MSG_CHANGE_MEDIA = _UxGT("Cambiar SD/USB"); - LSTR MSG_RELEASE_MEDIA = _UxGT("Lanzar SD/USB"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Iniciar SD/FD"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Cambiar SD/FD"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Lanzar SD/FD"); LSTR MSG_ZPROBE_OUT = _UxGT("Sonda Z fuera cama"); LSTR MSG_SKEW_FACTOR = _UxGT("Factor de desviación"); LSTR MSG_BLTOUCH = _UxGT("BLTouch"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index c17faa701460f..1f3acf5f09b0c 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -43,8 +43,8 @@ namespace Language_gl { LSTR MSG_MEDIA_ABORTING = _UxGT("Cancelando..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Tarxeta inserida"); LSTR MSG_MEDIA_REMOVED = _UxGT("Tarxeta retirada"); - LSTR MSG_MEDIA_WAITING = _UxGT("Agardando ao SD/USB"); - LSTR MSG_MEDIA_READ_ERROR = _UxGT("Erro lectura SD/USB"); + LSTR MSG_MEDIA_WAITING = _UxGT("Agardando ao SD/FD"); + LSTR MSG_MEDIA_READ_ERROR = _UxGT("Erro lectura SD/FD"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbord. Subch."); @@ -329,7 +329,7 @@ namespace Language_gl { LSTR MSG_ERR_EEPROM_INDEX = _UxGT("Erro: Índice EEPROM"); LSTR MSG_ERR_EEPROM_VERSION = _UxGT("Erro: Versión EEPROM"); LSTR MSG_SETTINGS_STORED = _UxGT("Config Gardada"); - LSTR MSG_MEDIA_UPDATE = _UxGT("Actualizar SD/USB"); + LSTR MSG_MEDIA_UPDATE = _UxGT("Actualizar SD/FD"); LSTR MSG_RESET_PRINTER = _UxGT("Reiniciar Impresora"); LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Recargar"); LSTR MSG_INFO_SCREEN = _UxGT("Información"); @@ -397,9 +397,9 @@ namespace Language_gl { LSTR MSG_FILAMENTUNLOAD = _UxGT("Descargar Filamento"); LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Descargar Filamento *"); LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Descargar Todo"); - LSTR MSG_ATTACH_MEDIA = _UxGT("Iniciar SD/USB"); - LSTR MSG_CHANGE_MEDIA = _UxGT("Cambiar SD/USB"); - LSTR MSG_RELEASE_MEDIA = _UxGT("Lanzar SD/USB"); + LSTR MSG_ATTACH_MEDIA = _UxGT("Iniciar SD/FD"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Cambiar SD/FD"); + LSTR MSG_RELEASE_MEDIA = _UxGT("Lanzar SD/FD"); LSTR MSG_ZPROBE_OUT = _UxGT("Sonda-Z fóra Cama"); LSTR MSG_SKEW_FACTOR = _UxGT("Factor de Desviación"); LSTR MSG_BLTOUCH = _UxGT("BLTouch"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index faa313e48af39..204091f5d5611 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -47,7 +47,7 @@ namespace Language_hu { LSTR MSG_MEDIA_INSERTED = _UxGT("Tároló behelyezve"); LSTR MSG_MEDIA_REMOVED = _UxGT("Tároló eltávolítva"); LSTR MSG_MEDIA_WAITING = _UxGT("Várakozás a tárolóra"); - LSTR MSG_SD_INIT_FAIL = _UxGT("SD-kártya hiba"); + LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Tároló-kártya hiba"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Tároló olvasási hiba"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB eltávolítva"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB eszköz hiba"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 1720c0a93ac80..780f4e9743e49 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -53,7 +53,7 @@ namespace Language_it { LSTR MSG_MEDIA_INSERTED = _UxGT("Media inserito"); LSTR MSG_MEDIA_REMOVED = _UxGT("Media rimosso"); LSTR MSG_MEDIA_WAITING = _UxGT("Aspettando media"); - LSTR MSG_SD_INIT_FAIL = _UxGT("Inizial.SD fallita"); + LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Iniz.Media fallita"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Err.leggendo media"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Dispos.USB rimosso"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("Avvio USB fallito"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 9105f58bdbb0b..bf94feea54ec6 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -53,7 +53,7 @@ namespace Language_pl { LSTR MSG_MEDIA_INSERTED = _UxGT("Karta włożona"); LSTR MSG_MEDIA_REMOVED = _UxGT("Karta usunięta"); LSTR MSG_MEDIA_WAITING = _UxGT("Oczekiwanie na kartę"); - LSTR MSG_SD_INIT_FAIL = _UxGT("Błąd inicializacji karty"); + LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Błąd inicializacji karty"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Bład odczytu karty"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Urządzenie USB usunięte"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("Błąd uruchomienia USB"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index e33018b0341c4..495410500a509 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -44,9 +44,9 @@ namespace Language_ru { LSTR MSG_MEDIA_REMOVED = _UxGT("SD карта извлечена"); LSTR MSG_MEDIA_WAITING = _UxGT("Вставьте SD карту"); #if LCD_WIDTH > 21 - LSTR MSG_SD_INIT_FAIL = _UxGT("Сбой инициализации SD"); + LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Сбой инициализации SD"); #else - LSTR MSG_SD_INIT_FAIL = _UxGT("Сбой инициализ. SD"); + LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Сбой инициализ. SD"); #endif LSTR MSG_MEDIA_READ_ERROR = _UxGT("Ошибка считывания"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB диск удалён"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 76e7f7fbd7a66..9ab08f2766388 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -56,7 +56,7 @@ namespace Language_sk { LSTR MSG_MEDIA_INSERTED = _UxGT("Karta vložená"); LSTR MSG_MEDIA_REMOVED = _UxGT("Karta vybraná"); LSTR MSG_MEDIA_WAITING = _UxGT("Čakám na kartu"); - LSTR MSG_SD_INIT_FAIL = _UxGT("Inicial. SD zlyhala"); + LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Inicial. SD zlyhala"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Chyba čítania karty"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB zaria. odstrán."); LSTR MSG_MEDIA_USB_FAILED = _UxGT("Chyba spúšťania USB"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index cdb902aef0697..69161d6b553b4 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -44,7 +44,7 @@ namespace Language_sv { LSTR MSG_MEDIA_INSERTED = _UxGT("Media Instatt"); LSTR MSG_MEDIA_REMOVED = _UxGT("Media Borttaget"); LSTR MSG_MEDIA_WAITING = _UxGT("Väntar på media"); - LSTR MSG_SD_INIT_FAIL = _UxGT("SD init misslyckades"); + LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Media init misslyckades"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Media läsningsfel"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB enhet borttagen"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB start misslyckad"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index afba537008c7a..23110b5e4db94 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -45,9 +45,9 @@ namespace Language_uk { LSTR MSG_MEDIA_REMOVED = _UxGT("SD-картка видалена"); LSTR MSG_MEDIA_WAITING = _UxGT("Вставте SD-картку"); #if LCD_WIDTH > 21 - LSTR MSG_SD_INIT_FAIL = _UxGT("Збій ініціалізації SD"); + LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Збій ініціалізації SD"); #else - LSTR MSG_SD_INIT_FAIL = _UxGT("Збій ініціаліз. SD"); + LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Збій ініціаліз. SD"); #endif LSTR MSG_MEDIA_READ_ERROR = _UxGT("Помилка зчитування"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB диск видалений"); diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index b2f950bc04fbf..da6e84c759429 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -457,7 +457,7 @@ void CardReader::mount() { cdroot(); #if ENABLED(USB_FLASH_DRIVE_SUPPORT) || PIN_EXISTS(SD_DETECT) else if (marlin_state != MF_INITIALIZING) - ui.set_status(GET_TEXT_F(MSG_SD_INIT_FAIL), -1); + ui.set_status(GET_TEXT_F(MSG_MEDIA_INIT_FAIL), -1); #endif ui.refresh(); From 2175d8aaee68c3555255279ee12da6deee034509 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 15 Dec 2021 01:03:24 +0000 Subject: [PATCH 153/273] [cron] Bump distribution date (2021-12-15) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 6133fd7b08005..75a96bb7de54b 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 "2021-12-14" +//#define STRING_DISTRIBUTION_DATE "2021-12-15" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2fab27fac8420..234c706a66195 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 "2021-12-14" + #define STRING_DISTRIBUTION_DATE "2021-12-15" #endif /** From 5f9140cccd31f22897dfe135c681f0888b12e041 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 16 Dec 2021 01:03:49 +0000 Subject: [PATCH 154/273] [cron] Bump distribution date (2021-12-16) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 75a96bb7de54b..6cf043df89644 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 "2021-12-15" +//#define STRING_DISTRIBUTION_DATE "2021-12-16" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 234c706a66195..1d3064d6ecb6d 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 "2021-12-15" + #define STRING_DISTRIBUTION_DATE "2021-12-16" #endif /** From 6dc056f77114a0c3e2cf68758eaa7cf41061e173 Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Thu, 16 Dec 2021 12:04:32 +0700 Subject: [PATCH 155/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20UTF-8=20errror=20i?= =?UTF-8?q?n=20configuration=20embed=20and=20retrieve=20=20(#23303)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit The feature added in commit b464a4b1a4ea9cca914126c5f50c3e7384108a5e introduced a UTF-8 encoding error for all users where UTF-8 is not the default codepage. --- buildroot/share/PlatformIO/scripts/signature.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/share/PlatformIO/scripts/signature.py b/buildroot/share/PlatformIO/scripts/signature.py index 53cf347eaad9c..654e3ea677383 100644 --- a/buildroot/share/PlatformIO/scripts/signature.py +++ b/buildroot/share/PlatformIO/scripts/signature.py @@ -12,7 +12,7 @@ # headers. # def extract_defines(filepath): - f = open(filepath).read().split("\n") + f = open(filepath, encoding="utf8").read().split("\n") a = [] for line in f: sline = line.strip(" \t\n\r") From a994a318ba99799fe749021a213b134f414705ff Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 17 Dec 2021 01:06:28 +0000 Subject: [PATCH 156/273] [cron] Bump distribution date (2021-12-17) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 6cf043df89644..516e710f043ea 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 "2021-12-16" +//#define STRING_DISTRIBUTION_DATE "2021-12-17" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 1d3064d6ecb6d..a6893d9fc691c 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 "2021-12-16" + #define STRING_DISTRIBUTION_DATE "2021-12-17" #endif /** From 9d2441f951da7a5def752105286834f40e0ed618 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 17 Dec 2021 15:57:16 -0600 Subject: [PATCH 157/273] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h | 2 +- docs/ConfigEmbedding.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) 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 2fda0fb2c0c26..cec1a838fc93d 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 @@ -150,7 +150,7 @@ * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) * RESET | 7 8 | PA9 (BTN_EN1) * (BTN_ENC) PA15 | 9 10 | PB5 (BEEPER) - * ------ + * ------ * EXP1 */ #define EXP1_09_PIN PA15 diff --git a/docs/ConfigEmbedding.md b/docs/ConfigEmbedding.md index 38db06b3df397..ed4ea39eda099 100644 --- a/docs/ConfigEmbedding.md +++ b/docs/ConfigEmbedding.md @@ -12,7 +12,7 @@ Send the command `M503 C` to write the file `mc.zip` to the SD card. Copy the fi Run the following commands to extract and apply the configuration: ``` $ git checkout -f -$ unzip mc.zip +$ unzip mc.zip $ python buildroot/share/PlatformIO/scripts/mc-apply.py ``` From 504e6fd786abeb06d39cb1cbb1dd83ab3acb1dd0 Mon Sep 17 00:00:00 2001 From: John Lagonikas <39417467+zeleps@users.noreply.github.com> Date: Sat, 18 Dec 2021 01:31:10 +0200 Subject: [PATCH 158/273] =?UTF-8?q?=F0=9F=94=A7=20Warning=20for=20IGNORE?= =?UTF-8?q?=5FTHERMOCOUPLE=5FERRORS=20(#23312)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/temperature.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 59d80e0ea8e77..341aec59b4b3e 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1353,6 +1353,8 @@ void Temperature::manage_heater() { if (degRedundant() > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.0) max_temp_error(H_REDUNDANT); if (degRedundant() < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + .01) min_temp_error(H_REDUNDANT); #endif + #else + #warning "Safety Alert! Disable IGNORE_THERMOCOUPLE_ERRORS for the final build!" #endif millis_t ms = millis(); From b16b1d1fc7e739ae57f80e02e3bfeb34cfe421f9 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 18 Dec 2021 01:07:50 +0000 Subject: [PATCH 159/273] [cron] Bump distribution date (2021-12-18) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 516e710f043ea..05316860bba03 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 "2021-12-17" +//#define STRING_DISTRIBUTION_DATE "2021-12-18" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a6893d9fc691c..95ca762b65cb2 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 "2021-12-17" + #define STRING_DISTRIBUTION_DATE "2021-12-18" #endif /** From b4727411d5a57a977625b484e3d22f4bea8f0790 Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Sun, 19 Dec 2021 05:33:21 +0700 Subject: [PATCH 160/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20loud=5Fkill=20heat?= =?UTF-8?q?er=20disable=20(#23314)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/temperature.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 341aec59b4b3e..dccdc55034fd0 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -983,8 +983,8 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) { marlin_state = MF_KILLED; + thermalManager.disable_all_heaters(); #if USE_BEEPER - thermalManager.disable_all_heaters(); for (uint8_t i = 20; i--;) { WRITE(BEEPER_PIN, HIGH); delay(25); From daec6c6bb9f3e42673a8e676bc51aacd7355ca41 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 18 Dec 2021 17:38:29 -0600 Subject: [PATCH 161/273] =?UTF-8?q?=F0=9F=93=9D=20Fix=20a=20config=20comme?= =?UTF-8?q?nt?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index eea15c9651aee..1878a6f25876d 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2416,7 +2416,7 @@ // Longer prime to clean out a SINGLENOZZLE #define TOOLCHANGE_FS_EXTRA_PRIME 0 // (mm) Extra priming length #define TOOLCHANGE_FS_PRIME_SPEED (4.6*60) // (mm/min) Extra priming feedrate - #define TOOLCHANGE_FS_WIPE_RETRACT 0 // (mm/min) Retract before cooling for less stringing, better wipe, etc. + #define TOOLCHANGE_FS_WIPE_RETRACT 0 // (mm) Retract before cooling for less stringing, better wipe, etc. // Cool after prime to reduce stringing #define TOOLCHANGE_FS_FAN -1 // Fan index or -1 to skip From 14ceccdbc6e1184f6c5786454d660d875627c852 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 19 Dec 2021 01:26:05 +0000 Subject: [PATCH 162/273] [cron] Bump distribution date (2021-12-19) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 05316860bba03..287dcce5ed88a 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 "2021-12-18" +//#define STRING_DISTRIBUTION_DATE "2021-12-19" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 95ca762b65cb2..fb0f53cd83069 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 "2021-12-18" + #define STRING_DISTRIBUTION_DATE "2021-12-19" #endif /** From ecaebe4363b2a817649ca37ae29365d5f1e382f4 Mon Sep 17 00:00:00 2001 From: Spencer Owen Date: Sat, 18 Dec 2021 18:58:46 -0700 Subject: [PATCH 163/273] =?UTF-8?q?=E2=9C=A8=20Creality3D=20V4.2.3=20/=20E?= =?UTF-8?q?nder-2=20Pro=20board=20(#23307)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 41 +++++++++--------- Marlin/src/pins/pins.h | 2 + Marlin/src/pins/stm32f1/pins_CREALITY_V423.h | 44 ++++++++++++++++++++ 3 files changed, 67 insertions(+), 20 deletions(-) create mode 100644 Marlin/src/pins/stm32f1/pins_CREALITY_V423.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 2fc08c8cc7c40..674d203027ddc 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -338,26 +338,27 @@ #define BOARD_CHITU3D_V6 4038 // Chitu3D TronXY X5SA V6 Board #define BOARD_CHITU3D_V9 4039 // Chitu3D TronXY X5SA V9 Board #define BOARD_CREALITY_V4 4040 // Creality v4.x (STM32F103RE) -#define BOARD_CREALITY_V427 4041 // Creality v4.2.7 (STM32F103RE) -#define BOARD_CREALITY_V4210 4042 // Creality v4.2.10 (STM32F103RE) as found in the CR-30 -#define BOARD_CREALITY_V431 4043 // Creality v4.3.1 (STM32F103RE) -#define BOARD_CREALITY_V431_A 4044 // Creality v4.3.1a (STM32F103RE) -#define BOARD_CREALITY_V431_B 4045 // Creality v4.3.1b (STM32F103RE) -#define BOARD_CREALITY_V431_C 4046 // Creality v4.3.1c (STM32F103RE) -#define BOARD_CREALITY_V431_D 4047 // Creality v4.3.1d (STM32F103RE) -#define BOARD_CREALITY_V452 4048 // Creality v4.5.2 (STM32F103RE) -#define BOARD_CREALITY_V453 4049 // Creality v4.5.3 (STM32F103RE) -#define BOARD_CREALITY_V24S1 4050 // Creality v2.4.S1 (STM32F103RE) v101 as found in the Ender 7 -#define BOARD_TRIGORILLA_PRO 4051 // Trigorilla Pro (STM32F103ZET6) -#define BOARD_FLY_MINI 4052 // FLYmaker FLY MINI (STM32F103RCT6) -#define BOARD_FLSUN_HISPEED 4053 // FLSUN HiSpeedV1 (STM32F103VET6) -#define BOARD_BEAST 4054 // STM32F103RET6 Libmaple-based controller -#define BOARD_MINGDA_MPX_ARM_MINI 4055 // STM32F103ZET6 Mingda MD-16 -#define BOARD_GTM32_PRO_VD 4056 // STM32F103VET6 controller -#define BOARD_ZONESTAR_ZM3E2 4057 // Zonestar ZM3E2 (STM32F103RCT6) -#define BOARD_ZONESTAR_ZM3E4 4058 // Zonestar ZM3E4 V1 (STM32F103VCT6) -#define BOARD_ZONESTAR_ZM3E4V2 4059 // Zonestar ZM3E4 V2 (STM32F103VCT6) -#define BOARD_ERYONE_ERY32_MINI 4060 // Eryone Ery32 mini (STM32F103VET6) +#define BOARD_CREALITY_V423 4041 // Creality v4.2.3 (STM32F103RE) +#define BOARD_CREALITY_V427 4042 // Creality v4.2.7 (STM32F103RE) +#define BOARD_CREALITY_V4210 4043 // Creality v4.2.10 (STM32F103RE) as found in the CR-30 +#define BOARD_CREALITY_V431 4044 // Creality v4.3.1 (STM32F103RE) +#define BOARD_CREALITY_V431_A 4045 // Creality v4.3.1a (STM32F103RE) +#define BOARD_CREALITY_V431_B 4046 // Creality v4.3.1b (STM32F103RE) +#define BOARD_CREALITY_V431_C 4047 // Creality v4.3.1c (STM32F103RE) +#define BOARD_CREALITY_V431_D 4048 // Creality v4.3.1d (STM32F103RE) +#define BOARD_CREALITY_V452 4049 // Creality v4.5.2 (STM32F103RE) +#define BOARD_CREALITY_V453 4050 // Creality v4.5.3 (STM32F103RE) +#define BOARD_CREALITY_V24S1 4051 // Creality v2.4.S1 (STM32F103RE) v101 as found in the Ender 7 +#define BOARD_TRIGORILLA_PRO 4052 // Trigorilla Pro (STM32F103ZET6) +#define BOARD_FLY_MINI 4053 // FLYmaker FLY MINI (STM32F103RCT6) +#define BOARD_FLSUN_HISPEED 4054 // FLSUN HiSpeedV1 (STM32F103VET6) +#define BOARD_BEAST 4055 // STM32F103RET6 Libmaple-based controller +#define BOARD_MINGDA_MPX_ARM_MINI 4056 // STM32F103ZET6 Mingda MD-16 +#define BOARD_GTM32_PRO_VD 4057 // STM32F103VET6 controller +#define BOARD_ZONESTAR_ZM3E2 4058 // Zonestar ZM3E2 (STM32F103RCT6) +#define BOARD_ZONESTAR_ZM3E4 4059 // Zonestar ZM3E4 V1 (STM32F103VCT6) +#define BOARD_ZONESTAR_ZM3E4V2 4060 // Zonestar ZM3E4 V2 (STM32F103VCT6) +#define BOARD_ERYONE_ERY32_MINI 4061 // Eryone Ery32 mini (STM32F103VET6) // // ARM Cortex-M4F diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 7759aeb7b7d12..54967197f0676 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -557,6 +557,8 @@ #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V4210) #include "stm32f1/pins_CREALITY_V4210.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple +#elif MB(CREALITY_V423) + #include "stm32f1/pins_CREALITY_V423.h" // STM32F1 env:STM32F103RET6_creality #elif MB(CREALITY_V427) #include "stm32f1/pins_CREALITY_V427.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V431, CREALITY_V431_A, CREALITY_V431_B, CREALITY_V431_C, CREALITY_V431_D) diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V423.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V423.h new file mode 100644 index 0000000000000..186051c1fcb08 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V423.h @@ -0,0 +1,44 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * CREALITY v4.2.3 (STM32F103) board pin assignments + */ + +#define BOARD_INFO_NAME "Creality v4.2.3" +#define DEFAULT_MACHINE_NAME "Creality3D" + +// +// Heaters +// +#define HEATER_BED_PIN PB10 // HOT BED + +#include "pins_CREALITY_V4.h" + +// +// Encoder +// +#if BTN_EN1 == PB10 + #undef BTN_EN1 + #define BTN_EN1 PA2 // Rotary Encoder +#endif From a055898870d2aac8d0d36a4d0b55846cdca1a808 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 20 Dec 2021 01:06:18 +0000 Subject: [PATCH 164/273] [cron] Bump distribution date (2021-12-20) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 287dcce5ed88a..e952cf1ab3daf 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 "2021-12-19" +//#define STRING_DISTRIBUTION_DATE "2021-12-20" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index fb0f53cd83069..a6019419b1d61 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 "2021-12-19" + #define STRING_DISTRIBUTION_DATE "2021-12-20" #endif /** From 9d4275506862e6d8029c0152c1d16ee737a4fa64 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 8 Jul 2021 01:33:49 -0500 Subject: [PATCH 165/273] =?UTF-8?q?=F0=9F=8E=A8=20Update=20SKR=20V2=20pins?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) 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 d4e07bb8b782c..196ca46319989 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 @@ -366,12 +366,12 @@ // #if SD_CONNECTION_IS(LCD) - #define SDSS PA4 + #define SDSS EXP2_07_PIN #define SD_SS_PIN SDSS - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PC4 + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN + #define SD_DETECT_PIN EXP2_04_PIN #elif SD_CONNECTION_IS(ONBOARD) From ba3239145429e15901bb642a7225204f95b8e308 Mon Sep 17 00:00:00 2001 From: GHGiampy <83699429+GHGiampy@users.noreply.github.com> Date: Mon, 20 Dec 2021 09:44:43 +0100 Subject: [PATCH 166/273] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Opt?= =?UTF-8?q?ion=20allowing=20>=20127=20Neopixels=20(#23322)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/leds/neopixel.cpp | 4 ++-- Marlin/src/feature/leds/neopixel.h | 14 +++++++++++--- Marlin/src/gcode/feature/leds/M150.cpp | 2 +- 3 files changed, 14 insertions(+), 6 deletions(-) diff --git a/Marlin/src/feature/leds/neopixel.cpp b/Marlin/src/feature/leds/neopixel.cpp index 2654e9a1df5a6..3569cb180d53b 100644 --- a/Marlin/src/feature/leds/neopixel.cpp +++ b/Marlin/src/feature/leds/neopixel.cpp @@ -35,7 +35,7 @@ #endif Marlin_NeoPixel neo; -int8_t Marlin_NeoPixel::neoindex; +pixel_index_t Marlin_NeoPixel::neoindex; Adafruit_NeoPixel Marlin_NeoPixel::adaneo1(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEOPIXEL_TYPE + NEO_KHZ800); #if CONJOINED_NEOPIXEL @@ -116,7 +116,7 @@ void Marlin_NeoPixel::init() { Marlin_NeoPixel2 neo2; - int8_t Marlin_NeoPixel2::neoindex; + pixel_index_t Marlin_NeoPixel2::neoindex; Adafruit_NeoPixel Marlin_NeoPixel2::adaneo(NEOPIXEL2_PIXELS, NEOPIXEL2_PIN, NEOPIXEL2_TYPE); void Marlin_NeoPixel2::set_color(const uint32_t color) { diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h index b2c16459f5046..814ae9c8d839d 100644 --- a/Marlin/src/feature/leds/neopixel.h +++ b/Marlin/src/feature/leds/neopixel.h @@ -25,6 +25,8 @@ * NeoPixel support */ +#define MAX_NEOPIXELS 127 + #ifndef _NEOPIXEL_INCLUDE_ #error "Always include 'leds.h' and not 'neopixel.h' directly." #endif @@ -63,7 +65,13 @@ #endif // ------------------------ -// Function prototypes +// Types +// ------------------------ + +typedef IF<(MAX_NEOPIXELS > 127), int16_t, int8_t>::type pixel_index_t; + +// ------------------------ +// Classes // ------------------------ class Marlin_NeoPixel { @@ -74,7 +82,7 @@ class Marlin_NeoPixel { #endif public: - static int8_t neoindex; + static pixel_index_t neoindex; static void init(); static void set_color_startup(const uint32_t c); @@ -150,7 +158,7 @@ extern Marlin_NeoPixel neo; static Adafruit_NeoPixel adaneo; public: - static int8_t neoindex; + static pixel_index_t neoindex; static void init(); static void set_color_startup(const uint32_t c); diff --git a/Marlin/src/gcode/feature/leds/M150.cpp b/Marlin/src/gcode/feature/leds/M150.cpp index 45278fe1f5d68..f01c220d01311 100644 --- a/Marlin/src/gcode/feature/leds/M150.cpp +++ b/Marlin/src/gcode/feature/leds/M150.cpp @@ -54,7 +54,7 @@ */ void GcodeSuite::M150() { #if ENABLED(NEOPIXEL_LED) - const int8_t index = parser.intval('I', -1); + const pixel_index_t index = parser.intval('I', -1); #if ENABLED(NEOPIXEL2_SEPARATE) int8_t brightness = neo.brightness(), unit = parser.intval('S', -1); switch (unit) { From b06f871dd094308828922039ea9923c89fd772a7 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 21 Dec 2021 01:08:00 +0000 Subject: [PATCH 167/273] [cron] Bump distribution date (2021-12-21) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e952cf1ab3daf..222ecc9393b97 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 "2021-12-20" +//#define STRING_DISTRIBUTION_DATE "2021-12-21" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a6019419b1d61..b5f62034aff2e 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 "2021-12-20" + #define STRING_DISTRIBUTION_DATE "2021-12-21" #endif /** From f374fa0eb8cfa60981b25cb99856c14328fd703e Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Tue, 21 Dec 2021 01:26:31 -0600 Subject: [PATCH 168/273] =?UTF-8?q?=F0=9F=9A=91=EF=B8=8F=20FAST=5FPWM=5FFA?= =?UTF-8?q?N=20default=201KHz=20base=20freq.=20(#23326)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/inc/Conditionals_post.h | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 971318518d0f7..7fb839550671a 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2668,10 +2668,14 @@ #endif /** - * FAST PWM FAN Settings + * FAST PWM FAN default PWM frequency */ -#if ENABLED(FAST_PWM_FAN) && !defined(FAST_PWM_FAN_FREQUENCY) - #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) // Fan frequency default +#if !defined(FAST_PWM_FAN_FREQUENCY) && ENABLED(FAST_PWM_FAN) + #ifdef __AVR__ + #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) + #else + #define FAST_PWM_FAN_FREQUENCY 1000U + #endif #endif /** From 9cee62681232f154b411a606f1f49f0dd80a49ac Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Wed, 22 Dec 2021 13:48:38 +1300 Subject: [PATCH 169/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Chitu=20Z=5FSTOP?= =?UTF-8?q?=5FPIN=20(#23330)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h index afe58df803d69..53b6797e91d27 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h @@ -23,6 +23,6 @@ #define BOARD_INFO_NAME "Chitu3D V5" -#define Z_STOP_PIN PG9 +#define Z_STOP_PIN PA14 #include "pins_CHITU3D_common.h" From fdd37a84a290bfd55311a200018e7fdcf63df079 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 22 Dec 2021 01:07:10 +0000 Subject: [PATCH 170/273] [cron] Bump distribution date (2021-12-22) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 222ecc9393b97..ddabd7b152e71 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 "2021-12-21" +//#define STRING_DISTRIBUTION_DATE "2021-12-22" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b5f62034aff2e..68cfee56e1316 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 "2021-12-21" + #define STRING_DISTRIBUTION_DATE "2021-12-22" #endif /** From c1dba3d02888824400413fdf366c1fa574cbb587 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Wed, 22 Dec 2021 15:44:04 +1300 Subject: [PATCH 171/273] =?UTF-8?q?=E2=9C=A8=20Option=20to=20reset=20EEPRO?= =?UTF-8?q?M=20on=20first=20run=20(#23276)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 1 + Marlin/src/module/settings.cpp | 76 ++++++++++++++----- .../PlatformIO/scripts/preflight-checks.py | 11 ++- 3 files changed, 68 insertions(+), 20 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 71a92113300c6..bb89bc14a3752 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1837,6 +1837,7 @@ #define EEPROM_BOOT_SILENT // Keep M503 quiet and only give errors during first load #if ENABLED(EEPROM_SETTINGS) //#define EEPROM_AUTO_INIT // Init EEPROM automatically on any errors. + //#define EEPROM_INIT_NOW // Init EEPROM on first boot after a new build. #endif // diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 8ccf773adc287..a9c771240c25c 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -36,7 +36,7 @@ */ // Change EEPROM version if the structure changes -#define EEPROM_VERSION "V85" +#define EEPROM_VERSION "V86" #define EEPROM_OFFSET 100 // Check the integrity of data offsets. @@ -198,20 +198,32 @@ static const feedRate_t _DMF[] PROGMEM = DEFAULT_MAX_FEEDRATE; */ typedef struct SettingsDataStruct { char version[4]; // Vnn\0 + #if ENABLED(EEPROM_INIT_NOW) + uint32_t build_hash; // Unique build hash + #endif uint16_t crc; // Data Checksum // // DISTINCT_E_FACTORS // - uint8_t esteppers; // DISTINCT_AXES - LINEAR_AXES + uint8_t e_factors; // DISTINCT_AXES - LINEAR_AXES + // + // Planner settings + // planner_settings_t planner_settings; xyze_float_t planner_max_jerk; // M205 XYZE planner.max_jerk float planner_junction_deviation_mm; // M205 J planner.junction_deviation_mm + // + // Home Offset + // xyz_pos_t home_offset; // M206 XYZ / M665 TPZ + // + // Hotend Offset + // #if HAS_HOTEND_OFFSET xyz_pos_t hotend_offset[HOTENDS - 1]; // M218 XYZ #endif @@ -649,13 +661,24 @@ void MarlinSettings::postprocess() { const char version[4] = EEPROM_VERSION; + #if ENABLED(EEPROM_INIT_NOW) + constexpr uint32_t strhash32(const char *s, const uint32_t h=0) { + return *s ? strhash32(s + 1, ((h + *s) << (*s & 3)) ^ *s) : h; + } + constexpr uint32_t build_hash = strhash32(__DATE__ __TIME__); + #endif + bool MarlinSettings::eeprom_error, MarlinSettings::validating; int MarlinSettings::eeprom_index; uint16_t MarlinSettings::working_crc; bool MarlinSettings::size_error(const uint16_t size) { if (size != datasize()) { - DEBUG_ERROR_MSG("EEPROM datasize error."); + DEBUG_ERROR_MSG("EEPROM datasize error." + #if ENABLED(MARLIN_DEV_MODE) + " (Actual:", size, " Expected:", datasize(), ")" + #endif + ); return true; } return false; @@ -675,13 +698,17 @@ void MarlinSettings::postprocess() { // Write or Skip version. (Flash doesn't allow rewrite without erase.) TERN(FLASH_EEPROM_EMULATION, EEPROM_SKIP, EEPROM_WRITE)(ver); - EEPROM_SKIP(working_crc); // Skip the checksum slot + #if ENABLED(EEPROM_INIT_NOW) + EEPROM_SKIP(build_hash); // Skip the hash slot + #endif + + EEPROM_SKIP(working_crc); // Skip the checksum slot working_crc = 0; // clear before first "real data" - const uint8_t esteppers = COUNT(planner.settings.axis_steps_per_mm) - LINEAR_AXES; - _FIELD_TEST(esteppers); - EEPROM_WRITE(esteppers); + const uint8_t e_factors = DISTINCT_AXES - (LINEAR_AXES); + _FIELD_TEST(e_factors); + EEPROM_WRITE(e_factors); // // Planner Motion @@ -1494,6 +1521,9 @@ void MarlinSettings::postprocess() { eeprom_index = EEPROM_OFFSET; EEPROM_WRITE(version); + #if ENABLED(EEPROM_INIT_NOW) + EEPROM_WRITE(build_hash); + #endif EEPROM_WRITE(final_crc); // Report storage size @@ -1527,9 +1557,6 @@ void MarlinSettings::postprocess() { char stored_ver[4]; EEPROM_READ_ALWAYS(stored_ver); - uint16_t stored_crc; - EEPROM_READ_ALWAYS(stored_crc); - // Version has to match or defaults are used if (strncmp(version, stored_ver, 3) != 0) { if (stored_ver[3] != '\0') { @@ -1543,14 +1570,25 @@ void MarlinSettings::postprocess() { eeprom_error = true; } else { + + // Optionally reset on the first boot after flashing + #if ENABLED(EEPROM_INIT_NOW) + uint32_t stored_hash; + EEPROM_READ_ALWAYS(stored_hash); + if (stored_hash != build_hash) { EEPROM_FINISH(); return true; } + #endif + + uint16_t stored_crc; + EEPROM_READ_ALWAYS(stored_crc); + float dummyf = 0; working_crc = 0; // Init to 0. Accumulated by EEPROM_READ - _FIELD_TEST(esteppers); + _FIELD_TEST(e_factors); - // Number of esteppers may change - uint8_t esteppers; - EEPROM_READ_ALWAYS(esteppers); + // Number of e_factors may change + uint8_t e_factors; + EEPROM_READ_ALWAYS(e_factors); // // Planner Motion @@ -1558,16 +1596,16 @@ void MarlinSettings::postprocess() { { // Get only the number of E stepper parameters previously stored // Any steppers added later are set to their defaults - uint32_t tmp1[LINEAR_AXES + esteppers]; - float tmp2[LINEAR_AXES + esteppers]; - feedRate_t tmp3[LINEAR_AXES + esteppers]; + uint32_t tmp1[LINEAR_AXES + e_factors]; + float tmp2[LINEAR_AXES + e_factors]; + feedRate_t tmp3[LINEAR_AXES + e_factors]; EEPROM_READ((uint8_t *)tmp1, sizeof(tmp1)); // max_acceleration_mm_per_s2 EEPROM_READ(planner.settings.min_segment_time_us); EEPROM_READ((uint8_t *)tmp2, sizeof(tmp2)); // axis_steps_per_mm EEPROM_READ((uint8_t *)tmp3, sizeof(tmp3)); // max_feedrate_mm_s if (!validating) LOOP_DISTINCT_AXES(i) { - const bool in = (i < esteppers + LINEAR_AXES); + const bool in = (i < e_factors + LINEAR_AXES); planner.settings.max_acceleration_mm_per_s2[i] = in ? tmp1[i] : pgm_read_dword(&_DMA[ALIM(i, _DMA)]); planner.settings.axis_steps_per_mm[i] = in ? tmp2[i] : pgm_read_float(&_DASU[ALIM(i, _DASU)]); planner.settings.max_feedrate_mm_s[i] = in ? tmp3[i] : pgm_read_float(&_DMF[ALIM(i, _DMF)]); @@ -2496,7 +2534,7 @@ void MarlinSettings::postprocess() { return success; } reset(); - #if ENABLED(EEPROM_AUTO_INIT) + #if EITHER(EEPROM_AUTO_INIT, EEPROM_INIT_NOW) (void)save(); SERIAL_ECHO_MSG("EEPROM Initialized"); #endif diff --git a/buildroot/share/PlatformIO/scripts/preflight-checks.py b/buildroot/share/PlatformIO/scripts/preflight-checks.py index 1837a7580d242..9f38ffe8bfa2b 100644 --- a/buildroot/share/PlatformIO/scripts/preflight-checks.py +++ b/buildroot/share/PlatformIO/scripts/preflight-checks.py @@ -81,10 +81,19 @@ def sanity_check_target(): # # Give warnings on every build # - warnfile = os.path.join(env['PROJECT_BUILD_DIR'], build_env, "src", "src", "inc", "Warnings.cpp.o") + srcpath = os.path.join(env['PROJECT_BUILD_DIR'], build_env, "src", "src") + warnfile = os.path.join(srcpath, "inc", "Warnings.cpp.o") if os.path.exists(warnfile): os.remove(warnfile) + # + # Rebuild 'settings.cpp' for EEPROM_INIT_NOW + # + if 'EEPROM_INIT_NOW' in env['MARLIN_FEATURES']: + setfile = os.path.join(srcpath, "module", "settings.cpp.o") + if os.path.exists(setfile): + os.remove(setfile) + # # Check for old files indicating an entangled Marlin (mixing old and new code) # From 2893048e2955963bb307a4ca67ec26bb336de2f5 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Tue, 21 Dec 2021 23:09:55 -0500 Subject: [PATCH 172/273] =?UTF-8?q?=E2=9C=A8=20BLTouch=20High=20Speed=20mo?= =?UTF-8?q?de=20runtime=20configuration=20(#22916)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 6 ++- Marlin/src/feature/bltouch.cpp | 24 ++++++------ Marlin/src/feature/bltouch.h | 15 +++++--- Marlin/src/gcode/bedlevel/G35.cpp | 6 ++- Marlin/src/gcode/calibrate/G34_M422.cpp | 6 ++- Marlin/src/gcode/probe/M401_M402.cpp | 20 ++++++++-- Marlin/src/inc/SanityCheck.h | 3 ++ Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/lcd/menu/menu_bed_corners.cpp | 21 ++++++----- Marlin/src/lcd/menu/menu_configuration.cpp | 14 +++++-- Marlin/src/lcd/menu/menu_tramming.cpp | 6 ++- Marlin/src/module/motion.cpp | 9 +++-- Marlin/src/module/probe.cpp | 17 ++++++--- Marlin/src/module/settings.cpp | 43 ++++++++++++++++------ 14 files changed, 132 insertions(+), 59 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 1878a6f25876d..e50e0cde8954a 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -897,12 +897,14 @@ //#define BLTOUCH_FORCE_MODE_SET /** - * Use "HIGH SPEED" mode for probing. + * Enable "HIGH SPEED" option for probing. * Danger: Disable if your probe sometimes fails. Only suitable for stable well-adjusted systems. * This feature was designed for Deltabots with very fast Z moves; however, higher speed Cartesians * might be able to use it. If the machine can't raise Z fast enough the BLTouch may go into ALARM. + * + * Set the default state here, change with 'M401 S' or UI, use M500 to save, M502 to reset. */ - //#define BLTOUCH_HS_MODE + //#define BLTOUCH_HS_MODE true // Safety: Enable voltage mode settings in the LCD menu. //#define BLTOUCH_LCD_VOLTAGE_MENU diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp index 49a10f62b1559..d3348e79f0b93 100644 --- a/Marlin/src/feature/bltouch.cpp +++ b/Marlin/src/feature/bltouch.cpp @@ -28,7 +28,12 @@ BLTouch bltouch; -bool BLTouch::last_written_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain +bool BLTouch::od_5v_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain +#ifdef BLTOUCH_HS_MODE + bool BLTouch::high_speed_mode; // Initialized by settings.load, 0 = Low Speed; 1 = High Speed +#else + constexpr bool BLTouch::high_speed_mode; +#endif #include "../module/servo.h" #include "../module/probe.h" @@ -64,17 +69,14 @@ void BLTouch::init(const bool set_voltage/*=false*/) { #else if (DEBUGGING(LEVELING)) { - DEBUG_ECHOLNPGM("last_written_mode - ", last_written_mode); - DEBUG_ECHOLNPGM("config mode - " - #if ENABLED(BLTOUCH_SET_5V_MODE) - "BLTOUCH_SET_5V_MODE" - #else - "OD" - #endif - ); + PGMSTR(mode0, "OD"); + PGMSTR(mode1, "5V"); + DEBUG_ECHOPGM("BLTouch Mode: "); + DEBUG_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); + DEBUG_ECHOLNPGM(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")"); } - const bool should_set = last_written_mode != ENABLED(BLTOUCH_SET_5V_MODE); + const bool should_set = od_5v_mode != ENABLED(BLTOUCH_SET_5V_MODE); #endif @@ -193,7 +195,7 @@ void BLTouch::mode_conv_proc(const bool M5V) { _mode_store(); if (M5V) _set_5V_mode(); else _set_OD_mode(); _stow(); - last_written_mode = M5V; + od_5v_mode = M5V; } #endif // BLTOUCH diff --git a/Marlin/src/feature/bltouch.h b/Marlin/src/feature/bltouch.h index 9ecccb4256f40..ae3ab66300365 100644 --- a/Marlin/src/feature/bltouch.h +++ b/Marlin/src/feature/bltouch.h @@ -23,10 +23,6 @@ #include "../inc/MarlinConfigPre.h" -#if DISABLED(BLTOUCH_HS_MODE) - #define BLTOUCH_SLOW_MODE 1 -#endif - // BLTouch commands are sent as servo angles typedef unsigned char BLTCommand; @@ -70,8 +66,17 @@ typedef unsigned char BLTCommand; class BLTouch { public: + static void init(const bool set_voltage=false); - static bool last_written_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain + static bool od_5v_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain + + #ifdef BLTOUCH_HS_MODE + static bool high_speed_mode; // Initialized by settings.load, 0 = Low Speed; 1 = High Speed + #else + static constexpr bool high_speed_mode = false; + #endif + + static inline float z_extra_clearance() { return high_speed_mode ? 7 : 0; } // DEPLOY and STOW are wrapped for error handling - these are used by homing and by probing static bool deploy() { return deploy_proc(); } diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index e45e18b7fbc2b..8cabb923825a7 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -33,6 +33,10 @@ #include "../../module/tool_change.h" #endif +#if ENABLED(BLTOUCH) + #include "../../feature/bltouch.h" +#endif + #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" @@ -102,7 +106,7 @@ void GcodeSuite::G35() { // In BLTOUCH HS mode, the probe travels in a deployed state. // Users of G35 might have a badly misaligned bed, so raise Z by the // length of the deployed pin (BLTOUCH stroke < 7mm) - do_blocking_move_to_z(SUM_TERN(BLTOUCH_HS_MODE, Z_CLEARANCE_BETWEEN_PROBES, 7)); + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES + TERN0(BLTOUCH, bltouch.z_extra_clearance())); const float z_probed_height = probe.probe_at_point(tramming_points[i], PROBE_PT_RAISE, 0, true); if (isnan(z_probed_height)) { diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 8f4eab2c9715b..328a40dbb46a1 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -45,6 +45,10 @@ #include "../../libs/least_squares_fit.h" #endif +#if ENABLED(BLTOUCH) + #include "../../feature/bltouch.h" +#endif + #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" @@ -149,7 +153,7 @@ void GcodeSuite::G34() { // In BLTOUCH HS mode, the probe travels in a deployed state. // Users of G34 might have a badly misaligned bed, so raise Z by the // length of the deployed pin (BLTOUCH stroke < 7mm) - #define Z_BASIC_CLEARANCE (Z_CLEARANCE_BETWEEN_PROBES + 7.0f * BOTH(BLTOUCH, BLTOUCH_HS_MODE)) + #define Z_BASIC_CLEARANCE (Z_CLEARANCE_BETWEEN_PROBES + TERN0(BLTOUCH, bltouch.z_extra_clearance())) // Compute a worst-case clearance height to probe from. After the first // iteration this will be re-calculated based on the actual bed position diff --git a/Marlin/src/gcode/probe/M401_M402.cpp b/Marlin/src/gcode/probe/M401_M402.cpp index bd9bb44c4061f..7cbae76f4b88e 100644 --- a/Marlin/src/gcode/probe/M401_M402.cpp +++ b/Marlin/src/gcode/probe/M401_M402.cpp @@ -28,13 +28,27 @@ #include "../../module/motion.h" #include "../../module/probe.h" +#ifdef BLTOUCH_HS_MODE + #include "../../feature/bltouch.h" +#endif + /** * M401: Deploy and activate the Z probe + * + * With BLTOUCH_HS_MODE: + * S Set High Speed (HS) Mode and exit without deploy */ void GcodeSuite::M401() { - probe.deploy(); - TERN_(PROBE_TARE, probe.tare()); - report_current_position(); + if (parser.seen('S')) { + #ifdef BLTOUCH_HS_MODE + bltouch.high_speed_mode = parser.value_bool(); + #endif + } + else { + probe.deploy(); + TERN_(PROBE_TARE, probe.tare()); + report_current_position(); + } } /** diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index a809fad132b30..fbc0e3d1f04dd 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1577,6 +1577,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif + #if ENABLED(BLTOUCH_HS_MODE) && BLTOUCH_HS_MODE == 0 + #error "BLTOUCH_HS_MODE must now be defined as true or false, indicating the default state." + #endif #if BLTOUCH_DELAY < 200 #error "BLTOUCH_DELAY less than 200 is unsafe and is not supported." #endif diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 89b8fd7d77874..1d8861b2c700d 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -491,6 +491,7 @@ namespace Language_en { LSTR MSG_BLTOUCH_STOW = _UxGT("Stow"); LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); + LSTR MSG_BLTOUCH_SPEED_MODE = _UxGT("High Speed"); LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 7bf247f40be29..5740978639568 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -217,13 +217,13 @@ static void _lcd_level_bed_corners_get_next_position() { bool _lcd_level_bed_corners_probe(bool verify=false) { if (verify) do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); // do clearance if needed - TERN_(BLTOUCH_SLOW_MODE, bltouch.deploy()); // Deploy in LOW SPEED MODE on every probe action + TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.deploy()); // Deploy in LOW SPEED MODE on every probe action do_blocking_move_to_z(last_z - LEVEL_CORNERS_PROBE_TOLERANCE, MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW)); // Move down to lower tolerance if (TEST(endstops.trigger_state(), Z_MIN_PROBE)) { // check if probe triggered endstops.hit_on_purpose(); set_current_from_steppers_for_axis(Z_AXIS); sync_plan_position(); - TERN_(BLTOUCH_SLOW_MODE, bltouch.stow()); // Stow in LOW SPEED MODE on every trigger + TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.stow()); // Stow in LOW SPEED MODE on every trigger // Triggered outside tolerance range? if (ABS(current_position.z - last_z) > LEVEL_CORNERS_PROBE_TOLERANCE) { last_z = current_position.z; // Above tolerance. Set a new Z for subsequent corners. @@ -249,7 +249,7 @@ static void _lcd_level_bed_corners_get_next_position() { } idle(); } - TERN_(BLTOUCH_SLOW_MODE, bltouch.stow()); + TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.stow()); ui.goto_screen(_lcd_draw_probing); return (probe_triggered); } @@ -263,13 +263,14 @@ static void _lcd_level_bed_corners_get_next_position() { do { ui.refresh(LCDVIEW_REDRAW_NOW); _lcd_draw_probing(); // update screen with # of good points - do_blocking_move_to_z(SUM_TERN(BLTOUCH_HS_MODE, current_position.z + LEVEL_CORNERS_Z_HOP, 7)); // clearance + + do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP + TERN0(BLTOUCH, bltouch.z_extra_clearance())); // clearance _lcd_level_bed_corners_get_next_position(); // Select next corner coordinates current_position -= probe.offset_xy; // Account for probe offsets do_blocking_move_to_xy(current_position); // Goto corner - TERN_(BLTOUCH_HS_MODE, bltouch.deploy()); // Deploy in HIGH SPEED MODE + TERN_(BLTOUCH, if (bltouch.high_speed_mode) bltouch.deploy()); // Deploy in HIGH SPEED MODE if (!_lcd_level_bed_corners_probe()) { // Probe down to tolerance if (_lcd_level_bed_corners_raise()) { // Prompt user to raise bed if needed #if ENABLED(LEVEL_CORNERS_VERIFY_RAISED) // Verify @@ -290,10 +291,12 @@ static void _lcd_level_bed_corners_get_next_position() { } while (good_points < nr_edge_points); // loop until all points within tolerance - #if ENABLED(BLTOUCH_HS_MODE) - // In HIGH SPEED MODE do clearance and stow at the very end - do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); - bltouch.stow(); + #if ENABLED(BLTOUCH) + if (bltouch.high_speed_mode) + // In HIGH SPEED MODE do clearance and stow at the very end + do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); + bltouch.stow(); + } #endif ui.goto_screen(_lcd_draw_level_prompt); // prompt for bed leveling diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index cd8bad9c8ba4c..19b3dcbafbbe2 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -217,11 +217,14 @@ void menu_advanced_settings(); #if ENABLED(BLTOUCH_LCD_VOLTAGE_MENU) void bltouch_report() { - SERIAL_ECHOLNPGM("EEPROM Last BLTouch Mode - ", bltouch.last_written_mode); - SERIAL_ECHOLNPGM("Configuration BLTouch Mode - " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD")); + PGMSTR(mode0, "OD"); + PGMSTR(mode1, "5V"); + SERIAL_ECHOPGM("BLTouch Mode: "); + SERIAL_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); + SERIAL_ECHOLNPGM(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")"); char mess[21]; - strcpy_P(mess, PSTR("BLTouch Mode - ")); - strcpy_P(&mess[15], bltouch.last_written_mode ? PSTR("5V") : PSTR("OD")); + strcpy_P(mess, PSTR("BLTouch Mode: ")); + strcpy_P(&mess[15], bltouch.od_5v_mode ? mode1 : mode0); ui.set_status(mess); ui.return_to_status(); } @@ -235,6 +238,9 @@ void menu_advanced_settings(); ACTION_ITEM(MSG_BLTOUCH_DEPLOY, bltouch._deploy); ACTION_ITEM(MSG_BLTOUCH_STOW, bltouch._stow); ACTION_ITEM(MSG_BLTOUCH_SW_MODE, bltouch._set_SW_mode); + #ifdef BLTOUCH_HS_MODE + EDIT_ITEM(bool, MSG_BLTOUCH_SPEED_MODE, &bltouch.high_speed_mode); + #endif #if ENABLED(BLTOUCH_LCD_VOLTAGE_MENU) CONFIRM_ITEM(MSG_BLTOUCH_5V_MODE, MSG_BLTOUCH_5V_MODE, MSG_BUTTON_CANCEL, bltouch._set_5V_mode, nullptr, GET_TEXT(MSG_BLTOUCH_MODE_CHANGE)); CONFIRM_ITEM(MSG_BLTOUCH_OD_MODE, MSG_BLTOUCH_OD_MODE, MSG_BUTTON_CANCEL, bltouch._set_OD_mode, nullptr, GET_TEXT(MSG_BLTOUCH_MODE_CHANGE)); diff --git a/Marlin/src/lcd/menu/menu_tramming.cpp b/Marlin/src/lcd/menu/menu_tramming.cpp index 8e9d4b3942b65..4033421b5673d 100644 --- a/Marlin/src/lcd/menu/menu_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_tramming.cpp @@ -36,6 +36,10 @@ #include "../../module/probe.h" #include "../../gcode/queue.h" +#if ENABLED(BLTOUCH) + #include "../../feature/bltouch.h" +#endif + //#define DEBUG_OUT 1 #include "../../core/debug_out.h" @@ -51,7 +55,7 @@ static int8_t reference_index; // = 0 static bool probe_single_point() { do_blocking_move_to_z(TERN(BLTOUCH, Z_CLEARANCE_DEPLOY_PROBE, Z_CLEARANCE_BETWEEN_PROBES)); // Stow after each point with BLTouch "HIGH SPEED" mode for push-pin safety - const float z_probed_height = probe.probe_at_point(tramming_points[tram_index], TERN(BLTOUCH_HS_MODE, PROBE_PT_STOW, PROBE_PT_RAISE), 0, true); + const float z_probed_height = probe.probe_at_point(tramming_points[tram_index], TERN0(BLTOUCH, bltouch.high_speed_mode) ? PROBE_PT_STOW : PROBE_PT_RAISE, 0, true); z_measured[tram_index] = z_probed_height; if (reference_index < 0) reference_index = tram_index; move_to_tramming_wait_pos(); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 9ff668bf30d25..2248c52d85d91 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1803,8 +1803,8 @@ void prepare_line_to_destination() { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Home Fast: ", move_length, "mm"); do_homing_move(axis, move_length, 0.0, !use_probe_bump); - #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH_SLOW_MODE) - if (axis == Z_AXIS) bltouch.stow(); // Intermediate STOW (in LOW SPEED MODE) + #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) + if (axis == Z_AXIS && !bltouch.high_speed_mode) bltouch.stow(); // Intermediate STOW (in LOW SPEED MODE) #endif // If a second homing move is configured... @@ -1837,8 +1837,9 @@ void prepare_line_to_destination() { } #endif - #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH_SLOW_MODE) - if (axis == Z_AXIS && bltouch.deploy()) return; // Intermediate DEPLOY (in LOW SPEED MODE) + #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) + if (axis == Z_AXIS && !bltouch.high_speed_mode && bltouch.deploy()) + return; // Intermediate DEPLOY (in LOW SPEED MODE) #endif // Slow move towards endstop until triggered diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 7e08db7a5b6e3..540b4e1ae6a46 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -489,8 +489,10 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { #if BOTH(HAS_TEMP_HOTEND, WAIT_FOR_HOTEND) thermalManager.wait_for_hotend_heating(active_extruder); #endif - - if (TERN0(BLTOUCH_SLOW_MODE, bltouch.deploy())) return true; // Deploy in LOW SPEED MODE on every probe action + #if ENABLED(BLTOUCH) + if (!bltouch.high_speed_mode && bltouch.deploy()) + return true; // Deploy in LOW SPEED MODE on every probe action + #endif // Disable stealthChop if used. Enable diag1 pin on driver. #if ENABLED(SENSORLESS_PROBING) @@ -531,8 +533,10 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { set_homing_current(false); #endif - if (probe_triggered && TERN0(BLTOUCH_SLOW_MODE, bltouch.stow())) // Stow in LOW SPEED MODE on every trigger - return true; + #if ENABLED(BLTOUCH) + if (probe_triggered && !bltouch.high_speed_mode && bltouch.stow()) + return true; // Stow in LOW SPEED MODE on every trigger + #endif // Clear endstop flags endstops.hit_on_purpose(); @@ -762,8 +766,9 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai DEBUG_POS("", current_position); } - #if BOTH(BLTOUCH, BLTOUCH_HS_MODE) - if (bltouch.triggered()) bltouch._reset(); + #if ENABLED(BLTOUCH) + if (bltouch.high_speed_mode && bltouch.triggered()) + bltouch._reset(); #endif // On delta keep Z below clip height or do_blocking_move_to will abort diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index a9c771240c25c..8a32d4c57ea7b 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -301,7 +301,10 @@ typedef struct SettingsDataStruct { // // BLTOUCH // - bool bltouch_last_written_mode; + bool bltouch_od_5v_mode; + #ifdef BLTOUCH_HS_MODE + bool bltouch_high_speed_mode; // M401 S + #endif // // Kinematic Settings @@ -918,9 +921,15 @@ void MarlinSettings::postprocess() { // BLTOUCH // { - _FIELD_TEST(bltouch_last_written_mode); - const bool bltouch_last_written_mode = TERN(BLTOUCH, bltouch.last_written_mode, false); - EEPROM_WRITE(bltouch_last_written_mode); + _FIELD_TEST(bltouch_od_5v_mode); + const bool bltouch_od_5v_mode = TERN0(BLTOUCH, bltouch.od_5v_mode); + EEPROM_WRITE(bltouch_od_5v_mode); + + #ifdef BLTOUCH_HS_MODE + _FIELD_TEST(bltouch_high_speed_mode); + const bool bltouch_high_speed_mode = TERN0(BLTOUCH, bltouch.high_speed_mode); + EEPROM_WRITE(bltouch_high_speed_mode); + #endif } // @@ -1810,13 +1819,23 @@ void MarlinSettings::postprocess() { // BLTOUCH // { - _FIELD_TEST(bltouch_last_written_mode); + _FIELD_TEST(bltouch_od_5v_mode); #if ENABLED(BLTOUCH) - const bool &bltouch_last_written_mode = bltouch.last_written_mode; + const bool &bltouch_od_5v_mode = bltouch.od_5v_mode; #else - bool bltouch_last_written_mode; + bool bltouch_od_5v_mode; + #endif + EEPROM_READ(bltouch_od_5v_mode); + + #ifdef BLTOUCH_HS_MODE + _FIELD_TEST(bltouch_high_speed_mode); + #if ENABLED(BLTOUCH) + const bool &bltouch_high_speed_mode = bltouch.high_speed_mode; + #else + bool bltouch_high_speed_mode; + #endif + EEPROM_READ(bltouch_high_speed_mode); #endif - EEPROM_READ(bltouch_last_written_mode); } // @@ -2827,11 +2846,11 @@ void MarlinSettings::reset() { TERN_(HAS_PTC, ptc.reset()); // - // BLTOUCH + // BLTouch // - //#if ENABLED(BLTOUCH) - // bltouch.last_written_mode; - //#endif + #ifdef BLTOUCH_HS_MODE + bltouch.high_speed_mode = ENABLED(BLTOUCH_HS_MODE); + #endif // // Kinematic settings From c80ef71c6bd5b3fed36f1b6485d040391a70af70 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 23 Dec 2021 01:05:31 +0000 Subject: [PATCH 173/273] [cron] Bump distribution date (2021-12-23) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ddabd7b152e71..fac298246f225 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 "2021-12-22" +//#define STRING_DISTRIBUTION_DATE "2021-12-23" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 68cfee56e1316..e75f1a1788692 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 "2021-12-22" + #define STRING_DISTRIBUTION_DATE "2021-12-23" #endif /** From 1b876c170fc62abbb7381cfa79f2456ab4ec48ac Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Thu, 23 Dec 2021 07:49:15 +0100 Subject: [PATCH 174/273] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20settings=20G21=20r?= =?UTF-8?q?eport=20(#23338)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/settings.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 8a32d4c57ea7b..5fda608e38390 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -3171,12 +3171,13 @@ void MarlinSettings::reset() { // Announce current units, in case inches are being displayed // CONFIG_ECHO_HEADING("Linear Units"); + CONFIG_ECHO_START(); #if ENABLED(INCH_MODE_SUPPORT) - SERIAL_ECHO_MSG(" G2", AS_DIGIT(parser.linear_unit_factor == 1.0), " ;"); + SERIAL_ECHOPGM(" G2", AS_DIGIT(parser.linear_unit_factor == 1.0), " ;"); #else - SERIAL_ECHO_MSG(" G21 ;"); + SERIAL_ECHOPGM(" G21 ;"); #endif - gcode.say_units(); + gcode.say_units(); // " (in/mm)" // // M149 Temperature units From da67deb621bcf140e2f843c030d2b2b195c39ef9 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Thu, 23 Dec 2021 08:32:27 +0100 Subject: [PATCH 175/273] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20Fix=20missing=20br?= =?UTF-8?q?ace=20(#23337)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #22916 Co-authored-by: Scott Lahteine --- Marlin/src/feature/bltouch.cpp | 16 +++++++++------- Marlin/src/lcd/menu/menu_bed_corners.cpp | 2 +- Marlin/src/lcd/menu/menu_configuration.cpp | 8 +++++--- buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive | 4 ++-- 4 files changed, 17 insertions(+), 13 deletions(-) diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp index d3348e79f0b93..b1cc30bee0d99 100644 --- a/Marlin/src/feature/bltouch.cpp +++ b/Marlin/src/feature/bltouch.cpp @@ -68,13 +68,15 @@ void BLTouch::init(const bool set_voltage/*=false*/) { #else - if (DEBUGGING(LEVELING)) { - PGMSTR(mode0, "OD"); - PGMSTR(mode1, "5V"); - DEBUG_ECHOPGM("BLTouch Mode: "); - DEBUG_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); - DEBUG_ECHOLNPGM(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")"); - } + #ifdef DEBUG_OUT + if (DEBUGGING(LEVELING)) { + PGMSTR(mode0, "OD"); + PGMSTR(mode1, "5V"); + DEBUG_ECHOPGM("BLTouch Mode: "); + DEBUG_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); + DEBUG_ECHOLNPGM(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")"); + } + #endif const bool should_set = od_5v_mode != ENABLED(BLTOUCH_SET_5V_MODE); diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 5740978639568..38a074eb0128b 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -292,7 +292,7 @@ static void _lcd_level_bed_corners_get_next_position() { } while (good_points < nr_edge_points); // loop until all points within tolerance #if ENABLED(BLTOUCH) - if (bltouch.high_speed_mode) + if (bltouch.high_speed_mode) { // In HIGH SPEED MODE do clearance and stow at the very end do_blocking_move_to_z(current_position.z + LEVEL_CORNERS_Z_HOP); bltouch.stow(); diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 19b3dcbafbbe2..4cd43e787aca4 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -53,6 +53,8 @@ #include "../../libs/buzzer.h" #endif +#include "../../core/debug_out.h" + #define HAS_DEBUG_MENU ENABLED(LCD_PROGRESS_BAR_TEST) void menu_advanced_settings(); @@ -219,9 +221,9 @@ void menu_advanced_settings(); void bltouch_report() { PGMSTR(mode0, "OD"); PGMSTR(mode1, "5V"); - SERIAL_ECHOPGM("BLTouch Mode: "); - SERIAL_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); - SERIAL_ECHOLNPGM(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")"); + DEBUG_ECHOPGM("BLTouch Mode: "); + DEBUG_ECHOPGM_P(bltouch.od_5v_mode ? mode1 : mode0); + DEBUG_ECHOLNPGM(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")"); char mess[21]; strcpy_P(mess, PSTR("BLTouch Mode: ")); strcpy_P(&mess[15], bltouch.od_5v_mode ? mode1 : mode0); diff --git a/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive b/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive index 197ece5dfd66e..34bf77be27a48 100755 --- a/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive +++ b/buildroot/tests/BIGTREE_GTR_V1_0_usb_flash_drive @@ -10,8 +10,8 @@ restore_configs opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT 3 \ EXTRUDERS 8 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 TEMP_SENSOR_5 1 TEMP_SENSOR_6 1 TEMP_SENSOR_7 1 opt_enable SDSUPPORT USB_FLASH_DRIVE_SUPPORT USE_OTG_USB_HOST \ - REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER BLTOUCH NEOPIXEL_LED Z_SAFE_HOMING \ - FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE + REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER BLTOUCH LEVEL_BED_CORNERS LEVEL_CORNERS_USE_PROBE \ + NEOPIXEL_LED Z_SAFE_HOMING FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE # Not necessary to enable auto-fan for all extruders to hit problematic code paths opt_set E0_AUTO_FAN_PIN PC10 E1_AUTO_FAN_PIN PC11 E2_AUTO_FAN_PIN PC12 NEOPIXEL_PIN PF13 \ X_DRIVER_TYPE TMC2208 Y_DRIVER_TYPE TMC2130 \ From 3e737cbc910315364b77af6b1d6d3e92306f48f3 Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Thu, 23 Dec 2021 15:19:39 +0700 Subject: [PATCH 176/273] =?UTF-8?q?=F0=9F=94=A7=20Group=20FAST=5FPWM=5FFAN?= =?UTF-8?q?.options=20(#23331)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 3 --- Marlin/Configuration_adv.h | 29 +++++++++++++++------- Marlin/src/inc/Conditionals_post.h | 11 -------- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 1 - 4 files changed, 20 insertions(+), 24 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index bb89bc14a3752..c425746bb5d1c 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -2841,9 +2841,6 @@ // :[1,2,3,4,5,6,7,8] //#define NUM_M106_FANS 1 -// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino -//#define FAST_PWM_FAN - // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency // which is not as annoying as with the hardware PWM. On the other hand, if this frequency // is too low, you should also increment SOFT_PWM_SCALE. diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e50e0cde8954a..3eb836ec65620 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -549,18 +549,21 @@ //#define FAN_MAX_PWM 128 /** - * FAST PWM FAN Settings + * Fan Fast PWM * - * Use to change the FAST FAN PWM frequency (if enabled in Configuration.h) - * Combinations of PWM Modes, prescale values and TOP resolutions are used internally to produce a - * frequency as close as possible to the desired frequency. + * Combinations of PWM Modes, prescale values and TOP resolutions are used internally + * to produce a frequency as close as possible to the desired frequency. * - * FAST_PWM_FAN_FREQUENCY [undefined by default] + * FAST_PWM_FAN_FREQUENCY * Set this to your desired frequency. - * If left undefined this defaults to F = F_CPU/(2*255*1) - * i.e., F = 31.4kHz on 16MHz microcontrollers or F = 39.2kHz on 20MHz microcontrollers. - * These defaults are the same as with the old FAST_PWM_FAN implementation - no migration is required + * For AVR, if left undefined this defaults to F = F_CPU/(2*255*1) + * i.e., F = 31.4kHz on 16MHz microcontrollers or F = 39.2kHz on 20MHz microcontrollers. + * For non AVR, if left undefined this defaults to F = 1Khz. + * This F value is only to protect the hardware from an absence of configuration + * and not to complete it when users are not aware that the frequency must be specifically set to support the target board. + * * NOTE: Setting very low frequencies (< 10 Hz) may result in unexpected timer behavior. + * Setting very high frequencies can damage your hardware. * * USE_OCR2A_AS_TOP [undefined by default] * Boards that use TIMER2 for PWM have limitations resulting in only a few possible frequencies on TIMER2: @@ -570,9 +573,17 @@ * PWM on pin OC2A. Only use this option if you don't need PWM on 0C2A. (Check your schematic.) * USE_OCR2A_AS_TOP sacrifices duty cycle control resolution to achieve this broader range of frequencies. */ +//#define FAST_PWM_FAN // Increase the fan PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino #if ENABLED(FAST_PWM_FAN) - //#define FAST_PWM_FAN_FREQUENCY 31400 + //#define FAST_PWM_FAN_FREQUENCY 31400 // Define here to override the defaults below //#define USE_OCR2A_AS_TOP + #ifndef FAST_PWM_FAN_FREQUENCY + #ifdef __AVR__ + #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) + #else + #define FAST_PWM_FAN_FREQUENCY 1000U + #endif + #endif #endif /** diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 7fb839550671a..95c8f7737b311 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2667,17 +2667,6 @@ #error "FAN_OFF_PWM must be less than or equal to FAN_MIN_PWM." #endif -/** - * FAST PWM FAN default PWM frequency - */ -#if !defined(FAST_PWM_FAN_FREQUENCY) && ENABLED(FAST_PWM_FAN) - #ifdef __AVR__ - #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) - #else - #define FAST_PWM_FAN_FREQUENCY 1000U - #endif -#endif - /** * Controller Fan Settings */ diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index c6f1e014e0760..15c6955a83a81 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -95,7 +95,6 @@ #define FAN_MAX_PWM 255 #else #define FAST_PWM_FAN // STM32 Variant allow TIMER2 Hardware PWM - #define FAST_PWM_FAN_FREQUENCY 31400 // This frequency allow a good range, fan starts at 3%, half noise at 50% #define FAN_MIN_PWM 5 #define FAN_MAX_PWM 255 #endif From df9eb566c763be34f4c7ed51fc7526a840df860d Mon Sep 17 00:00:00 2001 From: MrAlvin Date: Thu, 23 Dec 2021 10:47:52 +0100 Subject: [PATCH 177/273] =?UTF-8?q?=F0=9F=9A=B8=20Show=20mm'ss=20during=20?= =?UTF-8?q?first=20hour=20(#23335)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/libs/duration_t.h | 28 +++++++++++++++++----------- 1 file changed, 17 insertions(+), 11 deletions(-) diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index 2528bcdbff89c..df2c9cd099c10 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -127,11 +127,11 @@ struct duration_t { * 59s */ char* toString(char * const buffer) const { - int y = this->year(), - d = this->day() % 365, - h = this->hour() % 24, - m = this->minute() % 60, - s = this->second() % 60; + const uint16_t y = this->year(), + d = this->day() % 365, + h = this->hour() % 24, + m = this->minute() % 60, + s = this->second() % 60; if (y) sprintf_P(buffer, PSTR("%iy %id %ih %im %is"), y, d, h, m, s); else if (d) sprintf_P(buffer, PSTR("%id %ih %im %is"), d, h, m, s); @@ -149,23 +149,29 @@ struct duration_t { * * Output examples: * 123456789 (strlen) + * 12'34 * 99:59 * 11d 12:33 */ uint8_t toDigital(char *buffer, bool with_days=false) const { - uint16_t h = uint16_t(this->hour()), - m = uint16_t(this->minute() % 60UL); + const uint16_t h = uint16_t(this->hour()), + m = uint16_t(this->minute() % 60UL); if (with_days) { - uint16_t d = this->day(); - sprintf_P(buffer, PSTR("%hud %02hu:%02hu"), d, h % 24, m); + const uint16_t d = this->day(); + sprintf_P(buffer, PSTR("%hud %02hu:%02hu"), d, h % 24, m); // 1d 23:45 return d >= 10 ? 9 : 8; } + else if (!h) { + const uint16_t s = uint16_t(this->second() % 60UL); + sprintf_P(buffer, PSTR("%02hu'%02hu"), m, s); // 12'34 + return 5; + } else if (h < 100) { - sprintf_P(buffer, PSTR("%02hu:%02hu"), h, m); + sprintf_P(buffer, PSTR("%02hu:%02hu"), h, m); // 12:34 return 5; } else { - sprintf_P(buffer, PSTR("%hu:%02hu"), h, m); + sprintf_P(buffer, PSTR("%hu:%02hu"), h, m); // 123:45 return 6; } } From ca0215ba646e410e4828ebf14c86e75fc8765eeb Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 24 Dec 2021 01:04:40 +0000 Subject: [PATCH 178/273] [cron] Bump distribution date (2021-12-24) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index fac298246f225..8dc516a329b20 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 "2021-12-23" +//#define STRING_DISTRIBUTION_DATE "2021-12-24" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e75f1a1788692..df523fb3891b4 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 "2021-12-23" + #define STRING_DISTRIBUTION_DATE "2021-12-24" #endif /** From 80a537cd13f386fe8140ca672c4aa51d597d5e21 Mon Sep 17 00:00:00 2001 From: Attila BODY Date: Fri, 24 Dec 2021 06:57:20 +0100 Subject: [PATCH 179/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Robin=20Nano=20v3?= =?UTF-8?q?=20filament=20runout=20pins=20(#23344)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/pins/mega/pins_OVERLORD.h | 2 +- Marlin/src/pins/pins_postprocess.h | 7 +++++-- Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h | 1 - Marlin/src/pins/sam/pins_RURAMPS4D_11.h | 6 ++---- Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 6 ++---- Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h | 2 +- Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h | 4 ++-- 7 files changed, 13 insertions(+), 15 deletions(-) diff --git a/Marlin/src/pins/mega/pins_OVERLORD.h b/Marlin/src/pins/mega/pins_OVERLORD.h index 0884d8ecb5142..98f8da571940d 100644 --- a/Marlin/src/pins/mega/pins_OVERLORD.h +++ b/Marlin/src/pins/mega/pins_OVERLORD.h @@ -49,7 +49,7 @@ #define Z_MIN_PROBE_PIN 46 // JP4, Tfeed1 #endif -#if ENABLED(FILAMENT_RUNOUT_SENSOR) +#ifndef FIL_RUNOUT_PIN #define FIL_RUNOUT_PIN 44 // JP3, Tfeed2 #endif diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 1e6703fd4a3a4..fe8c4c6c41aaf 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -546,14 +546,17 @@ #undef K_MAX_PIN #endif -// Filament Sensor first pin alias #if HAS_FILAMENT_SENSOR - #define FIL_RUNOUT1_PIN FIL_RUNOUT_PIN + #define FIL_RUNOUT1_PIN FIL_RUNOUT_PIN // Filament Sensor first pin alias #else #undef FIL_RUNOUT_PIN #undef FIL_RUNOUT1_PIN #endif +#if NUM_RUNOUT_SENSORS < 2 + #undef FIL_RUNOUT2_PIN +#endif + #ifndef LCD_PINS_D4 #define LCD_PINS_D4 -1 #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h index 79ac308ce71cb..0a94a582d43c4 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h @@ -134,7 +134,6 @@ #define FAN_PIN 9 #define FAN1_PIN 12 -#define NUM_RUNOUT_SENSORS 2 #define FIL_RUNOUT_PIN 22 #define FIL_RUNOUT2_PIN 21 diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index 5e612d3e8c22c..65ecd37e62da3 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -121,10 +121,8 @@ #define Z_MIN_PROBE_PIN 49 #endif -#if HAS_FILAMENT_SENSOR - #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN Y_MIN_PIN - #endif +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN Y_MIN_PIN #endif // diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 37a76c5278211..76a2d5a3985fd 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -109,10 +109,8 @@ #define Z_MIN_PROBE_PIN 49 #endif -#if HAS_FILAMENT_SENSOR - #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN Y_MIN_PIN - #endif +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN Y_MIN_PIN #endif // diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index 1b37940e2a0a6..a450515a79ffc 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -68,7 +68,7 @@ #if SERVO0_PIN == BEEPER_PIN #undef BEEPER_PIN #endif -#elif ENABLED(FILAMENT_RUNOUT_SENSOR) +#elif HAS_FILAMENT_SENSOR #ifndef FIL_RUNOUT_PIN #define FIL_RUNOUT_PIN 27 #endif 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 c2dea50b29884..bbf162bb0d980 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 @@ -145,10 +145,10 @@ #endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN MT_DET_1_PIN + #define FIL_RUNOUT_PIN PA4 #endif #ifndef FIL_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN MT_DET_2_PIN + #define FIL_RUNOUT2_PIN PE6 #endif #ifndef POWER_LOSS_PIN From 21cd71550663f46c361e6798c04ebcc0165391f3 Mon Sep 17 00:00:00 2001 From: Sola <42537573+solawc@users.noreply.github.com> Date: Fri, 24 Dec 2021 14:03:32 +0800 Subject: [PATCH 180/273] =?UTF-8?q?=E2=9C=A8=20MKS=20TinyBee=20board=20sup?= =?UTF-8?q?port=20(#23340)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-Authored-By: Sola <42537573+solawc@users.noreply.github.com> --- Marlin/src/core/boards.h | 1 + Marlin/src/pins/esp32/pins_MKS_TINYBEE.h | 207 +++++++++++++++++++++++ Marlin/src/pins/pins.h | 2 + ini/esp32.ini | 5 + 4 files changed, 215 insertions(+) create mode 100644 Marlin/src/pins/esp32/pins_MKS_TINYBEE.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 674d203027ddc..aee9b3c49287c 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -433,6 +433,7 @@ #define BOARD_FYSETC_E4 6005 // FYSETC E4 #define BOARD_PANDA_ZHU 6006 // Panda_ZHU #define BOARD_PANDA_M4 6007 // Panda_M4 +#define BOARD_MKS_TINYBEE 6008 // MKS TinyBee based on ESP32 (with I2S stepper stream) // // SAMD51 ARM Cortex M4 diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h new file mode 100644 index 0000000000000..bfa38adadf73d --- /dev/null +++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h @@ -0,0 +1,207 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * MRR ESPE pin assignments + * MRR ESPE is a 3D printer control board based on the ESP32 microcontroller. + * Supports 5 stepper drivers (using I2S stepper stream), heated bed, + * single hotend, and LCD controller. + */ + +#include "env_validate.h" + +#if EXTRUDERS > 2 || E_STEPPERS > 2 + #error "MKS ESP Nano only supports two E Steppers. Comment out this line to continue." +#elif HOTENDS > 2 + #error "MKS ESP Nano only supports two hotend / E-stepper. Comment out this line to continue." +#endif + +#define BOARD_INFO_NAME "MKS TinyBee" +#define BOARD_WEBSITE_URL "https://github.com/makerbase-mks" +#define DEFAULT_MACHINE_NAME BOARD_INFO_NAME + +// +// Servos +// +#define SERVO0_PIN 2 + +// +// Limit Switches +// +#define X_STOP_PIN 33 +#define Y_STOP_PIN 32 +#define Z_STOP_PIN 22 +//#define FIL_RUNOUT_PIN 35 + +// +// Enable I2S stepper stream +// +#define I2S_STEPPER_STREAM +#if ENABLED(I2S_STEPPER_STREAM) + #define I2S_WS 26 + #define I2S_BCK 25 + #define I2S_DATA 27 + #if ENABLED(LIN_ADVANCE) + #error "I2S stream is currently incompatible with LIN_ADVANCE." + #endif +#endif + +// +// Steppers +// +#define X_STEP_PIN 129 +#define X_DIR_PIN 130 +#define X_ENABLE_PIN 128 + +#define Y_STEP_PIN 132 +#define Y_DIR_PIN 133 +#define Y_ENABLE_PIN 131 + +#define Z_STEP_PIN 135 +#define Z_DIR_PIN 136 +#define Z_ENABLE_PIN 134 + +#define E0_STEP_PIN 138 +#define E0_DIR_PIN 139 +#define E0_ENABLE_PIN 137 + +#define E1_STEP_PIN 141 +#define E1_DIR_PIN 142 +#define E1_ENABLE_PIN 140 + +#define Z2_STEP_PIN 141 +#define Z2_DIR_PIN 142 +#define Z2_ENABLE_PIN 140 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 36 // Analog Input +#define TEMP_1_PIN 34 // Analog Input, you need set R6=0Ω and R7=NC +#define TEMP_BED_PIN 39 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 145 +#define HEATER_1_PIN 146 +#define FAN_PIN 147 +#define FAN1_PIN 148 +#define HEATER_BED_PIN 144 + +//#define CONTROLLER_FAN_PIN 148 +//#define E0_AUTO_FAN_PIN 148 // need to update Configuration_adv.h @section extruder +//#define E1_AUTO_FAN_PIN 149 // need to update Configuration_adv.h @section extruder + +// +// MicroSD card +// +#define SD_MOSI_PIN 23 +#define SD_MISO_PIN 19 +#define SD_SCK_PIN 18 +#define SDSS 5 +#define SD_DETECT_PIN 34 // IO34 default is SD_DET signal(Jump to SDDET) +#define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers + +/** + * ------ ------ + * (BEEPER) 149 |10 9 | 13 (BTN_ENC) (SPI MISO) 19 |10 9 | 18 (SPI SCK) + * (LCD_EN) 21 | 8 7 | 4 (LCD_RS) (BTN_EN1) 14 | 8 7 | 5 (SPI CS) + * (LCD_D4) 0 | 6 5 16 (LCD_D5) (BTN_EN2) 12 | 6 5 23 (SPI MOSI) + * (LCD_D6) 15 | 4 3 | 17 (LCD_D7) (SPI_DET) 34 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | 3.3V + * ------ ------ + * EXP1 EXP2 + */ + +#define EXP1_03_PIN 17 +#define EXP1_04_PIN 15 +#define EXP1_05_PIN 16 +#define EXP1_06_PIN 0 +#define EXP1_07_PIN 4 +#define EXP1_08_PIN 21 +#define EXP1_09_PIN 13 +#define EXP1_10_PIN 149 + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN 34 +#define EXP2_05_PIN 23 +#define EXP2_06_PIN 12 +#define EXP2_07_PIN 5 +#define EXP2_08_PIN 14 +#define EXP2_09_PIN 18 +#define EXP2_10_PIN 19 + +#if HAS_WIRED_LCD + + #define BEEPER_PIN 149 + #define BTN_ENC 13 + #define LCD_PINS_ENABLE 21 + #define LCD_PINS_RS 4 + #define BTN_EN1 14 + #define BTN_EN2 12 + #define LCD_BACKLIGHT_PIN -1 + + // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) + #if ENABLED(MKS_MINI_12864) + + //#define LCD_BACKLIGHT_PIN -1 + //#define LCD_RESET_PIN -1 + #define DOGLCD_A0 15 + #define DOGLCD_CS 16 + //#define DOGLCD_SCK 19 + //#define DOGLCD_MOSI 23 + + // Required for MKS_MINI_12864 with this board + //#define MKS_LCD12864B + + #elif ENABLED(MKS_MINI_12864_V3) + + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define LCD_PINS_DC DOGLCD_A0 + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN EXP1_06_PIN + #define NEOPIXEL_PIN EXP1_05_PIN + #define DOGLCD_MOSI EXP2_05_PIN + #define DOGLCD_SCK EXP2_09_PIN + #if SD_CONNECTION_IS(ONBOARD) + #define FORCE_SOFT_SPI + #endif + + #else // !MKS_MINI_12864 + + #define LCD_PINS_D4 0 + #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #define LCD_PINS_D5 16 + #define LCD_PINS_D6 15 + #define LCD_PINS_D7 17 + #endif + + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 600 + + #endif // !MKS_MINI_12864 + +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 54967197f0676..0f0f42508db04 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -711,6 +711,8 @@ #include "esp32/pins_PANDA_ZHU.h" // ESP32 env:PANDA #elif MB(PANDA_M4) #include "esp32/pins_PANDA_M4.h" // ESP32 env:PANDA +#elif MB(MKS_TINYBEE) + #include "esp32/pins_MKS_TINYBEE.h" // ESP32 env:mks_tinybee // // Adafruit Grand Central M4 (SAMD51 ARM Cortex-M4) diff --git a/ini/esp32.ini b/ini/esp32.ini index 9c0c44db67b97..0815486cc9935 100644 --- a/ini/esp32.ini +++ b/ini/esp32.ini @@ -37,3 +37,8 @@ lib_deps = ${common.lib_deps} board_build.partitions = Marlin/src/HAL/ESP32/esp32.csv upload_speed = 115200 monitor_speed = 115200 + +[env:mks_tinybee] +extends = env:esp32 +platform = espressif32@2.1.0 +board_build.partitions = default_8MB.csv From d5dff1948d900ce6fdec31e3f839e905ba09a46b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Dec 2021 01:46:51 -0600 Subject: [PATCH 181/273] =?UTF-8?q?=F0=9F=94=A7=20Sanity=20check=20MMU2=5F?= =?UTF-8?q?MENUS?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index fbc0e3d1f04dd..c8ac48f7cff53 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1070,7 +1070,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #elif ENABLED(MMU_EXTRUDER_SENSOR) && DISABLED(FILAMENT_RUNOUT_SENSOR) #error "MMU_EXTRUDER_SENSOR requires FILAMENT_RUNOUT_SENSOR. Enable it to continue." #elif ENABLED(MMU_EXTRUDER_SENSOR) && !HAS_LCD_MENU - #error "MMU_EXTRUDER_SENSOR requires an LCD supporting MarlinUI to be enabled." + #error "MMU_EXTRUDER_SENSOR requires an LCD supporting MarlinUI." + #elif ENABLED(MMU2_MENUS) && !HAS_LCD_MENU + #error "MMU2_MENUS requires an LCD supporting MarlinUI." #elif DISABLED(ADVANCED_PAUSE_FEATURE) static_assert(nullptr == strstr(MMU2_FILAMENT_RUNOUT_SCRIPT, "M600"), "ADVANCED_PAUSE_FEATURE is required to use M600 with PRUSA_MMU2(S) / HAS_EXTENDABLE_MMU(S)."); #endif From 6d09d1d7fb2ce06dfe2693d841e3d417fd33c1b2 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 25 Dec 2021 01:04:01 +0000 Subject: [PATCH 182/273] [cron] Bump distribution date (2021-12-25) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 8dc516a329b20..596e910a1f61b 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 "2021-12-24" +//#define STRING_DISTRIBUTION_DATE "2021-12-25" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index df523fb3891b4..b43547ef53c11 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 "2021-12-24" + #define STRING_DISTRIBUTION_DATE "2021-12-25" #endif /** From cd1920b35057ee21c77f568af996434303122494 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Dec 2021 20:59:28 -0600 Subject: [PATCH 183/273] =?UTF-8?q?=F0=9F=94=A8=20Ignore=20cmake=20generat?= =?UTF-8?q?ed=20build=20folder?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 2b40149b5f50f..0af55339d8aae 100755 --- a/.gitignore +++ b/.gitignore @@ -155,6 +155,7 @@ spi_flash.bin CMakeLists.txt src/CMakeLists.txt CMakeListsPrivate.txt +build/ # CLion cmake-build-* From 532f21f96f421e485b472025de2cde9677999179 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Dec 2021 21:32:00 -0600 Subject: [PATCH 184/273] =?UTF-8?q?=F0=9F=94=A8=20Ignore=20sublime=20works?= =?UTF-8?q?pace=20file?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 0af55339d8aae..72fd117bd2348 100755 --- a/.gitignore +++ b/.gitignore @@ -25,6 +25,7 @@ bdf2u8g marlin_config.json mczip.h *.gen +*.sublime-workspace # # OS From e211ff148c39bf5dace72de7cffbb83f19d3f1bf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Dec 2021 21:33:59 -0600 Subject: [PATCH 185/273] =?UTF-8?q?=E2=99=BB=EF=B8=8F=20Refactor=20HAL=20a?= =?UTF-8?q?s=20singleton=20(#23295)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/HAL.cpp | 14 +- Marlin/src/HAL/AVR/HAL.h | 170 +++++++++++++-------- Marlin/src/HAL/AVR/MarlinSerial.cpp | 4 +- Marlin/src/HAL/AVR/fast_pwm.cpp | 11 +- Marlin/src/HAL/AVR/timers.h | 4 +- Marlin/src/HAL/DUE/HAL.cpp | 45 ++---- Marlin/src/HAL/DUE/HAL.h | 132 ++++++++++------ Marlin/src/HAL/DUE/MarlinSerial.cpp | 4 +- Marlin/src/HAL/DUE/timers.h | 2 +- Marlin/src/HAL/ESP32/HAL.cpp | 35 +++-- Marlin/src/HAL/ESP32/HAL.h | 142 ++++++++++------- Marlin/src/HAL/ESP32/timers.h | 4 +- Marlin/src/HAL/LINUX/HAL.cpp | 39 ++--- Marlin/src/HAL/LINUX/HAL.h | 145 ++++++++++++------ Marlin/src/HAL/LINUX/arduino.cpp | 4 +- Marlin/src/HAL/LINUX/include/Arduino.h | 5 +- Marlin/src/HAL/LINUX/timers.h | 4 +- Marlin/src/HAL/LPC1768/HAL.cpp | 42 +++-- Marlin/src/HAL/LPC1768/HAL.h | 160 ++++++++++++------- Marlin/src/HAL/LPC1768/Servo.h | 3 +- Marlin/src/HAL/LPC1768/fast_pwm.cpp | 14 +- Marlin/src/HAL/LPC1768/main.cpp | 6 +- Marlin/src/HAL/LPC1768/timers.h | 2 +- Marlin/src/HAL/NATIVE_SIM/HAL.h | 173 +++++++++++++-------- Marlin/src/HAL/NATIVE_SIM/timers.h | 4 +- Marlin/src/HAL/SAMD51/HAL.cpp | 26 ++-- Marlin/src/HAL/SAMD51/HAL.h | 125 +++++++++------ Marlin/src/HAL/STM32/HAL.cpp | 28 ++-- Marlin/src/HAL/STM32/HAL.h | 179 ++++++++++++---------- Marlin/src/HAL/STM32/HAL_SPI.cpp | 8 +- Marlin/src/HAL/STM32/eeprom_flash.cpp | 8 +- Marlin/src/HAL/STM32/fast_pwm.cpp | 4 +- Marlin/src/HAL/STM32/pinsDebug.h | 6 +- Marlin/src/HAL/STM32/timers.h | 4 +- Marlin/src/HAL/STM32F1/HAL.cpp | 190 +++++++++++------------ Marlin/src/HAL/STM32F1/HAL.h | 184 ++++++++++++---------- Marlin/src/HAL/STM32F1/Servo.h | 3 +- Marlin/src/HAL/STM32F1/fast_pwm.cpp | 8 +- Marlin/src/HAL/STM32F1/timers.h | 2 +- Marlin/src/HAL/TEENSY31_32/HAL.cpp | 79 +++++----- Marlin/src/HAL/TEENSY31_32/HAL.h | 131 +++++++++++----- Marlin/src/HAL/TEENSY31_32/timers.h | 2 +- Marlin/src/HAL/TEENSY35_36/HAL.cpp | 110 +++++++------- Marlin/src/HAL/TEENSY35_36/HAL.h | 133 +++++++++++----- Marlin/src/HAL/TEENSY35_36/timers.h | 2 +- Marlin/src/HAL/TEENSY40_41/HAL.cpp | 194 ++++++++++++------------ Marlin/src/HAL/TEENSY40_41/HAL.h | 148 ++++++++++++------ Marlin/src/HAL/TEENSY40_41/timers.h | 2 +- Marlin/src/HAL/shared/HAL.cpp | 36 +++++ Marlin/src/HAL/shared/HAL_spi_L6470.cpp | 8 +- Marlin/src/MarlinCore.cpp | 48 +++--- Marlin/src/feature/caselight.cpp | 2 +- Marlin/src/feature/controllerfan.cpp | 2 +- Marlin/src/feature/e_parser.h | 4 +- Marlin/src/feature/leds/leds.cpp | 2 +- Marlin/src/feature/spindle_laser.cpp | 10 +- Marlin/src/feature/spindle_laser.h | 2 +- Marlin/src/gcode/control/M42.cpp | 4 +- Marlin/src/gcode/gcode_d.cpp | 10 +- Marlin/src/inc/SanityCheck.h | 7 + Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 4 +- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 2 +- Marlin/src/module/endstops.cpp | 2 +- Marlin/src/module/planner.cpp | 6 +- Marlin/src/module/servo.cpp | 2 +- Marlin/src/module/servo.h | 2 +- Marlin/src/module/stepper.cpp | 10 +- Marlin/src/module/temperature.cpp | 112 +++++++------- ini/native.ini | 4 +- 69 files changed, 1756 insertions(+), 1267 deletions(-) create mode 100644 Marlin/src/HAL/shared/HAL.cpp diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index d7bf2a6f6fbb8..2b6d2bdbcf074 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -36,7 +36,7 @@ // ------------------------ // Don't initialize/override variable (which would happen in .init4) -uint8_t reset_reason __attribute__((section(".noinit"))); +uint8_t MarlinHAL::reset_reason __attribute__((section(".noinit"))); // ------------------------ // Public functions @@ -45,22 +45,22 @@ uint8_t reset_reason __attribute__((section(".noinit"))); __attribute__((naked)) // Don't output function pro- and epilogue __attribute__((used)) // Output the function, even if "not used" __attribute__((section(".init3"))) // Put in an early user definable section -void HAL_save_reset_reason() { +void save_reset_reason() { #if ENABLED(OPTIBOOT_RESET_REASON) __asm__ __volatile__( A("STS %0, r2") - : "=m"(reset_reason) + : "=m"(hal.reset_reason) ); #else - reset_reason = MCUSR; + hal.reset_reason = MCUSR; #endif // Clear within 16ms since WDRF bit enables a 16ms watchdog timer -> Boot loop - MCUSR = 0; + hal.clear_reset_source(); wdt_disable(); } -void HAL_init() { +void MarlinHAL::init() { // Init Servo Pins #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) #if HAS_SERVO_0 @@ -77,7 +77,7 @@ void HAL_init() { #endif } -void HAL_reboot() { +void MarlinHAL::reboot() { #if ENABLED(USE_WATCHDOG) while (1) { /* run out the watchdog */ } #else diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 2217f239d64ea..9babe2d60352b 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -74,9 +74,8 @@ #define CRITICAL_SECTION_START() unsigned char _sreg = SREG; cli() #define CRITICAL_SECTION_END() SREG = _sreg #endif -#define ISRS_ENABLED() TEST(SREG, SREG_I) -#define ENABLE_ISRS() sei() -#define DISABLE_ISRS() cli() + +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment // ------------------------ // Types @@ -84,16 +83,16 @@ typedef int8_t pin_t; +// Use shared/servos.cpp #define SHARED_SERVOS HAS_SERVOS -#define HAL_SERVO_LIB Servo + +class Servo; +typedef Servo hal_servo_t; // ------------------------ -// Public Variables +// Serial ports // ------------------------ -extern uint8_t reset_reason; - -// Serial ports #ifdef USBCON #include "../../core/serial_hook.h" typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; @@ -142,20 +141,31 @@ extern uint8_t reset_reason; #endif #endif -// ------------------------ -// Public functions -// ------------------------ +// +// ADC +// +#define HAL_ADC_VREF 5.0 +#define HAL_ADC_RESOLUTION 10 -void HAL_init(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -//void cli(); +#define HAL_SENSITIVE_PINS 0, 1, -//void _delay_ms(const int delay); +#ifdef __AVR_AT90USB1286__ + #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) +#endif -inline void HAL_clear_reset_source() { } -inline uint8_t HAL_get_reset_source() { return reset_reason; } +// AVR compatibility +#define strtof strtod -void HAL_reboot(); +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -166,63 +176,89 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ADC -#ifdef DIDR2 - #define HAL_ANALOG_SELECT(ind) do{ if (ind < 8) SBI(DIDR0, ind); else SBI(DIDR2, ind & 0x07); }while(0) -#else - #define HAL_ANALOG_SELECT(ind) SBI(DIDR0, ind); -#endif +// ------------------------ +// MarlinHAL Class +// ------------------------ -inline void HAL_adc_init() { - ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07; - DIDR0 = 0; - #ifdef DIDR2 - DIDR2 = 0; - #endif -} +class MarlinHAL { +public: -#define SET_ADMUX_ADCSRA(ch) ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC) -#ifdef MUX5 - #define HAL_START_ADC(ch) if (ch > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(ch) -#else - #define HAL_START_ADC(ch) ADCSRB = 0; SET_ADMUX_ADCSRA(ch) -#endif + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 -#define HAL_READ_ADC() ADC -#define HAL_ADC_READY() !TEST(ADCSRA, ADSC) + static void init(); // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + static inline bool isr_state() { return TEST(SREG, SREG_I); } + static inline void isr_on() { sei(); } + static inline void isr_off() { cli(); } -#define HAL_SENSITIVE_PINS 0, 1, + static inline void delay_ms(const int ms) { _delay_ms(ms); } -#ifdef __AVR_AT90USB1286__ - #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) -#endif + // Tasks, called from idle() + static inline void idletask() {} -// AVR compatibility -#define strtof strtod + // Reset + static uint8_t reset_reason; + static inline uint8_t get_reset_source() { return reset_reason; } + static inline void clear_reset_source() { MCUSR = 0; } -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment + // Free SRAM + static inline int freeMemory() { return freeMemory(); } -/** - * set_pwm_frequency - * Sets the frequency of the timer corresponding to the provided pin - * as close as possible to the provided desired frequency. Internally - * calculates the required waveform generation mode, prescaler and - * resolution values required and sets the timer registers accordingly. - * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B) - * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings) - */ -void set_pwm_frequency(const pin_t pin, int f_desired); + // + // ADC Methods + // -/** - * set_pwm_duty - * Set the PWM duty cycle of the provided pin to the provided value - * Optionally allows inverting the duty cycle [default = false] - * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - */ -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + // Called by Temperature::init once at startup + static inline void adc_init() { + ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07; + DIDR0 = 0; + #ifdef DIDR2 + DIDR2 = 0; + #endif + } + + // Called by Temperature::init for each sensor at startup + static inline void adc_enable(const uint8_t ch) { + #ifdef DIDR2 + if (ch > 7) { SBI(DIDR2, ch & 0x07); return; } + #endif + SBI(DIDR0, ch); + } + + // Begin ADC sampling on the given channel + static inline void adc_start(const pin_t ch) { + #ifdef MUX5 + if (ch > 7) { ADCSRB = _BV(MUX5); return; } + #endif + ADCSRB = 0; + ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC); + } + + // Is the ADC ready for reading? + static inline bool adc_ready() { return !TEST(ADCSRA, ADSC); } + + // The current value of the ADC register + static inline __typeof__(ADC) adc_value() { return ADC; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + + /** + * Set the frequency of the timer for the given pin as close as + * possible to the provided desired frequency. Internally calculate + * the required waveform generation mode, prescaler, and resolution + * values and set timer registers accordingly. + * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B) + * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings) + */ + static void set_pwm_frequency(const pin_t pin, int f_desired); +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index cd8bf5e6903b8..986462437c8f5 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -486,7 +486,7 @@ void MarlinSerial::write(const uint8_t c) { const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); // If global interrupts are disabled (as the result of being called from an ISR)... - if (!ISRS_ENABLED()) { + if (!hal.isr_state()) { // Make room by polling if it is possible to transmit, and do so! while (i == tx_buffer.tail) { @@ -534,7 +534,7 @@ void MarlinSerial::flushTX() { if (!_written) return; // If global interrupts are disabled (as the result of being called from an ISR)... - if (!ISRS_ENABLED()) { + if (!hal.isr_state()) { // Wait until everything was transmitted - We must do polling, as interrupts are disabled while (tx_buffer.head != tx_buffer.tail || !B_TXC) { diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index 804e5fad30709..0053b44c3c7b4 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -35,10 +35,9 @@ struct Timer { }; /** - * get_pwm_timer - * Get the timer information and register of the provided pin. - * Return a Timer struct containing this information. - * Used by set_pwm_frequency, set_pwm_duty + * Get the timer information and register for a pin. + * Return a Timer struct containing this information. + * Used by set_pwm_frequency, set_pwm_duty */ Timer get_pwm_timer(const pin_t pin) { uint8_t q = 0; @@ -150,7 +149,7 @@ Timer get_pwm_timer(const pin_t pin) { return timer; } -void set_pwm_frequency(const pin_t pin, int f_desired) { +void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { Timer timer = get_pwm_timer(pin); if (timer.n == 0) return; // Don't proceed if protected timer or not recognized uint16_t size; @@ -230,7 +229,7 @@ void set_pwm_frequency(const pin_t pin, int f_desired) { #endif // NEEDS_HARDWARE_PWM -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { #if NEEDS_HARDWARE_PWM // If v is 0 or v_size (max), digitalWrite to LOW or HIGH. diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index 36b04eae0d1ff..e1fcbf52d6d8e 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -109,8 +109,8 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) { * (otherwise, characters will be lost due to UART overflow). * Then: Stepper, Endstops, Temperature, and -finally- all others. */ -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP /* 18 cycles maximum latency */ #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp index a3985652e71dd..20b711b1b05eb 100644 --- a/Marlin/src/HAL/DUE/HAL.cpp +++ b/Marlin/src/HAL/DUE/HAL.cpp @@ -34,7 +34,7 @@ // Public Variables // ------------------------ -uint16_t HAL_adc_result; +uint16_t MarlinHAL::adc_result; // ------------------------ // Public functions @@ -42,8 +42,7 @@ uint16_t HAL_adc_result; TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -// HAL initialization task -void HAL_init() { +void MarlinHAL::init() { // Initialize the USB stack #if ENABLED(SDSUPPORT) OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up @@ -52,21 +51,17 @@ void HAL_init() { TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler } -// HAL idle task -void HAL_idletask() { - // Perform USB stack housekeeping - usb_task_idle(); +void MarlinHAL::init_board() { + #ifdef BOARD_INIT + BOARD_INIT(); + #endif } -// Disable interrupts -void cli() { noInterrupts(); } - -// Enable interrupts -void sei() { interrupts(); } - -void HAL_clear_reset_source() { } +void MarlinHAL::idletask() { + usb_task_idle(); // Perform USB stack housekeeping +} -uint8_t HAL_get_reset_source() { +uint8_t MarlinHAL::get_reset_source() { switch ((RSTC->RSTC_SR >> 8) & 0x07) { case 0: return RST_POWER_ON; case 1: return RST_BACKUP; @@ -77,12 +72,7 @@ uint8_t HAL_get_reset_source() { } } -void HAL_reboot() { rstc_start_software_reset(RSTC); } - -void _delay_ms(const int delay_ms) { - // Todo: port for Due? - delay(delay_ms); -} +void MarlinHAL::reboot() { rstc_start_software_reset(RSTC); } extern "C" { extern unsigned int _ebss; // end of bss section @@ -94,19 +84,6 @@ int freeMemory() { return (int)&free_memory - (heap_end ?: (int)&_ebss); } -// ------------------------ -// ADC -// ------------------------ - -void HAL_adc_start_conversion(const uint8_t ch) { - HAL_adc_result = analogRead(ch); -} - -uint16_t HAL_adc_get_result() { - // nop - return HAL_adc_result; -} - // Forward the default serial ports #if USING_HW_SERIAL0 DefaultSerial1 MSerial0(false, Serial); diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 96ab5d9808ac1..0dd123acdd511 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -38,6 +38,10 @@ #include "../../core/serial_hook.h" +// ------------------------ +// Serial ports +// ------------------------ + typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; @@ -97,35 +101,31 @@ extern DefaultSerial4 MSerial3; #include "MarlinSerial.h" #include "MarlinSerialUSB.h" -// On AVR this is in math.h? -#define square(x) ((x)*(x)) +// ------------------------ +// Types +// ------------------------ typedef int8_t pin_t; +// Use shared/servos.cpp #define SHARED_SERVOS HAS_SERVOS -#define HAL_SERVO_LIB Servo +class Servo; +typedef Servo hal_servo_t; // // Interrupts // -#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_PRIMASK()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() - -void cli(); // Disable interrupts -void sei(); // Enable interrupts - -void HAL_clear_reset_source(); // clear reset reason -uint8_t HAL_get_reset_source(); // get reset reason +#define sei() noInterrupts() +#define cli() interrupts() -void HAL_reboot(); +#define CRITICAL_SECTION_START() const bool _irqon = hal.isr_state(); hal.isr_off() +#define CRITICAL_SECTION_END() if (_irqon) hal.isr_on() // // ADC // -extern uint16_t HAL_adc_result; // result of last ADC conversion +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) @@ -133,24 +133,8 @@ extern uint16_t HAL_adc_result; // result of last ADC conversion #define HAL_ANALOG_SELECT(ch) -inline void HAL_adc_init() {}//todo - -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -void HAL_adc_start_conversion(const uint8_t ch); -uint16_t HAL_adc_get_result(); - // -// PWM -// -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - -// -// Pin Map +// Pin Mapping for M42, M43, M226 // #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin @@ -159,27 +143,18 @@ inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, // // Tone // -void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// Enable hooks into idle and setup for HAL -#define HAL_IDLETASK 1 -void HAL_idletask(); -void HAL_init(); - -// -// Utility functions -// -void _delay_ms(const int delay); +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" #endif -int freeMemory(); - #pragma GCC diagnostic pop #ifdef __cplusplus @@ -189,3 +164,70 @@ char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s #ifdef __cplusplus } #endif + +// Return free RAM between end of heap (or end bss) and whatever is current +int freeMemory(); + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static void init_board(); // Called less early in setup() + static void reboot(); // Software reset + + static inline bool isr_state() { return !__get_PRIMASK(); } + static inline void isr_on() { __enable_irq(); } + static inline void isr_off() { __disable_irq(); } + + static inline void delay_ms(const int ms) { delay(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static inline void clear_reset_source() {} + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static inline void adc_init() {} + + // Called by Temperature::init for each sensor at startup + static inline void adc_enable(const int ch) {} + + // Begin ADC sampling on the given channel + static inline void adc_start(const uint8_t ch) { adc_result = analogRead(ch); } + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static inline uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * No inverting the duty cycle in this HAL. + * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL. + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index fe62ff5607d51..638f7a100722d 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -406,7 +406,7 @@ size_t MarlinSerial::write(const uint8_t c) { const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); // If global interrupts are disabled (as the result of being called from an ISR)... - if (!ISRS_ENABLED()) { + if (!hal.isr_state()) { // Make room by polling if it is possible to transmit, and do so! while (i == tx_buffer.tail) { @@ -454,7 +454,7 @@ void MarlinSerial::flushTX() { if (!_written) return; // If global interrupts are disabled (as the result of being called from an ISR)... - if (!ISRS_ENABLED()) { + if (!hal.isr_state()) { // Wait until everything was transmitted - We must do polling, as interrupts are disabled while (tx_buffer.head != tx_buffer.tail || !(HWUART->UART_SR & UART_SR_TXEMPTY)) { diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index e2932ff36f91b..bcfd07e268c57 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -125,4 +125,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR; } -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 810e386894ec4..604acae8dd5b9 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -52,7 +52,7 @@ // Externs // ------------------------ -portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED; +portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED; // ------------------------ // Local defines @@ -64,7 +64,7 @@ portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED; // Public Variables // ------------------------ -uint16_t HAL_adc_result; +uint16_t MarlinHAL::adc_result; // ------------------------ // Private Variables @@ -95,20 +95,22 @@ volatile int numPWMUsed = 0, #endif #if ENABLED(USE_ESP32_EXIO) + HardwareSerial YSerial2(2); void Write_EXIO(uint8_t IO, uint8_t v) { - if (ISRS_ENABLED()) { - DISABLE_ISRS(); + if (hal.isr_state()) { + hal.isr_off(); YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); - ENABLE_ISRS(); + hal.isr_on(); } else YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); } + #endif -void HAL_init_board() { +void MarlinHAL::init_board() { #if ENABLED(USE_ESP32_TASK_WDT) esp_task_wdt_init(10, true); #endif @@ -154,27 +156,24 @@ void HAL_init_board() { #endif } -void HAL_idletask() { +void MarlinHAL::idletask() { #if BOTH(WIFISUPPORT, OTASUPPORT) OTA_handle(); #endif TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask()); } -void HAL_clear_reset_source() { } - -uint8_t HAL_get_reset_source() { return rtc_get_reset_reason(1); } +uint8_t MarlinHAL::get_reset_source() { return rtc_get_reset_reason(1); } -void HAL_reboot() { ESP.restart(); } - -void _delay_ms(int delay_ms) { delay(delay_ms); } +void MarlinHAL::reboot() { ESP.restart(); } // return free memory between end of heap (or end bss) and whatever is current -int freeMemory() { return ESP.getFreeHeap(); } +int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); } // ------------------------ // ADC // ------------------------ + #define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL adc1_channel_t get_channel(int pin) { @@ -196,7 +195,7 @@ void adc1_set_attenuation(adc1_channel_t chan, adc_atten_t atten) { } } -void HAL_adc_init() { +void MarlinHAL::adc_init() { // Configure ADC adc1_config_width(ADC_WIDTH_12Bit); @@ -226,11 +225,11 @@ void HAL_adc_init() { } } -void HAL_adc_start_conversion(const uint8_t adc_pin) { - const adc1_channel_t chan = get_channel(adc_pin); +void MarlinHAL::adc_start(const pin_t pin) { + const adc1_channel_t chan = get_channel(pin); uint32_t mv; esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv); - HAL_adc_result = mv * 1023.0 / 3300.0; + adc_result = mv * 1023.0 / 3300.0; // Change the attenuation level based on the new reading adc_atten_t atten; diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 8473e3c4e4693..361c9032317df 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -49,8 +49,6 @@ // Defines // ------------------------ -extern portMUX_TYPE spinlock; - #define MYSERIAL1 flushableSerial #if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) @@ -65,9 +63,6 @@ extern portMUX_TYPE spinlock; #define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock) #define CRITICAL_SECTION_END() portEXIT_CRITICAL(&spinlock) -#define ISRS_ENABLED() (spinlock.owner == portMUX_FREE_VAL) -#define ENABLE_ISRS() if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock) -#define DISABLE_ISRS() portENTER_CRITICAL(&spinlock) // ------------------------ // Types @@ -75,14 +70,8 @@ extern portMUX_TYPE spinlock; typedef int16_t pin_t; -#define HAL_SERVO_LIB Servo - -// ------------------------ -// Public Variables -// ------------------------ - -/** result of last ADC conversion */ -extern uint16_t HAL_adc_result; +class Servo; +typedef Servo hal_servo_t; // ------------------------ // Public functions @@ -91,59 +80,21 @@ extern uint16_t HAL_adc_result; // // Tone // -void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// clear reset reason -void HAL_clear_reset_source(); - -// reset reason -uint8_t HAL_get_reset_source(); - -void HAL_reboot(); - -void _delay_ms(int delay); - -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif - -int freeMemory(); - -#pragma GCC diagnostic pop - void analogWrite(pin_t pin, int value); // ADC #define HAL_ANALOG_SELECT(pin) -void HAL_adc_init(); - -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -void HAL_adc_start_conversion(const uint8_t adc_pin); - -// PWM -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - -// Pin Map +// +// Pin Mapping for M42, M43, M226 +// #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -// Enable hooks into idle and setup for HAL -#define HAL_IDLETASK 1 -#define BOARD_INIT() HAL_init_board(); -void HAL_idletask(); -inline void HAL_init() {} -void HAL_init_board(); - #if ENABLED(USE_ESP32_EXIO) void Write_EXIO(uint8_t IO, uint8_t v); #endif @@ -188,3 +139,86 @@ FORCE_INLINE static void DELAY_CYCLES(uint32_t x) { } } + +// ------------------------ +// Class Utilities +// ------------------------ + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +int freeMemory(); + +#pragma GCC diagnostic pop + +void _delay_ms(const int ms); + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static inline void init() {} // Called early in setup() + static void init_board(); // Called less early in setup() + static void reboot(); // Restart the firmware + + static portMUX_TYPE spinlock; + static inline bool isr_state() { return spinlock.owner == portMUX_FREE_VAL; } + static inline void isr_on() { if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock); } + static inline void isr_off() { portENTER_CRITICAL(&spinlock); } + + static inline void delay_ms(const int ms) { _delay_ms(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static inline void clear_reset_source() {} + + // Free SRAM + static int freeMemory(); + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static inline void adc_enable(const pin_t pin) {} + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static inline uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * No inverting the duty cycle in this HAL. + * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL. + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index 266169848daf7..efae594f6cd85 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -136,5 +136,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp index 0b679170ef171..91739aaa7b06d 100644 --- a/Marlin/src/HAL/LINUX/HAL.cpp +++ b/Marlin/src/HAL/LINUX/HAL.cpp @@ -24,6 +24,12 @@ #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" +extern MarlinHAL hal; + +// ------------------------ +// Serial ports +// ------------------------ + MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true)); // U8glib required functions @@ -37,42 +43,21 @@ extern "C" { //************************// // return free heap space -int freeMemory() { - return 0; -} +int freeMemory() { return 0; } // ------------------------ // ADC // ------------------------ -void HAL_adc_init() { +uint8_t MarlinHAL::active_ch = 0; -} - -void HAL_adc_enable_channel(const uint8_t ch) { - -} - -uint8_t active_ch = 0; -void HAL_adc_start_conversion(const uint8_t ch) { - active_ch = ch; -} - -bool HAL_adc_finished() { - return true; -} - -uint16_t HAL_adc_get_result() { - pin_t pin = analogInputToDigitalPin(active_ch); +uint16_t MarlinHAL::adc_value() { + const pin_t pin = analogInputToDigitalPin(active_ch); if (!VALID_PIN(pin)) return 0; - uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); + const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); return data; // return 10bit value as Marlin expects } -void HAL_pwm_init() { - -} - -void HAL_reboot() { /* Reset the application state and GPIO */ } +void MarlinHAL::reboot() { /* Reset the application state and GPIO */ } #endif // __PLAT_LINUX__ diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index d7d3a92b73b95..0bd8635c90454 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -21,25 +21,42 @@ */ #pragma once -#define CPU_32_BIT - -#define F_CPU 100000000UL -#define SystemCoreClock F_CPU #include #include #include - #undef min #undef max - #include -void _printf (const char *format, ...); +#include "hardware/Clock.h" + +#include "../shared/Marduino.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" +#include "fastio.h" +#include "watchdog.h" +#include "serial.h" + +// ------------------------ +// Defines +// ------------------------ + +#define CPU_32_BIT +#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp + +#define F_CPU 100000000UL +#define SystemCoreClock F_CPU + +#define DELAY_CYCLES(x) Clock::delayCycles(x) + +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +void _printf(const char *format, ...); void _putc(uint8_t c); uint8_t _getc(); -//extern "C" volatile uint32_t _millis; - //arduino: Print.h #define DEC 10 #define HEX 16 @@ -49,36 +66,28 @@ uint8_t _getc(); #define B01 1 #define B10 2 -#include "hardware/Clock.h" - -#include "../shared/Marduino.h" -#include "../shared/math_32bit.h" -#include "../shared/HAL_SPI.h" -#include "fastio.h" -#include "watchdog.h" -#include "serial.h" - -#define SHARED_SERVOS HAS_SERVOS +// ------------------------ +// Serial ports +// ------------------------ extern MSerialT usb_serial; #define MYSERIAL1 usb_serial -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - // // Interrupts // #define CRITICAL_SECTION_START() #define CRITICAL_SECTION_END() -#define ISRS_ENABLED() -#define ENABLE_ISRS() -#define DISABLE_ISRS() -inline void HAL_init() {} +// ADC +#define HAL_ADC_VREF 5.0 +#define HAL_ADC_RESOLUTION 10 +#define HAL_ANALOG_SELECT(ch) hal.adc_enable(ch) + +// ------------------------ +// Class Utilities +// ------------------------ -// Utility functions #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" @@ -88,29 +97,67 @@ int freeMemory(); #pragma GCC diagnostic pop -// ADC -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) -#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static inline void init() {} // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Reset the application state and GPIO + + static inline bool isr_state() { return true; } + static inline void isr_on() {} + static inline void isr_off() {} + + static inline void delay_ms(const int ms) { _delay_ms(ms); } + + // Tasks, called from idle() + static inline void idletask() {} + + // Reset + static constexpr uint8_t reset_reason = RST_POWER_ON; + static inline uint8_t get_reset_source() { return reset_reason; } + static inline void clear_reset_source() {} + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static uint8_t active_ch; + + // Called by Temperature::init once at startup + static inline void adc_init() {} + + // Called by Temperature::init for each sensor at startup + static inline void adc_enable(const uint8_t) {} + + // Begin ADC sampling on the given channel + static inline void adc_start(const pin_t ch) { active_ch = ch; } -void HAL_adc_init(); -void HAL_adc_enable_channel(const uint8_t ch); -void HAL_adc_start_conversion(const uint8_t ch); -uint16_t HAL_adc_get_result(); + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } -// PWM -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // The current value of the ADC register + static uint16_t adc_value(); -// Reset source -inline void HAL_clear_reset_source(void) {} -inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to change the resolution or invert the duty cycle. + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } -void HAL_reboot(); // Reset the application state and GPIO + static inline void set_pwm_frequency(const pin_t, int) {} +}; -/* ---------------- Delay in cycles */ -FORCE_INLINE static void DELAY_CYCLES(uint64_t x) { - Clock::delayCycles(x); -} +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/LINUX/arduino.cpp b/Marlin/src/HAL/LINUX/arduino.cpp index 4b56d02a389c2..075b4ccde2f4d 100644 --- a/Marlin/src/HAL/LINUX/arduino.cpp +++ b/Marlin/src/HAL/LINUX/arduino.cpp @@ -31,9 +31,7 @@ void cli() { } // Disable void sei() { } // Enable // Time functions -void _delay_ms(const int delay_ms) { - delay(delay_ms); -} +void _delay_ms(const int ms) { delay(ms); } uint32_t millis() { return (uint32_t)Clock::millis(); diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h index d4086e259a2f1..49e04d0cb7d37 100644 --- a/Marlin/src/HAL/LINUX/include/Arduino.h +++ b/Marlin/src/HAL/LINUX/include/Arduino.h @@ -59,7 +59,6 @@ typedef uint8_t byte; #endif #define sq(v) ((v) * (v)) -#define square(v) sq(v) #define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value))) //Interrupts @@ -74,8 +73,8 @@ extern "C" { } // Time functions -extern "C" void delay(const int milis); -void _delay_ms(const int delay); +extern "C" void delay(const int ms); +void _delay_ms(const int ms); void delayMicroseconds(unsigned long); uint32_t millis(); diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index a98ceb6f391d9..2d2a95774c1b0 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -92,5 +92,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index cee9cfc5f744c..541848b08acc3 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -31,7 +31,7 @@ DefaultSerial1 USBSerial(false, UsbSerial); -uint32_t HAL_adc_reading = 0; +uint32_t MarlinHAL::adc_result = 0; // U8glib required functions extern "C" { @@ -41,8 +41,6 @@ extern "C" { void u8g_Delay(uint16_t val) { delay(val); } } -//************************// - // return free heap space int freeMemory() { char stack_end; @@ -54,33 +52,33 @@ int freeMemory() { return result; } -// scan command line for code -// return index into pin map array if found and the pin is valid. -// return dval if not found or not a valid pin. -int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { - const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100; - const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2; - return ind > -1 ? ind : dval; +void MarlinHAL::reboot() { NVIC_SystemReset(); } + +uint8_t MarlinHAL::get_reset_source() { + #if ENABLED(USE_WATCHDOG) + if (watchdog_timed_out()) return RST_WATCHDOG; + #endif + return RST_POWER_ON; +} + +void MarlinHAL::clear_reset_source() { + TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); } void flashFirmware(const int16_t) { delay(500); // Give OS time to disconnect USB_Connect(false); // USB clear connection delay(1000); // Give OS time to notice - HAL_reboot(); + hal.reboot(); } -void HAL_clear_reset_source(void) { - TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); -} - -uint8_t HAL_get_reset_source(void) { - #if ENABLED(USE_WATCHDOG) - if (watchdog_timed_out()) return RST_WATCHDOG; - #endif - return RST_POWER_ON; +// For M42/M43, scan command line for pin code +// return index into pin map array if found and the pin is valid. +// return dval if not found or not a valid pin. +int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { + const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100; + const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2; + return ind > -1 ? ind : dval; } -void HAL_reboot() { NVIC_SystemReset(); } - #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 348ea6b21a040..ba0729590f5b9 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -28,8 +28,6 @@ #define CPU_32_BIT -void HAL_init(); - #include #include #include @@ -47,12 +45,9 @@ extern "C" volatile uint32_t _millis; #include #include -// -// Default graphical display delays -// -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 +// ------------------------ +// Serial ports +// ------------------------ typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1; extern DefaultSerial1 USBSerial; @@ -114,26 +109,12 @@ extern DefaultSerial1 USBSerial; // // Interrupts // -#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_PRIMASK()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() - -// -// Utility functions -// -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif -int freeMemory(); - -#pragma GCC diagnostic pop +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() // -// ADC API +// ADC // #define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift), @@ -152,20 +133,11 @@ int freeMemory(); #define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t #define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL -using FilteredADC = LPC176x::ADC; -extern uint32_t HAL_adc_reading; -[[gnu::always_inline]] inline void HAL_adc_start_conversion(const pin_t pin) { - HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits -} -[[gnu::always_inline]] inline uint16_t HAL_adc_get_result() { - return HAL_adc_reading; -} +#define HAL_ANALOG_SELECT(pin) hal.adc_enable(pin) -#define HAL_adc_init() -#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin) -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() (true) +// +// Pin Mapping for M42, M43, M226 +// // Test whether the pin is valid constexpr bool VALID_PIN(const pin_t pin) { @@ -192,32 +164,104 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); // P0.6 thru P0.9 are for the onboard SD card #define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09, -#define HAL_IDLETASK 1 -void HAL_idletask(); +// ------------------------ +// Defines +// ------------------------ #define PLATFORM_M997_SUPPORT void flashFirmware(const int16_t); #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment -/** - * set_pwm_frequency - * Set the frequency of the timer corresponding to the provided pin - * All Hardware PWM pins run at the same frequency and all - * Software PWM pins run at the same frequency - */ -void set_pwm_frequency(const pin_t pin, int f_desired); +// Default graphical display delays +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 -/** - * set_pwm_duty - * Set the PWM duty cycle of the provided pin to the provided value - * Optionally allows inverting the duty cycle [default = false] - * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - */ -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); +// ------------------------ +// Class Utilities +// ------------------------ + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +int freeMemory(); + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + static inline bool isr_state() { return !__get_PRIMASK(); } + static inline void isr_on() { __enable_irq(); } + static inline void isr_off() { __disable_irq(); } + + static inline void delay_ms(const int ms) { _delay_ms(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source(); + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + using FilteredADC = LPC176x::ADC; + + // Called by Temperature::init once at startup + static inline void adc_init() {} + + // Called by Temperature::init for each sensor at startup + static inline void adc_enable(const pin_t pin) { + FilteredADC::enable_channel(pin); + } + + // Begin ADC sampling on the given pin + static uint32_t adc_result; + FORCE_INLINE static void adc_start(const pin_t pin) { + adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits + } + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + FORCE_INLINE static uint16_t adc_value() { + return (uint16_t)adc_result; + } + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); -// Reset source -void HAL_clear_reset_source(void); -uint8_t HAL_get_reset_source(void); + /** + * Set the frequency of the timer corresponding to the provided pin + * All Hardware PWM pins will run at the same frequency and + * All Software PWM pins will run at the same frequency + */ + static void set_pwm_frequency(const pin_t pin, int f_desired); +}; -void HAL_reboot(); +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h index eb12fd20f4d87..f02f503a67daa 100644 --- a/Marlin/src/HAL/LPC1768/Servo.h +++ b/Marlin/src/HAL/LPC1768/Servo.h @@ -65,4 +65,5 @@ class libServo: public Servo { } }; -#define HAL_SERVO_LIB libServo +class libServo; +typedef libServo hal_servo_t; diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp index eae0e36b0b0e3..91e92a1575015 100644 --- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp +++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp @@ -21,21 +21,17 @@ */ #ifdef TARGET_LPC1768 -#include "../../inc/MarlinConfigPre.h" +#include "../../inc/MarlinConfig.h" #include -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!LPC176x::pin_is_valid(pin)) return; if (LPC176x::pwm_attach_pin(pin)) LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size); // map 1-254 onto PWM range } -#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM - - void set_pwm_frequency(const pin_t pin, int f_desired) { - LPC176x::pwm_set_frequency(pin, f_desired); - } - -#endif +void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { + LPC176x::pwm_set_frequency(pin, f_desired); +} #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index ef0dc42c78cad..419c99793fb8a 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -48,7 +48,7 @@ void SysTick_Callback() { disk_timerproc(); } TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -void HAL_init() { +void MarlinHAL::init() { // Init LEDs #if PIN_EXISTS(LED) @@ -130,7 +130,7 @@ void HAL_init() { const millis_t usb_timeout = millis() + 2000; while (!USB_Configuration && PENDING(millis(), usb_timeout)) { delay(50); - HAL_idletask(); + idletask(); #if PIN_EXISTS(LED) TOGGLE(LED_PIN); // Flash quickly during USB initialization #endif @@ -142,7 +142,7 @@ void HAL_init() { } // HAL idle task -void HAL_idletask() { +void MarlinHAL::idletask() { #if HAS_SHARED_MEDIA // If Marlin is using the SD card we need to lock it to prevent access from // a PC via USB. diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index 78e856db28578..c6d7bc632e2ed 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -170,4 +170,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 436b4b4daa265..bfbdaf211ff30 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -21,18 +21,10 @@ */ #pragma once -#define CPU_32_BIT -#define HAL_IDLETASK -void HAL_idletask(); - -#define F_CPU 100000000 -#define SystemCoreClock F_CPU #include #include - #undef min #undef max - #include #include "pinmapping.h" @@ -40,8 +32,6 @@ void _printf (const char *format, ...); void _putc(uint8_t c); uint8_t _getc(); -//extern "C" volatile uint32_t _millis; - //arduino: Print.h #define DEC 10 #define HEX 16 @@ -58,7 +48,23 @@ uint8_t _getc(); #include "watchdog.h" #include "serial.h" -#define SHARED_SERVOS HAS_SERVOS +// ------------------------ +// Defines +// ------------------------ + +#define CPU_32_BIT +#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp + +#define F_CPU 100000000 +#define SystemCoreClock F_CPU + +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +// ------------------------ +// Serial ports +// ------------------------ extern MSerialT serial_stream_0; extern MSerialT serial_stream_1; @@ -98,49 +104,20 @@ extern MSerialT serial_stream_3; #endif #endif - -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -// +// ------------------------ // Interrupts -// +// ------------------------ + #define CRITICAL_SECTION_START() #define CRITICAL_SECTION_END() -#define ISRS_ENABLED() -#define ENABLE_ISRS() -#define DISABLE_ISRS() - -inline void HAL_init() {} - -// Utility functions -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" -int freeMemory(); -#pragma GCC diagnostic pop +// ------------------------ // ADC +// ------------------------ + #define HAL_ADC_VREF 5.0 #define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) -#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true - -void HAL_adc_init(); -void HAL_adc_enable_channel(const uint8_t ch); -void HAL_adc_start_conversion(const uint8_t ch); -uint16_t HAL_adc_get_result(); - -// PWM -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - -// Reset source -inline void HAL_clear_reset_source(void) {} -inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } - -void HAL_reboot(); +#define HAL_ANALOG_SELECT(ch) hal.adc_enable(ch) /* ---------------- Delay in cycles */ @@ -159,29 +136,22 @@ constexpr inline std::size_t strlen_constexpr(const char* str) { // https://github.com/gcc-mirror/gcc/blob/5c7634a0e5f202935aa6c11b6ea953b8bf80a00a/libstdc%2B%2B-v3/include/bits/char_traits.h#L329 if (str != nullptr) { std::size_t i = 0; - while (str[i] != '\0') { - ++i; - } - + while (str[i] != '\0') ++i; return i; } - return 0; } constexpr inline int strncmp_constexpr(const char* lhs, const char* rhs, std::size_t count) { // https://github.com/gcc-mirror/gcc/blob/13b9cbfc32fe3ac4c81c4dd9c42d141c8fb95db4/libstdc%2B%2B-v3/include/bits/char_traits.h#L655 - if (lhs == nullptr || rhs == nullptr) { + if (lhs == nullptr || rhs == nullptr) return rhs != nullptr ? -1 : 1; - } - for (std::size_t i = 0; i < count; ++i) { + for (std::size_t i = 0; i < count; ++i) if (lhs[i] != rhs[i]) { return lhs[i] < rhs[i] ? -1 : 1; - } else if (lhs[i] == '\0') { + else if (lhs[i] == '\0') return 0; - } - } return 0; } @@ -193,14 +163,11 @@ constexpr inline const char* strstr_constexpr(const char* str, const char* targe do { char sc = {}; do { - if ((sc = *str++) == '\0') { - return nullptr; - } + if ((sc = *str++) == '\0') return nullptr; } while (sc != c); } while (strncmp_constexpr(str, target, len) != 0); --str; } - return str; } @@ -211,12 +178,88 @@ constexpr inline char* strstr_constexpr(char* str, const char* target) { do { char sc = {}; do { - if ((sc = *str++) == '\0') { - return nullptr; - } + if ((sc = *str++) == '\0') return nullptr; } while (sc != c); } while (strncmp_constexpr(str, target, len) != 0); --str; } return str; } + +// ------------------------ +// Class Utilities +// ------------------------ + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +int freeMemory(); + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static inline void init() {} // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + static inline bool isr_state() { return true; } + static inline void isr_on() {} + static inline void isr_off() {} + + static inline void delay_ms(const int ms) { _delay_ms(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static constexpr uint8_t reset_reason = RST_POWER_ON; + static inline uint8_t get_reset_source() { return reset_reason; } + static inline void clear_reset_source() {} + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static uint8_t active_ch; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const uint8_t ch); + + // Begin ADC sampling on the given channel + static void adc_start(const uint8_t ch); + + // Is the ADC ready for reading? + static bool adc_ready(); + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index cedfdb62d631f..be38d583b6861 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -87,5 +87,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index 8baad31bc7512..f0383251283d0 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -106,7 +106,7 @@ // Private Variables // ------------------------ -uint16_t HAL_adc_result; +uint16_t MarlinHAL::adc_result; #if ADC_IS_REQUIRED @@ -402,7 +402,7 @@ uint16_t HAL_adc_result; // ------------------------ // HAL initialization task -void HAL_init() { +void MarlinHAL::init() { TERN_(DMA_IS_REQUIRED, dma_init()); #if ENABLED(SDSUPPORT) #if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT) @@ -412,17 +412,9 @@ void HAL_init() { #endif } -// HAL idle task -/* -void HAL_idletask() { -} -*/ - -void HAL_clear_reset_source() { } - #pragma push_macro("WDT") #undef WDT // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define -uint8_t HAL_get_reset_source() { +uint8_t MarlinHAL::get_reset_source() { RSTC_RCAUSE_Type resetCause; resetCause.reg = REG_RSTC_RCAUSE; @@ -436,7 +428,7 @@ uint8_t HAL_get_reset_source() { } #pragma pop_macro("WDT") -void HAL_reboot() { NVIC_SystemReset(); } +void MarlinHAL::reboot() { NVIC_SystemReset(); } extern "C" { void * _sbrk(int incr); @@ -454,7 +446,7 @@ int freeMemory() { // ADC // ------------------------ -void HAL_adc_init() { +void MarlinHAL::adc_init() { #if ADC_IS_REQUIRED memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results)); // Fill result with invalid values @@ -491,17 +483,17 @@ void HAL_adc_init() { #endif // ADC_IS_REQUIRED } -void HAL_adc_start_conversion(const uint8_t adc_pin) { +void MarlinHAL::adc_start(const pin_t pin) { #if ADC_IS_REQUIRED LOOP_L_N(pi, COUNT(adc_pins)) { - if (adc_pin == adc_pins[pi]) { - HAL_adc_result = HAL_adc_results[pi]; + if (pin == adc_pins[pi]) { + adc_result = HAL_adc_results[pi]; return; } } #endif - HAL_adc_result = 0xFFFF; + adc_result = 0xFFFF; } #endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index c262752a8d66a..144bf9c08dfa1 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -89,51 +89,31 @@ typedef int8_t pin_t; -#define SHARED_SERVOS HAS_SERVOS -#define HAL_SERVO_LIB Servo +#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp +class Servo; +typedef Servo hal_servo_t; // // Interrupts // -#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_PRIMASK()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() -#define cli() __disable_irq() // Disable interrupts -#define sei() __enable_irq() // Enable interrupts - -void HAL_clear_reset_source(); // clear reset reason -uint8_t HAL_get_reset_source(); // get reset reason - -void HAL_reboot(); +#define cli() __disable_irq() // Disable interrupts +#define sei() __enable_irq() // Enable interrupts // // ADC // -extern uint16_t HAL_adc_result; // Most recent ADC conversion #define HAL_ANALOG_SELECT(pin) -void HAL_adc_init(); - //#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values. #define HAL_ADC_VREF 3.3 #define HAL_ADC_RESOLUTION 10 // ... 12 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -void HAL_adc_start_conversion(const uint8_t adc_pin); - -// -// PWM -// -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } // -// Pin Map +// Pin Mapping for M42, M43, M226 // #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin @@ -142,35 +122,92 @@ inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, // // Tone // -void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// Enable hooks into idle and setup for HAL -void HAL_init(); -/* -#define HAL_IDLETASK 1 -void HAL_idletask(); -*/ - -// -// Utility functions -// -FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" #endif -int freeMemory(); - -#pragma GCC diagnostic pop - #ifdef __cplusplus extern "C" { #endif + char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s); + +extern "C" int freeMemory(); + #ifdef __cplusplus } #endif + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + static inline bool isr_state() { return !__get_PRIMASK(); } + static inline void isr_on() { sei(); } + static inline void isr_off() { cli(); } + + static inline void delay_ms(const int ms) { delay(ms); } + + // Tasks, called from idle() + static inline void idletask() {} + + // Reset + static uint8_t get_reset_source(); + static inline void clear_reset_source() {} + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const uint8_t ch); + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index 0920a72ec1bcd..324a78316a2d7 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -53,16 +53,18 @@ // Public Variables // ------------------------ -uint16_t HAL_adc_result; +uint16_t MarlinHAL::adc_result; // ------------------------ // Public functions // ------------------------ -TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); +#if ENABLED(POSTMORTEM_DEBUGGING) + extern void install_min_serial(); +#endif // HAL initialization task -void HAL_init() { +void MarlinHAL::init() { // Ensure F_CPU is a constant expression. // If the compiler breaks here, it means that delay code that should compute at compile time will not work. // So better safe than sorry here. @@ -103,7 +105,7 @@ void HAL_init() { } // HAL idle task -void HAL_idletask() { +void MarlinHAL::idletask() { #if HAS_SHARED_MEDIA // Stm32duino currently doesn't have a "loop/idle" method CDC_resume_receive(); @@ -111,9 +113,9 @@ void HAL_idletask() { #endif } -void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } +void MarlinHAL::reboot() { NVIC_SystemReset(); } -uint8_t HAL_get_reset_source() { +uint8_t MarlinHAL::get_reset_source() { return #ifdef RCC_FLAG_IWDGRST // Some sources may not exist... RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) ? RST_WATCHDOG : @@ -137,24 +139,14 @@ uint8_t HAL_get_reset_source() { ; } -void HAL_reboot() { NVIC_SystemReset(); } - -void _delay_ms(const int delay_ms) { delay(delay_ms); } +void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } extern "C" { extern unsigned int _ebss; // end of bss section } -// ------------------------ -// ADC -// ------------------------ - -// TODO: Make sure this doesn't cause any delay -void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); } -uint16_t HAL_adc_get_result() { return HAL_adc_result; } - // Reset the system to initiate a firmware flash -WEAK void flashFirmware(const int16_t) { HAL_reboot(); } +WEAK void flashFirmware(const int16_t) { hal.reboot(); } // Maple Compatibility volatile uint32_t systick_uptime_millis = 0; diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index adaf14223f324..d71ccd796b2f2 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -44,9 +44,9 @@ #define CPU_ST7920_DELAY_2 40 #define CPU_ST7920_DELAY_3 340 -// -// Serial Ports -// +// ------------------------ +// Serial ports +// ------------------------ #ifdef USBCON #include #include "../../core/serial_hook.h" @@ -115,17 +115,14 @@ #define analogInputToDigitalPin(p) (p) #endif -#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_PRIMASK()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() +// +// Interrupts +// +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() #define cli() __disable_irq() #define sei() __enable_irq() -// On AVR this is in math.h? -#define square(x) ((x)*(x)) - // ------------------------ // Types // ------------------------ @@ -136,54 +133,14 @@ typedef int16_t pin_t; #endif -#define HAL_SERVO_LIB libServo +class libServo; +typedef libServo hal_servo_t; #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos() // ------------------------ -// Public Variables -// ------------------------ - -// result of last ADC conversion -extern uint16_t HAL_adc_result; - -// ------------------------ -// Public functions -// ------------------------ - -// Memory related -#define __bss_end __bss_end__ - -// Enable hooks into setup for HAL -void HAL_init(); -#define HAL_IDLETASK 1 -void HAL_idletask(); - -// Clear reset reason -void HAL_clear_reset_source(); - -// Reset reason -uint8_t HAL_get_reset_source(); - -void HAL_reboot(); - -void _delay_ms(const int delay); - -extern "C" char* _sbrk(int incr); - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" - -static inline int freeMemory() { - volatile char top; - return &top - reinterpret_cast(_sbrk(0)); -} - -#pragma GCC diagnostic pop - -// // ADC -// +// ------------------------ #define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) @@ -194,16 +151,10 @@ static inline int freeMemory() { #endif #define HAL_ADC_VREF 3.3 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -inline void HAL_adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); } - -void HAL_adc_start_conversion(const uint8_t adc_pin); - -uint16_t HAL_adc_get_result(); +// +// Pin Mapping for M42, M43, M226 +// #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) @@ -226,17 +177,93 @@ extern volatile uint32_t systick_uptime_millis; #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment -/** - * set_pwm_frequency - * Set the frequency of the timer corresponding to the provided pin - * All Timer PWM pins run at the same frequency - */ -void set_pwm_frequency(const pin_t pin, int f_desired); +// ------------------------ +// Class Utilities +// ------------------------ -/** - * set_pwm_duty - * Set the PWM duty cycle of the provided pin to the provided value - * Optionally allows inverting the duty cycle [default = false] - * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - */ -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); +// Memory related +#define __bss_end __bss_end__ + +extern "C" char* _sbrk(int incr); + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +static inline int freeMemory() { + volatile char top; + return &top - reinterpret_cast(_sbrk(0)); +} + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + static inline bool isr_state() { return !__get_PRIMASK(); } + static inline void isr_on() { sei(); } + static inline void isr_off() { cli(); } + + static inline void delay_ms(const int ms) { delay(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source(); + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static inline void adc_init() { + analogReadResolution(HAL_ADC_RESOLUTION); + } + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin); + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin) { adc_result = analogRead(pin); } + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + + /** + * Set the frequency of the timer for the given pin. + * All Timer PWM pins run at the same frequency. + */ + static void set_pwm_frequency(const pin_t pin, int f_desired); + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 8ee4761647856..7737245de85b1 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -102,9 +102,9 @@ static SPISettings spiConfig; // Soft SPI receive byte uint8_t spiRec() { - DISABLE_ISRS(); // No interrupts during byte receive + hal.isr_off(); // No interrupts during byte receive const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF); - ENABLE_ISRS(); // Enable interrupts + hal.isr_off(); // Enable interrupts return data; } @@ -116,9 +116,9 @@ static SPISettings spiConfig; // Soft SPI send byte void spiSend(uint8_t data) { - DISABLE_ISRS(); // No interrupts during byte send + hal.isr_off(); // No interrupts during byte send HAL_SPI_STM32_SpiTransfer_Mode_3(data); // Don't care what is received - ENABLE_ISRS(); // Enable interrupts + hal.isr_on(); // Enable interrupts } // Soft SPI send block diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 252b057362c99..7c8cc8dd21e18 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -174,9 +174,9 @@ bool PersistentStore::access_finish() { UNLOCK_FLASH(); TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); - DISABLE_ISRS(); + hal.isr_off(); status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError); - ENABLE_ISRS(); + hal.isr_on(); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); if (status != HAL_OK) { DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status); @@ -229,9 +229,9 @@ bool PersistentStore::access_finish() { // output. Servo output still glitches with interrupts disabled, but recovers after the // erase. TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); - DISABLE_ISRS(); + hal.isr_off(); eeprom_buffer_flush(); - ENABLE_ISRS(); + hal.isr_on(); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); eeprom_data_written = false; diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index b1bea5ce20eb8..f6d0481c05c1d 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -29,7 +29,7 @@ // Array to support sticky frequency sets per timer static uint16_t timer_freq[TIMER_NUM]; -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer const PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); @@ -56,7 +56,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume(); } -void set_pwm_frequency(const pin_t pin, int f_desired) { +void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer const PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index 73d850fc43132..a7f022a0b62dd 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -115,7 +115,6 @@ const XrefInfo pin_xref[] PROGMEM = { #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define PRINT_PORT(ANUM) port_print(ANUM) #define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine -#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num // x is a variable used to search pin_array #define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) @@ -123,6 +122,11 @@ const XrefInfo pin_xref[] PROGMEM = { #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin +// +// Pin Mapping for M43 +// +#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num + #ifndef M43_NEVER_TOUCH #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP) #ifdef KILL_PIN diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index aad543229e164..6828998198af1 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -116,5 +116,5 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha } } -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index f29b30536146e..efc513cf94d29 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -79,7 +79,7 @@ #define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ // ------------------------ -// Public Variables +// Serial ports // ------------------------ #if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE @@ -112,72 +112,21 @@ #endif #endif -uint16_t HAL_adc_result; - // ------------------------ -// Private Variables +// ADC // ------------------------ -STM32ADC adc(ADC1); -const uint8_t adc_pins[] = { - #if HAS_TEMP_ADC_0 - TEMP_0_PIN, - #endif - #if HAS_TEMP_ADC_PROBE - TEMP_PROBE_PIN, - #endif - #if HAS_HEATED_BED - TEMP_BED_PIN, - #endif - #if HAS_TEMP_CHAMBER - TEMP_CHAMBER_PIN, - #endif - #if HAS_TEMP_COOLER - TEMP_COOLER_PIN, - #endif - #if HAS_TEMP_ADC_1 - TEMP_1_PIN, - #endif - #if HAS_TEMP_ADC_2 - TEMP_2_PIN, - #endif - #if HAS_TEMP_ADC_3 - TEMP_3_PIN, - #endif - #if HAS_TEMP_ADC_4 - TEMP_4_PIN, - #endif - #if HAS_TEMP_ADC_5 - TEMP_5_PIN, - #endif - #if HAS_TEMP_ADC_6 - TEMP_6_PIN, - #endif - #if HAS_TEMP_ADC_7 - TEMP_7_PIN, - #endif - #if ENABLED(FILAMENT_WIDTH_SENSOR) - FILWIDTH_PIN, - #endif - #if HAS_ADC_BUTTONS - ADC_KEYPAD_PIN, - #endif - #if HAS_JOY_ADC_X - JOY_X_PIN, - #endif - #if HAS_JOY_ADC_Y - JOY_Y_PIN, - #endif - #if HAS_JOY_ADC_Z - JOY_Z_PIN, - #endif - #if ENABLED(POWER_MONITOR_CURRENT) - POWER_MONITOR_CURRENT_PIN, - #endif - #if ENABLED(POWER_MONITOR_VOLTAGE) - POWER_MONITOR_VOLTAGE_PIN, - #endif -}; +uint16_t analogRead(pin_t pin) { + const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG; + return is_analog ? analogRead(uint8_t(pin)) : 0; +} + +// Wrapper to maple unprotected analogWrite +void analogWrite(pin_t pin, int pwm_val8) { + if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8); +} + +uint16_t MarlinHAL::adc_result; enum TempPinIndex : char { #if HAS_TEMP_ADC_0 @@ -245,15 +194,16 @@ uint16_t HAL_adc_results[ADC_PIN_COUNT]; // ------------------------ // Private functions // ------------------------ + static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); // only values 0..7 are used - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ + reg_value = SCB->AIRCR; // read old register configuration + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); // clear bits to change reg_value = (reg_value | ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8)); /* Insert write key & priority group */ + (PriorityGroupTmp << 8)); // Insert write key & priority group SCB->AIRCR = reg_value; } @@ -261,6 +211,8 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { // Public functions // ------------------------ +void flashFirmware(const int16_t) { hal.reboot(); } + // // Leave PA11/PA12 intact if USBSerial is not used // @@ -280,7 +232,11 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -void HAL_init() { +// ------------------------ +// MarlinHAL class +// ------------------------ + +void MarlinHAL::init() { NVIC_SetPriorityGrouping(0x3); #if PIN_EXISTS(LED) OUT_WRITE(LED_PIN, LOW); @@ -299,7 +255,7 @@ void HAL_init() { } // HAL idle task -void HAL_idletask() { +void MarlinHAL::idletask() { #if HAS_SHARED_MEDIA // If Marlin is using the SD card we need to lock it to prevent access from // a PC via USB. @@ -314,14 +270,7 @@ void HAL_idletask() { #endif } -void HAL_clear_reset_source() { } - -/** - * TODO: Check this and change or remove. - */ -uint8_t HAL_get_reset_source() { return RST_POWER_ON; } - -void _delay_ms(const int delay_ms) { delay(delay_ms); } +void MarlinHAL::reboot() { nvic_sys_reset(); } extern "C" { extern unsigned int _ebss; // end of bss section @@ -355,11 +304,70 @@ extern "C" { } */ -// ------------------------ // ADC -// ------------------------ + // Init the AD in continuous capture mode -void HAL_adc_init() { +void MarlinHAL::adc_init() { + static const uint8_t adc_pins[] = { + #if HAS_TEMP_ADC_0 + TEMP_0_PIN, + #endif + #if HAS_TEMP_ADC_PROBE + TEMP_PROBE_PIN, + #endif + #if HAS_HEATED_BED + TEMP_BED_PIN, + #endif + #if HAS_TEMP_CHAMBER + TEMP_CHAMBER_PIN, + #endif + #if HAS_TEMP_COOLER + TEMP_COOLER_PIN, + #endif + #if HAS_TEMP_ADC_1 + TEMP_1_PIN, + #endif + #if HAS_TEMP_ADC_2 + TEMP_2_PIN, + #endif + #if HAS_TEMP_ADC_3 + TEMP_3_PIN, + #endif + #if HAS_TEMP_ADC_4 + TEMP_4_PIN, + #endif + #if HAS_TEMP_ADC_5 + TEMP_5_PIN, + #endif + #if HAS_TEMP_ADC_6 + TEMP_6_PIN, + #endif + #if HAS_TEMP_ADC_7 + TEMP_7_PIN, + #endif + #if ENABLED(FILAMENT_WIDTH_SENSOR) + FILWIDTH_PIN, + #endif + #if HAS_ADC_BUTTONS + ADC_KEYPAD_PIN, + #endif + #if HAS_JOY_ADC_X + JOY_X_PIN, + #endif + #if HAS_JOY_ADC_Y + JOY_Y_PIN, + #endif + #if HAS_JOY_ADC_Z + JOY_Z_PIN, + #endif + #if ENABLED(POWER_MONITOR_CURRENT) + POWER_MONITOR_CURRENT_PIN, + #endif + #if ENABLED(POWER_MONITOR_VOLTAGE) + POWER_MONITOR_VOLTAGE_PIN, + #endif + }; + static STM32ADC adc(ADC1); // configure the ADC adc.calibrate(); #if F_CPU > 72000000 @@ -374,10 +382,10 @@ void HAL_adc_init() { adc.startConversion(); } -void HAL_adc_start_conversion(const uint8_t adc_pin) { +void MarlinHAL::adc_start(const pin_t pin) { //TEMP_PINS pin_index; TempPinIndex pin_index; - switch (adc_pin) { + switch (pin) { default: return; #if HAS_TEMP_ADC_0 case TEMP_0_PIN: pin_index = TEMP_0; break; @@ -440,20 +448,4 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits } -uint16_t HAL_adc_get_result() { return HAL_adc_result; } - -uint16_t analogRead(pin_t pin) { - const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG; - return is_analog ? analogRead(uint8_t(pin)) : 0; -} - -// Wrapper to maple unprotected analogWrite -void analogWrite(pin_t pin, int pwm_val8) { - if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8); -} - -void HAL_reboot() { nvic_sys_reset(); } - -void flashFirmware(const int16_t) { HAL_reboot(); } - #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 153cfe8ac89e6..517c8f2cb808a 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -66,6 +66,10 @@ #endif #endif +// ------------------------ +// Serial ports +// ------------------------ + #ifdef SERIAL_USB typedef ForwardSerial1Class< USBSerial > DefaultSerial1; extern DefaultSerial1 MSerial0; @@ -141,11 +145,6 @@ #endif #endif -// Set interrupt grouping for this MCU -void HAL_init(); -#define HAL_IDLETASK 1 -void HAL_idletask(); - /** * TODO: review this to return 1 for pins that are not analog input */ @@ -158,15 +157,7 @@ void HAL_idletask(); #define NO_COMPILE_TIME_PWM #endif -#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); (void)__iCliRetVal() -#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal() -#define ISRS_ENABLED() (!__get_primask()) -#define ENABLE_ISRS() ((void)__iSeiRetVal()) -#define DISABLE_ISRS() ((void)__iCliRetVal()) - -// On AVR this is in math.h? -#define square(x) ((x)*(x)) - +// Reset Reason #define RST_POWER_ON 1 #define RST_EXTERNAL 2 #define RST_BROWN_OUT 4 @@ -181,62 +172,24 @@ void HAL_idletask(); typedef int8_t pin_t; -// ------------------------ -// Public Variables -// ------------------------ - // Result of last ADC conversion extern uint16_t HAL_adc_result; // ------------------------ -// Public functions +// Interrupts // ------------------------ -// Disable interrupts +#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); (void)__iCliRetVal() +#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal() #define cli() noInterrupts() - -// Enable interrupts #define sei() interrupts() -// Memory related -#define __bss_end __bss_end__ - -// Clear reset reason -void HAL_clear_reset_source(); - -// Reset reason -uint8_t HAL_get_reset_source(); - -void HAL_reboot(); - -void _delay_ms(const int delay); - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" - -/* -extern "C" { - int freeMemory(); -} -*/ - -extern "C" char* _sbrk(int incr); - -static inline int freeMemory() { - volatile char top; - return &top - _sbrk(0); -} - -#pragma GCC diagnostic pop - -// +// ------------------------ // ADC -// +// ------------------------ #define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG); -void HAL_adc_init(); - #ifdef ADC_RESOLUTION #define HAL_ADC_RESOLUTION ADC_RESOLUTION #else @@ -244,43 +197,116 @@ void HAL_adc_init(); #endif #define HAL_ADC_VREF 3.3 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? +// +// Pin Mapping for M42, M43, M226 +// #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY) +#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY) #define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE) #define PLATFORM_M997_SUPPORT void flashFirmware(const int16_t); +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment #ifndef PWM_FREQUENCY #define PWM_FREQUENCY 1000 // Default PWM Frequency #endif -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment -/** - * set_pwm_frequency - * Set the frequency of the timer corresponding to the provided pin - * All Timer PWM pins run at the same frequency - */ -void set_pwm_frequency(const pin_t pin, int f_desired); +// ------------------------ +// Class Utilities +// ------------------------ -/** - * set_pwm_duty - * Set the PWM duty cycle of the provided pin to the provided value - * Optionally allows inverting the duty cycle [default = false] - * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. - */ -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); +// Memory related +#define __bss_end __bss_end__ + +void _delay_ms(const int ms); + +extern "C" char* _sbrk(int incr); + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +static inline int freeMemory() { + volatile char top; + return &top - _sbrk(0); +} + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + static inline bool isr_state() { return !__get_primask(); } + static inline void isr_on() { ((void)__iSeiRetVal()); } + static inline void isr_off() { ((void)__iCliRetVal()); } + + static inline void delay_ms(const int ms) { delay(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static inline uint8_t get_reset_source() { return RST_POWER_ON; } + static inline void clear_reset_source() {} + + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin); + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] + * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false); + + /** + * Set the frequency of the timer for the given pin. + * All Timer PWM pins run at the same frequency. + */ + static void set_pwm_frequency(const pin_t pin, int f_desired); + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/STM32F1/Servo.h b/Marlin/src/HAL/STM32F1/Servo.h index b6143de81d62a..745a1c93f07d4 100644 --- a/Marlin/src/HAL/STM32F1/Servo.h +++ b/Marlin/src/HAL/STM32F1/Servo.h @@ -35,7 +35,8 @@ #define SERVO_DEFAULT_MIN_ANGLE 0 #define SERVO_DEFAULT_MAX_ANGLE 180 -#define HAL_SERVO_LIB libServo +class libServo; +typedef libServo hal_servo_t; class libServo { public: diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp index 98d56bc5e9319..11a1a107123e6 100644 --- a/Marlin/src/HAL/STM32F1/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp @@ -21,11 +21,9 @@ */ #ifdef __STM32F1__ -#include "../../inc/MarlinConfigPre.h" +#include "../../inc/MarlinConfig.h" #include -#include "HAL.h" -#include "timers.h" #define NR_TIMERS TERN(STM32_XL_DENSITY, 14, 8) // Maple timers, 14 for STM32_XL_DENSITY (F/G chips), 8 for HIGH density (C D E) @@ -38,7 +36,7 @@ inline uint8_t timer_and_index_for_pin(const pin_t pin, timer_dev **timer_ptr) { return 0; } -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!PWM_PIN(pin)) return; timer_dev *timer; UNUSED(timer); @@ -51,7 +49,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode } -void set_pwm_frequency(const pin_t pin, int f_desired) { +void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer timer_dev *timer; UNUSED(timer); diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index f9ab6d13d3741..0cd807fc84799 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -188,7 +188,7 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP // No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple. // Needed here to reset ARPE=0 for stepper timer diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp index f08cf799e9e8b..b923ab77b1f12 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL.cpp @@ -31,6 +31,10 @@ #include +// ------------------------ +// Serial ports +// ------------------------ + #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -40,33 +44,32 @@ #endif USBSerialType USBSerial(false, SerialUSB); -uint16_t HAL_adc_result; - -static const uint8_t pin2sc1a[] = { - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13 - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9) - 31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33 - 0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13) - 26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0. -}; - -/* - // disable interrupts - void cli() { noInterrupts(); } +// ------------------------ +// Class Utilities +// ------------------------ - // enable interrupts - void sei() { interrupts(); } -*/ +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; -void HAL_adc_init() { - analog_init(); - while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish - NVIC_ENABLE_IRQ(IRQ_FTM1); + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } } -void HAL_clear_reset_source() { } +// ------------------------ +// MarlinHAL Class +// ------------------------ -uint8_t HAL_get_reset_source() { +void MarlinHAL::reboot() { _reboot_Teensyduino_(); } + +uint8_t MarlinHAL::get_reset_source() { switch (RCM_SRS0) { case 128: return RST_POWER_ON; break; case 64: return RST_EXTERNAL; break; @@ -78,25 +81,25 @@ uint8_t HAL_get_reset_source() { return 0; } -void HAL_reboot() { _reboot_Teensyduino_(); } +// ADC -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; - - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; - } +void MarlinHAL::adc_init() { + analog_init(); + while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish + NVIC_ENABLE_IRQ(IRQ_FTM1); } -void HAL_adc_start_conversion(const uint8_t adc_pin) { ADC0_SC1A = pin2sc1a[adc_pin]; } +void MarlinHAL::adc_start(const pin_t pin) { + static const uint8_t pin2sc1a[] = { + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13 + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9) + 31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33 + 0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13) + 26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0. + }; + ADC0_SC1A = pin2sc1a[pin]; +} -uint16_t HAL_adc_get_result() { return ADC0_RA; } +uint16_t MarlinHAL::adc_value() { return ADC0_RA; } #endif // __MK20DX256__ diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 61d8b34604c52..fdf914b1b02e2 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -36,12 +36,9 @@ #include -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -//#undef MOTHERBOARD -//#define MOTHERBOARD BOARD_TEENSY31_32 +// ------------------------ +// Defines +// ------------------------ #define IS_32BIT_TEENSY 1 #define IS_TEENSY_31_32 1 @@ -49,6 +46,14 @@ #define IS_TEENSY32 1 #endif +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +// ------------------------ +// Serial ports +// ------------------------ + #include "../../core/serial_hook.h" #define Serial0 Serial @@ -72,31 +77,46 @@ extern USBSerialType USBSerial; #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif -#define HAL_SERVO_LIB libServo +// ------------------------ +// Types +// ------------------------ + +class libServo; +typedef libServo hal_servo_t; typedef int8_t pin_t; +// ------------------------ +// Interrupts +// ------------------------ + +uint32_t __get_PRIMASK(void); // CMSIS +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() + +// ------------------------ +// ADC +// ------------------------ + #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_PRIMASK()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() - -inline void HAL_init() {} - -// Clear the reset reason -void HAL_clear_reset_source(); +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 -// Get the reason for the reset -uint8_t HAL_get_reset_source(); +#define HAL_ANALOG_SELECT(pin) -void HAL_reboot(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -107,27 +127,64 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ADC +// ------------------------ +// MarlinHAL Class +// ------------------------ -void HAL_adc_init(); +class MarlinHAL { +public: -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ANALOG_SELECT(pin) + static inline void init() {} // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); + static inline bool isr_state() { return !__get_PRIMASK(); } + static inline void isr_on() { __enable_irq(); } + static inline void isr_off() { __disable_irq(); } -// PWM + static inline void delay_ms(const int ms) { delay(ms); } -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // Tasks, called from idle() + static inline void idletask() {} -// Pin Map + // Reset + static uint8_t get_reset_source(); + static inline void clear_reset_source() {} -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t ch); + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t ch); + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 3b073d63ab293..9fcbb6f232c93 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -110,4 +110,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp index 046c00b56ed53..54a5ad3855361 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL.cpp @@ -31,6 +31,10 @@ #include +// ------------------------ +// Serial ports +// ------------------------ + #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -39,42 +43,34 @@ USBSerialType USBSerial(false, SerialUSB); -uint16_t HAL_adc_result, HAL_adc_select; - -static const uint8_t pin2sc1a[] = { - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13 - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9 - 255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only - 14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128, // 31-39 are A12-A20 - 255, 255, 255, 255, 255, 255, 255, 255, 255, // 40-48 are digital only - 10+128, 11+128, // 49-50 are A23-A24 - 255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only - 255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only - 3, 19+128, // 64-65 are A10-A11 - 23, 23+128,// 66-67 are A21-A22 (DAC pins) - 1, 1+128, // 68-69 are A25-A26 (unused USB host port on Teensy 3.5) - 26, // 70 is Temperature Sensor - 18+128 // 71 is Vref -}; - -/* - // disable interrupts - void cli() { noInterrupts(); } - - // enable interrupts - void sei() { interrupts(); } -*/ - -void HAL_adc_init() { - analog_init(); - while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish - while (ADC1_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish - NVIC_ENABLE_IRQ(IRQ_FTM1); +// ------------------------ +// Class Utilities +// ------------------------ + +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; + + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } } -void HAL_clear_reset_source() { } +// ------------------------ +// MarlinHAL Class +// ------------------------ -uint8_t HAL_get_reset_source() { +void MarlinHAL::reboot() { _reboot_Teensyduino_(); } + +// Reset + +uint8_t MarlinHAL::get_reset_source() { switch (RCM_SRS0) { case 128: return RST_POWER_ON; break; case 64: return RST_EXTERNAL; break; @@ -86,41 +82,49 @@ uint8_t HAL_get_reset_source() { return 0; } -void HAL_reboot() { _reboot_Teensyduino_(); } +// ADC -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; +int8_t MarlinHAL::adc_select; - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; - } +void MarlinHAL::adc_init() { + analog_init(); + while (ADC0_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ } + while (ADC1_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ } + NVIC_ENABLE_IRQ(IRQ_FTM1); } -void HAL_adc_start_conversion(const uint8_t adc_pin) { +void MarlinHAL::adc_start(const pin_t adc_pin) { + static const uint8_t pin2sc1a[] = { + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13 + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9 + 255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only + 14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128, // 31-39 are A12-A20 + 255, 255, 255, 255, 255, 255, 255, 255, 255, // 40-48 are digital only + 10+128, 11+128, // 49-50 are A23-A24 + 255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only + 255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only + 3, 19+128, // 64-65 are A10-A11 + 23, 23+128,// 66-67 are A21-A22 (DAC pins) + 1, 1+128, // 68-69 are A25-A26 (unused USB host port on Teensy 3.5) + 26, // 70 is Temperature Sensor + 18+128 // 71 is Vref + }; const uint16_t pin = pin2sc1a[adc_pin]; if (pin == 0xFF) { - // Digital only - HAL_adc_select = -1; + adc_select = -1; // Digital only } else if (pin & 0x80) { - HAL_adc_select = 1; + adc_select = 1; ADC1_SC1A = pin & 0x7F; } else { - HAL_adc_select = 0; + adc_select = 0; ADC0_SC1A = pin; } } -uint16_t HAL_adc_get_result() { - switch (HAL_adc_select) { +uint16_t MarlinHAL::adc_value() { + switch (adc_select) { case 0: return ADC0_RA; case 1: return ADC1_RA; } diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 892eb2d3c5b8f..5506599cdf036 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -37,10 +37,6 @@ #include #include -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - // ------------------------ // Defines // ------------------------ @@ -53,6 +49,17 @@ #define IS_TEENSY35 1 #endif +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +#undef sq +#define sq(x) ((x)*(x)) + +// ------------------------ +// Serial ports +// ------------------------ + #include "../../core/serial_hook.h" #define Serial0 Serial @@ -76,34 +83,45 @@ extern USBSerialType USBSerial; #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif -#define HAL_SERVO_LIB libServo +// ------------------------ +// Types +// ------------------------ + +class libServo; +typedef libServo hal_servo_t; typedef int8_t pin_t; -#ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) -#endif +// ------------------------ +// Interrupts +// ------------------------ -#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_primask()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() +#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() -#undef sq -#define sq(x) ((x)*(x)) +// ------------------------ +// ADC +// ------------------------ -inline void HAL_init() {} +#ifndef analogInputToDigitalPin + #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) +#endif -// Clear reset reason -void HAL_clear_reset_source(); +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 -// Reset reason -uint8_t HAL_get_reset_source(); +#define HAL_ANALOG_SELECT(pin) -void HAL_reboot(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -114,27 +132,66 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ADC +// ------------------------ +// MarlinHAL Class +// ------------------------ -void HAL_adc_init(); +class MarlinHAL { +public: -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ANALOG_SELECT(pin) + static inline void init() {} // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); + static inline bool isr_state() { return true; } + static inline void isr_on() { __enable_irq(); } + static inline void isr_off() { __disable_irq(); } -// PWM + static inline void delay_ms(const int ms) { delay(ms); } -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // Tasks, called from idle() + static inline void idletask() {} -// Pin Map + // Reset + static uint8_t get_reset_source(); + static inline void clear_reset_source() {} -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + // Free SRAM + static inline int freeMemory() { return freeMemory(); } + + // + // ADC Methods + // + + static int8_t adc_select; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static inline void adc_enable(const pin_t) {} + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 6c342bbe0d252..8af79d73928e5 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -109,4 +109,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index 270bee0dc9d45..68bd38f72ff89 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -33,6 +33,10 @@ #include "timers.h" #include +// ------------------------ +// Serial ports +// ------------------------ + #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -40,75 +44,42 @@ #endif USBSerialType USBSerial(false, SerialUSB); -uint16_t HAL_adc_result, HAL_adc_select; - -static const uint8_t pin2sc1a[] = { - 0x07, // 0/A0 AD_B1_02 - 0x08, // 1/A1 AD_B1_03 - 0x0C, // 2/A2 AD_B1_07 - 0x0B, // 3/A3 AD_B1_06 - 0x06, // 4/A4 AD_B1_01 - 0x05, // 5/A5 AD_B1_00 - 0x0F, // 6/A6 AD_B1_10 - 0x00, // 7/A7 AD_B1_11 - 0x0D, // 8/A8 AD_B1_08 - 0x0E, // 9/A9 AD_B1_09 - 0x01, // 24/A10 AD_B0_12 - 0x02, // 25/A11 AD_B0_13 - 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 - 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 - 0x07, // 14/A0 AD_B1_02 - 0x08, // 15/A1 AD_B1_03 - 0x0C, // 16/A2 AD_B1_07 - 0x0B, // 17/A3 AD_B1_06 - 0x06, // 18/A4 AD_B1_01 - 0x05, // 19/A5 AD_B1_00 - 0x0F, // 20/A6 AD_B1_10 - 0x00, // 21/A7 AD_B1_11 - 0x0D, // 22/A8 AD_B1_08 - 0x0E, // 23/A9 AD_B1_09 - 0x01, // 24/A10 AD_B0_12 - 0x02, // 25/A11 AD_B0_13 - 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 - 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 - #ifdef ARDUINO_TEENSY41 - 0xFF, // 28 - 0xFF, // 29 - 0xFF, // 30 - 0xFF, // 31 - 0xFF, // 32 - 0xFF, // 33 - 0xFF, // 34 - 0xFF, // 35 - 0xFF, // 36 - 0xFF, // 37 - 0x81, // 38/A14 AD_B1_12 - only on ADC2, 1 - 0x82, // 39/A15 AD_B1_13 - only on ADC2, 2 - 0x09, // 40/A16 AD_B1_04 - 0x0A, // 41/A17 AD_B1_05 - #endif -}; - -/* -// disable interrupts -void cli() { noInterrupts(); } - -// enable interrupts -void sei() { interrupts(); } -*/ - -void HAL_adc_init() { - analog_init(); - while (ADC1_GC & ADC_GC_CAL) ; - while (ADC2_GC & ADC_GC_CAL) ; +// ------------------------ +// Class Utilities +// ------------------------ + +#define __bss_end _ebss + +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; + + // Doesn't work on Teensy 4.x + uint32_t freeMemory() { + uint32_t free_memory; + free_memory = ((uint32_t)&free_memory) - (((uint32_t)__brkval) ?: ((uint32_t)&__bss_end)); + return free_memory; + } } -void HAL_clear_reset_source() { - uint32_t reset_source = SRC_SRSR; - SRC_SRSR = reset_source; +// ------------------------ +// FastIO +// ------------------------ + +bool is_output(pin_t pin) { + const struct digital_pin_bitband_and_config_table_struct *p; + p = digital_pin_to_info_PGM + pin; + return (*(p->reg + 1) & p->mask); } -uint8_t HAL_get_reset_source() { +// ------------------------ +// MarlinHAL Class +// ------------------------ + +void MarlinHAL::reboot() { _reboot_Teensyduino_(); } + +uint8_t MarlinHAL::get_reset_source() { switch (SRC_SRSR & 0xFF) { case 1: return RST_POWER_ON; break; case 2: return RST_SOFTWARE; break; @@ -121,57 +92,92 @@ uint8_t HAL_get_reset_source() { return 0; } -void HAL_reboot() { _reboot_Teensyduino_(); } +void MarlinHAL::clear_reset_source() { + uint32_t reset_source = SRC_SRSR; + SRC_SRSR = reset_source; +} -#define __bss_end _ebss +// ADC -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; +int8_t MarlinHAL::adc_select; - // Doesn't work on Teensy 4.x - uint32_t freeMemory() { - uint32_t free_memory; - if ((uint32_t)__brkval == 0) - free_memory = ((uint32_t)&free_memory) - ((uint32_t)&__bss_end); - else - free_memory = ((uint32_t)&free_memory) - ((uint32_t)__brkval); - return free_memory; - } +void MarlinHAL::adc_init() { + analog_init(); + while (ADC1_GC & ADC_GC_CAL) { /* wait */ } + while (ADC2_GC & ADC_GC_CAL) { /* wait */ } } -void HAL_adc_start_conversion(const uint8_t adc_pin) { +void MarlinHAL::adc_start(const pin_t adc_pin) { + static const uint8_t pin2sc1a[] = { + 0x07, // 0/A0 AD_B1_02 + 0x08, // 1/A1 AD_B1_03 + 0x0C, // 2/A2 AD_B1_07 + 0x0B, // 3/A3 AD_B1_06 + 0x06, // 4/A4 AD_B1_01 + 0x05, // 5/A5 AD_B1_00 + 0x0F, // 6/A6 AD_B1_10 + 0x00, // 7/A7 AD_B1_11 + 0x0D, // 8/A8 AD_B1_08 + 0x0E, // 9/A9 AD_B1_09 + 0x01, // 24/A10 AD_B0_12 + 0x02, // 25/A11 AD_B0_13 + 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 + 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 + 0x07, // 14/A0 AD_B1_02 + 0x08, // 15/A1 AD_B1_03 + 0x0C, // 16/A2 AD_B1_07 + 0x0B, // 17/A3 AD_B1_06 + 0x06, // 18/A4 AD_B1_01 + 0x05, // 19/A5 AD_B1_00 + 0x0F, // 20/A6 AD_B1_10 + 0x00, // 21/A7 AD_B1_11 + 0x0D, // 22/A8 AD_B1_08 + 0x0E, // 23/A9 AD_B1_09 + 0x01, // 24/A10 AD_B0_12 + 0x02, // 25/A11 AD_B0_13 + 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 + 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 + #ifdef ARDUINO_TEENSY41 + 0xFF, // 28 + 0xFF, // 29 + 0xFF, // 30 + 0xFF, // 31 + 0xFF, // 32 + 0xFF, // 33 + 0xFF, // 34 + 0xFF, // 35 + 0xFF, // 36 + 0xFF, // 37 + 0x81, // 38/A14 AD_B1_12 - only on ADC2, 1 + 0x82, // 39/A15 AD_B1_13 - only on ADC2, 2 + 0x09, // 40/A16 AD_B1_04 + 0x0A, // 41/A17 AD_B1_05 + #endif + }; const uint16_t pin = pin2sc1a[adc_pin]; if (pin == 0xFF) { - HAL_adc_select = -1; // Digital only + adc_select = -1; // Digital only } else if (pin & 0x80) { - HAL_adc_select = 1; + adc_select = 1; ADC2_HC0 = pin & 0x7F; } else { - HAL_adc_select = 0; + adc_select = 0; ADC1_HC0 = pin; } } -uint16_t HAL_adc_get_result() { - switch (HAL_adc_select) { +uint16_t MarlinHAL::adc_value() { + switch (adc_select) { case 0: - while (!(ADC1_HS & ADC_HS_COCO0)) ; // wait + while (!(ADC1_HS & ADC_HS_COCO0)) { /* wait */ } return ADC1_R0; case 1: - while (!(ADC2_HS & ADC_HS_COCO0)) ; // wait + while (!(ADC2_HS & ADC_HS_COCO0)) { /* wait */ } return ADC2_R0; } return 0; } -bool is_output(pin_t pin) { - const struct digital_pin_bitband_and_config_table_struct *p; - p = digital_pin_to_info_PGM + pin; - return (*(p->reg + 1) & p->mask); -} - #endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 2b730768a8025..4a0b5688d77cf 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -41,10 +41,6 @@ #include "../../feature/ethernet.h" #endif -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - // ------------------------ // Defines // ------------------------ @@ -55,7 +51,23 @@ #define IS_TEENSY41 1 #endif +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +#undef sq +#define sq(x) ((x)*(x)) + +// Don't place string constants in PROGMEM +#undef PSTR +#define PSTR(str) ({static const char *data = (str); &data[0];}) + +// ------------------------ +// Serial ports +// ------------------------ + #include "../../core/serial_hook.h" + #define Serial0 Serial #define _DECLARE_SERIAL(X) \ typedef ForwardSerial1Class DefaultSerial##X; \ @@ -89,41 +101,49 @@ extern USBSerialType USBSerial; #endif #endif -#define HAL_SERVO_LIB libServo +// ------------------------ +// Types +// ------------------------ + +class libServo; +typedef libServo hal_servo_t; typedef int8_t pin_t; -#ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) -#endif +// ------------------------ +// Interrupts +// ------------------------ -#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq() -#define CRITICAL_SECTION_END() if (!primask) __enable_irq() -#define ISRS_ENABLED() (!__get_primask()) -#define ENABLE_ISRS() __enable_irq() -#define DISABLE_ISRS() __disable_irq() +#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() -#undef sq -#define sq(x) ((x)*(x)) +// ------------------------ +// ADC +// ------------------------ -// Don't place string constants in PROGMEM -#undef PSTR -#define PSTR(str) ({static const char *data = (str); &data[0];}) +#ifndef analogInputToDigitalPin + #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) +#endif -// Enable hooks into idle and setup for HAL -#define HAL_IDLETASK 1 -FORCE_INLINE void HAL_idletask() {} -FORCE_INLINE void HAL_init() {} +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_FILTERED // turn off ADC oversampling -// Clear reset reason -void HAL_clear_reset_source(); +#define HAL_ANALOG_SELECT(pin) -// Reset reason -uint8_t HAL_get_reset_source(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -void HAL_reboot(); +// FastIO +bool is_output(pin_t pin); -FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -134,30 +154,66 @@ extern "C" uint32_t freeMemory(); #pragma GCC diagnostic pop -// ADC +// ------------------------ +// MarlinHAL Class +// ------------------------ -void HAL_adc_init(); +class MarlinHAL { +public: -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_ADC_FILTERED // turn off ADC oversampling -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ANALOG_SELECT(pin) + static inline void init() {} // Called early in setup() + static inline void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); + static inline bool isr_state() { return !__get_primask(); } + static inline void isr_on() { __enable_irq(); } + static inline void isr_off() { __disable_irq(); } -// PWM + static inline void delay_ms(const int ms) { delay(ms); } -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // Tasks, called from idle() + static inline void idletask() {} -// Pin Map + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source(); -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + // Free SRAM + static inline int freeMemory() { return freeMemory(); } -bool is_output(pin_t pin); + // + // ADC Methods + // + + static int8_t adc_select; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin); + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static inline bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; + +extern MarlinHAL hal; diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 81cf67f7bc08a..77fe0953d3bd5 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -114,4 +114,4 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); //void HAL_timer_isr_epilogue(const uint8_t timer_num) {} -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/shared/HAL.cpp b/Marlin/src/HAL/shared/HAL.cpp new file mode 100644 index 0000000000000..a5fe407188db4 --- /dev/null +++ b/Marlin/src/HAL/shared/HAL.cpp @@ -0,0 +1,36 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * HAL/shared/HAL.cpp + */ + +#include "../../inc/MarlinConfig.h" + +MarlinHAL hal; + +#if ENABLED(SOFT_RESET_VIA_SERIAL) + + // Global for use by e_parser.h + void HAL_reboot() { hal.reboot(); } + +#endif diff --git a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp index bd85dbe7bd7ef..5d4ce89b2748e 100644 --- a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp +++ b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp @@ -92,9 +92,9 @@ uint8_t L64XX_Marlin::transfer_single(uint8_t data, int16_t ss_pin) { // First device in chain has data sent last extDigitalWrite(ss_pin, LOW); - DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips) + hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips) const uint8_t data_out = L6470_SpiTransfer_Mode_3(data); - ENABLE_ISRS(); // Enable interrupts + hal.isr_on(); // Enable interrupts extDigitalWrite(ss_pin, HIGH); return data_out; @@ -107,9 +107,9 @@ uint8_t L64XX_Marlin::transfer_chain(uint8_t data, int16_t ss_pin, uint8_t chain extDigitalWrite(ss_pin, LOW); for (uint8_t i = L64XX::chain[0]; !L64xxManager.spi_abort && i >= 1; i--) { // Send data unless aborted - DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips) + hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips) const uint8_t temp = L6470_SpiTransfer_Mode_3(uint8_t(i == chain_position ? data : dSPIN_NOP)); - ENABLE_ISRS(); // Enable interrupts + hal.isr_on(); // Enable interrupts if (i == chain_position) data_out = temp; } diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5132d07e8711f..009edeba2f581 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -790,7 +790,7 @@ void idle(bool no_stepper_sleep/*=false*/) { #endif // Run HAL idle tasks - TERN_(HAL_IDLETASK, HAL_idletask()); + hal.idletask(); // Check network connection TERN_(HAS_ETHERNET, ethernet.check()); @@ -929,7 +929,7 @@ void minkill(const bool steppers_off/*=false*/) { watchdog_refresh(); // Reboot the board - HAL_reboot(); + hal.reboot(); #else @@ -1041,7 +1041,7 @@ inline void tmc_standby_setup() { * • L64XX Stepper Drivers (SPI) * • Stepper Driver Reset: DISABLE * • TMC Stepper Drivers (SPI) - * • Run BOARD_INIT if defined + * • Run hal.init_board() for additional pins setup * • ESP WiFi * - Get the Reset Reason and report it * - Print startup messages and diagnostics @@ -1119,8 +1119,8 @@ void setup() { tmc_standby_setup(); // TMC Low Power Standby pins must be set early or they're not usable // Check startup - does nothing if bootloader sets MCUSR to 0 - const byte mcu = HAL_get_reset_source(); - HAL_clear_reset_source(); + const byte mcu = hal.get_reset_source(); + hal.clear_reset_source(); #if ENABLED(MARLIN_DEV_MODE) auto log_current_ms = [&](PGM_P const msg) { @@ -1181,23 +1181,20 @@ void setup() { JTAGSWD_RESET(); #endif - #if EITHER(DISABLE_DEBUG, DISABLE_JTAG) + // Disable any hardware debug to free up pins for IO + #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) delay(10); - // Disable any hardware debug to free up pins for IO - #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) - SETUP_LOG("JTAGSWD_DISABLE"); - JTAGSWD_DISABLE(); - #elif defined(JTAG_DISABLE) - SETUP_LOG("JTAG_DISABLE"); - JTAG_DISABLE(); - #else - #error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board." - #endif + SETUP_LOG("JTAGSWD_DISABLE"); + JTAGSWD_DISABLE(); + #elif ENABLED(DISABLE_JTAG) && defined(JTAG_DISABLE) + delay(10); + SETUP_LOG("JTAG_DISABLE"); + JTAG_DISABLE(); #endif TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime - SETUP_RUN(HAL_init()); + SETUP_RUN(hal.init()); // Init and disable SPI thermocouples; this is still needed #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0)) @@ -1243,19 +1240,16 @@ void setup() { SETUP_RUN(tmc_init_cs_pins()); #endif - #ifdef BOARD_INIT - SETUP_LOG("BOARD_INIT"); - BOARD_INIT(); - #endif + SETUP_RUN(hal.init_board()); SETUP_RUN(esp_wifi_init()); // Report Reset Reason - if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP); - if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET); + if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP); + if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET); if (mcu & RST_BROWN_OUT) SERIAL_ECHOLNPGM(STR_BROWNOUT_RESET); - if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET); - if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); + if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET); + if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); // Identify myself as Marlin x.x.x SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION); @@ -1266,7 +1260,7 @@ void setup() { ); #endif SERIAL_ECHO_MSG(" Compiled: " __DATE__); - SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); + SERIAL_ECHO_MSG(STR_FREE_MEMORY, hal.freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); // Some HAL need precise delay adjustment calibrate_delay_loop(); @@ -1538,7 +1532,7 @@ void setup() { #endif #if ENABLED(USE_WATCHDOG) - SETUP_RUN(watchdog_init()); // Reinit watchdog after HAL_get_reset_source call + SETUP_RUN(watchdog_init()); // Reinit watchdog after hal.get_reset_source call #endif #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index 59832fd6edd7c..a58cb66affc78 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -69,7 +69,7 @@ void CaseLight::update(const bool sflag) { #if CASELIGHT_USES_BRIGHTNESS if (pin_is_pwm()) - set_pwm_duty(pin_t(CASE_LIGHT_PIN), ( + hal.set_pwm_duty(pin_t(CASE_LIGHT_PIN), ( #if CASE_LIGHT_MAX_PWM == 255 n10ct #else diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index 59ba665e11144..f42bf52ae40a0 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -76,7 +76,7 @@ void ControllerFan::update() { thermalManager.soft_pwm_controller_speed = speed; #else if (PWM_PIN(CONTROLLER_FAN_PIN)) - set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); + hal.set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); else WRITE(CONTROLLER_FAN_PIN, speed > 0); #endif diff --git a/Marlin/src/feature/e_parser.h b/Marlin/src/feature/e_parser.h index 1dee0cf7550c1..fda1ba144bc4d 100644 --- a/Marlin/src/feature/e_parser.h +++ b/Marlin/src/feature/e_parser.h @@ -41,7 +41,9 @@ extern bool wait_for_user, wait_for_heatup; void quickresume_stepper(); #endif -void HAL_reboot(); +#if ENABLED(SOFT_RESET_VIA_SERIAL) + void HAL_reboot(); +#endif class EmergencyParser { diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 17d790b8cc9a2..0a4b5114769de 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -123,7 +123,7 @@ void LEDLights::set_color(const LEDColor &incol // If the pins can do PWM then their intensity will be set. #define _UPDATE_RGBW(C,c) do { \ if (PWM_PIN(RGB_LED_##C##_PIN)) \ - set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \ + hal.set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \ else \ WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \ }while(0) diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index cde2b47d90aad..2840a92c58383 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -66,10 +66,10 @@ void SpindleLaser::init() { #endif #if ENABLED(SPINDLE_LASER_USE_PWM) SET_PWM(SPINDLE_LASER_PWM_PIN); - set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed + hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed #endif #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY) - set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); + hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY); #endif #if ENABLED(AIR_EVACUATION) @@ -90,10 +90,10 @@ void SpindleLaser::init() { * @param ocr Power value */ void SpindleLaser::_set_ocr(const uint8_t ocr) { - #if NEEDS_HARDWARE_PWM && SPINDLE_LASER_FREQUENCY - set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); + #if BOTH(NEEDS_HARDWARE_PWM, HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY + hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); #endif - set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); + hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); } void SpindleLaser::set_ocr(const uint8_t ocr) { diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 95d60ae486748..0415c9c8bb1ca 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -103,7 +103,7 @@ class SpindleLaser { static void init(); #if ENABLED(MARLIN_DEV_MODE) - static inline void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } + static inline void refresh_frequency() { hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } #endif // Modifying this function should update everywhere diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 77c0ccc49b0f8..807681831723d 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -126,10 +126,10 @@ void GcodeSuite::M42() { extDigitalWrite(pin, pin_status); #ifdef ARDUINO_ARCH_STM32 - // A simple I/O will be set to 0 by set_pwm_duty() + // A simple I/O will be set to 0 by hal.set_pwm_duty() if (pin_status <= 1 && !PWM_PIN(pin)) return; #endif - set_pwm_duty(pin, pin_status); + hal.set_pwm_duty(pin, pin_status); } #endif // DIRECT_PIN_CONTROL diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index 204455e65ec60..2dd1de00013b4 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -38,7 +38,7 @@ #include "../sd/cardreader.h" #include "../MarlinCore.h" // for kill -extern void dump_delay_accuracy_check(); +void dump_delay_accuracy_check(); /** * Dn: G-code for development and testing @@ -54,7 +54,7 @@ void GcodeSuite::D(const int16_t dcode) { for (;;) { /* loop forever (watchdog reset) */ } case 0: - HAL_reboot(); + hal.reboot(); break; case 10: @@ -74,7 +74,7 @@ void GcodeSuite::D(const int16_t dcode) { settings.reset(); settings.save(); #endif - HAL_reboot(); + hal.reboot(); } break; case 2: { // D2 Read / Write SRAM @@ -189,12 +189,12 @@ void GcodeSuite::D(const int16_t dcode) { SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")"); thermalManager.disable_all_heaters(); delay(1000); // Allow time to print - DISABLE_ISRS(); + hal.isr_off(); // Use a low-level delay that does not rely on interrupts to function // Do not spin forever, to avoid thermal risks if heaters are enabled and // watchdog does not work. for (int i = 10000; i--;) DELAY_US(1000UL); - ENABLE_ISRS(); + hal.isr_on(); SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset."); } break; diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index c8ac48f7cff53..6ee58f769bde3 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3850,3 +3850,10 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #undef _TEST_PWM #undef _LINEAR_AXES_STR #undef _LOGICAL_AXES_STR + +// JTAG support in the HAL +#if ENABLED(DISABLE_DEBUG) && !defined(JTAGSWD_DISABLE) + #error "DISABLE_DEBUG is not supported for the selected MCU/Board." +#elif ENABLED(DISABLE_JTAG) && !defined(JTAG_DISABLE) + #error "DISABLE_JTAG is not supported for the selected MCU/Board." +#endif diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 59c74148adef3..61db2db9209b0 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -282,9 +282,9 @@ void MarlinUI::init_lcd() { #if PIN_EXISTS(LCD_RESET) // Perform a clean hardware reset with needed delays OUT_WRITE(LCD_RESET_PIN, LOW); - _delay_ms(5); + hal.delay_ms(5); WRITE(LCD_RESET_PIN, HIGH); - _delay_ms(5); + hal.delay_ms(5); u8g.begin(); #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index d1a9ba7077fda..64a65bb6863be 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -2149,7 +2149,7 @@ void RebootPrinter() { thermalManager.disable_all_heaters(); planner.finish_and_disable(); DWIN_RebootScreen(); - HAL_reboot(); + hal.reboot(); } void Goto_InfoMenu(){ diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 7a2cefdd4cea3..df6a857803508 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -1345,7 +1345,7 @@ void Endstops::update() { ES_REPORT_CHANGE(K_MAX); #endif SERIAL_ECHOLNPGM("\n"); - set_pwm_duty(pin_t(LED_PIN), local_LED_status); + hal.set_pwm_duty(pin_t(LED_PIN), local_LED_status); local_LED_status ^= 255; old_live_state_local = live_state_local; } diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 45ccdd1702ef8..752834c6ab996 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1264,7 +1264,7 @@ void Planner::recalculate() { #if ENABLED(FAN_SOFT_PWM) #define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F); #else - #define _FAN_SET(F) set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); + #define _FAN_SET(F) hal.set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); #endif #define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0) @@ -1400,8 +1400,8 @@ void Planner::check_axes_activity() { TERN_(AUTOTEMP, autotemp_task()); #if ENABLED(BARICUDA) - TERN_(HAS_HEATER_1, set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); - TERN_(HAS_HEATER_2, set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); + TERN_(HAS_HEATER_1, hal.set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); + TERN_(HAS_HEATER_2, hal.set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); #endif } diff --git a/Marlin/src/module/servo.cpp b/Marlin/src/module/servo.cpp index 231efe84e1f2c..96d5ba9da837e 100644 --- a/Marlin/src/module/servo.cpp +++ b/Marlin/src/module/servo.cpp @@ -30,7 +30,7 @@ #include "servo.h" -HAL_SERVO_LIB servo[NUM_SERVOS]; +hal_servo_t servo[NUM_SERVOS]; #if ENABLED(EDITABLE_SERVO_ANGLES) uint16_t servo_angles[NUM_SERVOS][2]; diff --git a/Marlin/src/module/servo.h b/Marlin/src/module/servo.h index 73dbbdddb7297..cd55a317a2751 100644 --- a/Marlin/src/module/servo.h +++ b/Marlin/src/module/servo.h @@ -112,5 +112,5 @@ #define MOVE_SERVO(I, P) servo[I].move(P) #define DETACH_SERVO(I) servo[I].detach() -extern HAL_SERVO_LIB servo[NUM_SERVOS]; +extern hal_servo_t servo[NUM_SERVOS]; void servo_init(); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index c100051f98087..0f47d66791c4d 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1474,7 +1474,7 @@ void Stepper::isr() { #ifndef __AVR__ // Disable interrupts, to avoid ISR preemption while we reprogram the period // (AVR enters the ISR with global interrupts disabled, so no need to do it here) - DISABLE_ISRS(); + hal.isr_off(); #endif // Program timer compare for the maximum period, so it does NOT @@ -1492,7 +1492,7 @@ void Stepper::isr() { hal_timer_t min_ticks; do { // Enable ISRs to reduce USART processing latency - ENABLE_ISRS(); + hal.isr_on(); if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses @@ -1576,7 +1576,7 @@ void Stepper::isr() { * is less than the current count due to something preempting between the * read and the write of the new period value). */ - DISABLE_ISRS(); + hal.isr_off(); /** * Get the current tick value + margin @@ -1611,7 +1611,7 @@ void Stepper::isr() { HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(next_isr_ticks)); // Don't forget to finally reenable interrupts - ENABLE_ISRS(); + hal.isr_on(); } #if MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE @@ -3261,7 +3261,7 @@ void Stepper::report_positions() { #elif HAS_MOTOR_CURRENT_PWM - #define _WRITE_CURRENT_PWM(P) set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) + #define _WRITE_CURRENT_PWM(P) hal.set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) switch (driver) { case 0: #if PIN_EXISTS(MOTOR_CURRENT_PWM_X) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index dccdc55034fd0..1960dc5d9b526 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -326,7 +326,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0) #endif #if ENABLED(FAST_PWM_FAN) - #define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY) + #define SET_FAST_PWM_FREQ(P) hal.set_pwm_frequency(pin_t(P), FAST_PWM_FAN_FREQUENCY) #else #define SET_FAST_PWM_FREQ(P) NOOP #endif @@ -813,7 +813,7 @@ volatile bool Temperature::raw_temps_ready = false; } // Run HAL idle tasks - TERN_(HAL_IDLETASK, HAL_idletask()); + hal.idletask(); // Run UI update TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update()); @@ -912,7 +912,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #define _UPDATE_AUTO_FAN(P,D,A) do{ \ if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \ - set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ + hal.set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ else \ WRITE(P##_AUTO_FAN_PIN, D); \ }while(0) @@ -2326,73 +2326,73 @@ void Temperature::init() { TERN_(HAS_MAXTC_SW_SPI, max_tc_spi.init()); - HAL_adc_init(); + hal.adc_init(); #if HAS_TEMP_ADC_0 - HAL_ANALOG_SELECT(TEMP_0_PIN); + hal.adc_enable(TEMP_0_PIN); #endif #if HAS_TEMP_ADC_1 - HAL_ANALOG_SELECT(TEMP_1_PIN); + hal.adc_enable(TEMP_1_PIN); #endif #if HAS_TEMP_ADC_2 - HAL_ANALOG_SELECT(TEMP_2_PIN); + hal.adc_enable(TEMP_2_PIN); #endif #if HAS_TEMP_ADC_3 - HAL_ANALOG_SELECT(TEMP_3_PIN); + hal.adc_enable(TEMP_3_PIN); #endif #if HAS_TEMP_ADC_4 - HAL_ANALOG_SELECT(TEMP_4_PIN); + hal.adc_enable(TEMP_4_PIN); #endif #if HAS_TEMP_ADC_5 - HAL_ANALOG_SELECT(TEMP_5_PIN); + hal.adc_enable(TEMP_5_PIN); #endif #if HAS_TEMP_ADC_6 - HAL_ANALOG_SELECT(TEMP_6_PIN); + hal.adc_enable(TEMP_6_PIN); #endif #if HAS_TEMP_ADC_7 - HAL_ANALOG_SELECT(TEMP_7_PIN); + hal.adc_enable(TEMP_7_PIN); #endif #if HAS_JOY_ADC_X - HAL_ANALOG_SELECT(JOY_X_PIN); + hal.adc_enable(JOY_X_PIN); #endif #if HAS_JOY_ADC_Y - HAL_ANALOG_SELECT(JOY_Y_PIN); + hal.adc_enable(JOY_Y_PIN); #endif #if HAS_JOY_ADC_Z - HAL_ANALOG_SELECT(JOY_Z_PIN); + hal.adc_enable(JOY_Z_PIN); #endif #if HAS_JOY_ADC_EN SET_INPUT_PULLUP(JOY_EN_PIN); #endif #if HAS_TEMP_ADC_BED - HAL_ANALOG_SELECT(TEMP_BED_PIN); + hal.adc_enable(TEMP_BED_PIN); #endif #if HAS_TEMP_ADC_CHAMBER - HAL_ANALOG_SELECT(TEMP_CHAMBER_PIN); + hal.adc_enable(TEMP_CHAMBER_PIN); #endif #if HAS_TEMP_ADC_COOLER - HAL_ANALOG_SELECT(TEMP_COOLER_PIN); + hal.adc_enable(TEMP_COOLER_PIN); #endif #if HAS_TEMP_ADC_PROBE - HAL_ANALOG_SELECT(TEMP_PROBE_PIN); + hal.adc_enable(TEMP_PROBE_PIN); #endif #if HAS_TEMP_ADC_BOARD - HAL_ANALOG_SELECT(TEMP_BOARD_PIN); + hal.adc_enable(TEMP_BOARD_PIN); #endif #if HAS_TEMP_ADC_REDUNDANT - HAL_ANALOG_SELECT(TEMP_REDUNDANT_PIN); + hal.adc_enable(TEMP_REDUNDANT_PIN); #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - HAL_ANALOG_SELECT(FILWIDTH_PIN); + hal.adc_enable(FILWIDTH_PIN); #endif #if HAS_ADC_BUTTONS - HAL_ANALOG_SELECT(ADC_KEYPAD_PIN); + hal.adc_enable(ADC_KEYPAD_PIN); #endif #if ENABLED(POWER_MONITOR_CURRENT) - HAL_ANALOG_SELECT(POWER_MONITOR_CURRENT_PIN); + hal.adc_enable(POWER_MONITOR_CURRENT_PIN); #endif #if ENABLED(POWER_MONITOR_VOLTAGE) - HAL_ANALOG_SELECT(POWER_MONITOR_VOLTAGE_PIN); + hal.adc_enable(POWER_MONITOR_VOLTAGE_PIN); #endif HAL_timer_start(MF_TIMER_TEMP, TEMP_TIMER_FREQUENCY); @@ -3333,8 +3333,8 @@ void Temperature::isr() { * This gives each ADC 0.9765ms to charge up. */ #define ACCUMULATE_ADC(obj) do{ \ - if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; \ - else obj.sample(HAL_READ_ADC()); \ + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; \ + else obj.sample(hal.adc_value()); \ }while(0) ADCSensorState next_sensor_state = adc_sensor_state < SensorsReady ? (ADCSensorState)(int(adc_sensor_state) + 1) : StartSampling; @@ -3366,115 +3366,115 @@ void Temperature::isr() { break; #if HAS_TEMP_ADC_0 - case PrepareTemp_0: HAL_START_ADC(TEMP_0_PIN); break; + case PrepareTemp_0: hal.adc_start(TEMP_0_PIN); break; case MeasureTemp_0: ACCUMULATE_ADC(temp_hotend[0]); break; #endif #if HAS_TEMP_ADC_BED - case PrepareTemp_BED: HAL_START_ADC(TEMP_BED_PIN); break; + case PrepareTemp_BED: hal.adc_start(TEMP_BED_PIN); break; case MeasureTemp_BED: ACCUMULATE_ADC(temp_bed); break; #endif #if HAS_TEMP_ADC_CHAMBER - case PrepareTemp_CHAMBER: HAL_START_ADC(TEMP_CHAMBER_PIN); break; + case PrepareTemp_CHAMBER: hal.adc_start(TEMP_CHAMBER_PIN); break; case MeasureTemp_CHAMBER: ACCUMULATE_ADC(temp_chamber); break; #endif #if HAS_TEMP_ADC_COOLER - case PrepareTemp_COOLER: HAL_START_ADC(TEMP_COOLER_PIN); break; + case PrepareTemp_COOLER: hal.adc_start(TEMP_COOLER_PIN); break; case MeasureTemp_COOLER: ACCUMULATE_ADC(temp_cooler); break; #endif #if HAS_TEMP_ADC_PROBE - case PrepareTemp_PROBE: HAL_START_ADC(TEMP_PROBE_PIN); break; + case PrepareTemp_PROBE: hal.adc_start(TEMP_PROBE_PIN); break; case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break; #endif #if HAS_TEMP_ADC_BOARD - case PrepareTemp_BOARD: HAL_START_ADC(TEMP_BOARD_PIN); break; + case PrepareTemp_BOARD: hal.adc_start(TEMP_BOARD_PIN); break; case MeasureTemp_BOARD: ACCUMULATE_ADC(temp_board); break; #endif #if HAS_TEMP_ADC_REDUNDANT - case PrepareTemp_REDUNDANT: HAL_START_ADC(TEMP_REDUNDANT_PIN); break; + case PrepareTemp_REDUNDANT: hal.adc_start(TEMP_REDUNDANT_PIN); break; case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break; #endif #if HAS_TEMP_ADC_1 - case PrepareTemp_1: HAL_START_ADC(TEMP_1_PIN); break; + case PrepareTemp_1: hal.adc_start(TEMP_1_PIN); break; case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break; #endif #if HAS_TEMP_ADC_2 - case PrepareTemp_2: HAL_START_ADC(TEMP_2_PIN); break; + case PrepareTemp_2: hal.adc_start(TEMP_2_PIN); break; case MeasureTemp_2: ACCUMULATE_ADC(temp_hotend[2]); break; #endif #if HAS_TEMP_ADC_3 - case PrepareTemp_3: HAL_START_ADC(TEMP_3_PIN); break; + case PrepareTemp_3: hal.adc_start(TEMP_3_PIN); break; case MeasureTemp_3: ACCUMULATE_ADC(temp_hotend[3]); break; #endif #if HAS_TEMP_ADC_4 - case PrepareTemp_4: HAL_START_ADC(TEMP_4_PIN); break; + case PrepareTemp_4: hal.adc_start(TEMP_4_PIN); break; case MeasureTemp_4: ACCUMULATE_ADC(temp_hotend[4]); break; #endif #if HAS_TEMP_ADC_5 - case PrepareTemp_5: HAL_START_ADC(TEMP_5_PIN); break; + case PrepareTemp_5: hal.adc_start(TEMP_5_PIN); break; case MeasureTemp_5: ACCUMULATE_ADC(temp_hotend[5]); break; #endif #if HAS_TEMP_ADC_6 - case PrepareTemp_6: HAL_START_ADC(TEMP_6_PIN); break; + case PrepareTemp_6: hal.adc_start(TEMP_6_PIN); break; case MeasureTemp_6: ACCUMULATE_ADC(temp_hotend[6]); break; #endif #if HAS_TEMP_ADC_7 - case PrepareTemp_7: HAL_START_ADC(TEMP_7_PIN); break; + case PrepareTemp_7: hal.adc_start(TEMP_7_PIN); break; case MeasureTemp_7: ACCUMULATE_ADC(temp_hotend[7]); break; #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - case Prepare_FILWIDTH: HAL_START_ADC(FILWIDTH_PIN); break; + case Prepare_FILWIDTH: hal.adc_start(FILWIDTH_PIN); break; case Measure_FILWIDTH: - if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state - else filwidth.accumulate(HAL_READ_ADC()); + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state + else filwidth.accumulate(hal.adc_value()); break; #endif #if ENABLED(POWER_MONITOR_CURRENT) case Prepare_POWER_MONITOR_CURRENT: - HAL_START_ADC(POWER_MONITOR_CURRENT_PIN); + hal.adc_start(POWER_MONITOR_CURRENT_PIN); break; case Measure_POWER_MONITOR_CURRENT: - if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state - else power_monitor.add_current_sample(HAL_READ_ADC()); + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state + else power_monitor.add_current_sample(hal.adc_value()); break; #endif #if ENABLED(POWER_MONITOR_VOLTAGE) case Prepare_POWER_MONITOR_VOLTAGE: - HAL_START_ADC(POWER_MONITOR_VOLTAGE_PIN); + hal.adc_start(POWER_MONITOR_VOLTAGE_PIN); break; case Measure_POWER_MONITOR_VOLTAGE: - if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state - else power_monitor.add_voltage_sample(HAL_READ_ADC()); + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state + else power_monitor.add_voltage_sample(hal.adc_value()); break; #endif #if HAS_JOY_ADC_X - case PrepareJoy_X: HAL_START_ADC(JOY_X_PIN); break; + case PrepareJoy_X: hal.adc_start(JOY_X_PIN); break; case MeasureJoy_X: ACCUMULATE_ADC(joystick.x); break; #endif #if HAS_JOY_ADC_Y - case PrepareJoy_Y: HAL_START_ADC(JOY_Y_PIN); break; + case PrepareJoy_Y: hal.adc_start(JOY_Y_PIN); break; case MeasureJoy_Y: ACCUMULATE_ADC(joystick.y); break; #endif #if HAS_JOY_ADC_Z - case PrepareJoy_Z: HAL_START_ADC(JOY_Z_PIN); break; + case PrepareJoy_Z: hal.adc_start(JOY_Z_PIN); break; case MeasureJoy_Z: ACCUMULATE_ADC(joystick.z); break; #endif @@ -3482,12 +3482,12 @@ void Temperature::isr() { #ifndef ADC_BUTTON_DEBOUNCE_DELAY #define ADC_BUTTON_DEBOUNCE_DELAY 16 #endif - case Prepare_ADC_KEY: HAL_START_ADC(ADC_KEYPAD_PIN); break; + case Prepare_ADC_KEY: hal.adc_start(ADC_KEYPAD_PIN); break; case Measure_ADC_KEY: - if (!HAL_ADC_READY()) + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // redo this state else if (ADCKey_count < ADC_BUTTON_DEBOUNCE_DELAY) { - raw_ADCKey_value = HAL_READ_ADC(); + raw_ADCKey_value = hal.adc_value(); if (raw_ADCKey_value <= 900UL * HAL_ADC_RANGE / 1024UL) { NOMORE(current_ADCKey_raw, raw_ADCKey_value); ADCKey_count++; diff --git a/ini/native.ini b/ini/native.ini index fe5fe3a5d05ad..eba34afc83948 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -34,14 +34,14 @@ src_filter = ${common.default_src_filter} + [simulator_common] platform = native framework = -build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/include -IMarlin/src/HAL/NATIVE_SIM/u8g +build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/u8g src_build_flags = -Wall -Wno-expansion-to-defined -Wcast-align release_flags = -g0 -O3 -flto debug_build_flags = -fstack-protector-strong -g -g3 -ggdb lib_compat_mode = off src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} - MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/master.zip + MarlinSimUI=https://github.com/thinkyhead/MarlinSimUI/archive/updated_marlin_hal_2093.zip Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip extra_scripts = ${common.extra_scripts} From a941cd33e290ed7268ac963388eb0cb28485cd72 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 24 Dec 2021 23:47:52 -0600 Subject: [PATCH 186/273] =?UTF-8?q?=F0=9F=94=A8=20Configurable=20firmware?= =?UTF-8?q?=20bin=20filename?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Configuration.h > FIRMWARE_BIN --- buildroot/share/PlatformIO/scripts/marlin.py | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py index b8a6283cedf1b..4830232d0bc50 100644 --- a/buildroot/share/PlatformIO/scripts/marlin.py +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -48,6 +48,15 @@ def encrypt_mks(source, target, env, new_name): key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] + # If FIRMWARE_BIN is defined by config, override all + import re + patt = re.compile("^\\s*#define\\s+FIRMWARE_BIN\\s+\"?(.+)\"?") + with open(join("Marlin", "Configuration.h")) as f: + for line in f: + m = patt.search(line) + if m != None: + new_name = m.group(1) + fwpath = target[0].path fwfile = open(fwpath, "rb") enfile = open(target[0].dir.path + "/" + new_name, "wb") From c74161c011abfeb7004631f63642566f37a845db Mon Sep 17 00:00:00 2001 From: fflosi <34758322+fflosi@users.noreply.github.com> Date: Sat, 25 Dec 2021 05:57:07 -0300 Subject: [PATCH 187/273] =?UTF-8?q?=E2=9C=A8=20Per-axis=20TMC=20hold=20mul?= =?UTF-8?q?tiplier=20(#23345)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 19 + Marlin/src/inc/Conditionals_post.h | 505 +++++++++++++++---------- Marlin/src/module/stepper/trinamic.cpp | 28 +- 3 files changed, 336 insertions(+), 216 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 3eb836ec65620..2410d8b9033f2 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2690,6 +2690,7 @@ #define X_RSENSE 0.11 #define X_CHAIN_POS -1 // -1..0: Not chained. 1: MCU MOSI connected. 2: Next in chain, ... //#define X_INTERPOLATE true // Enable to override 'INTERPOLATE' for the X axis + //#define X_HOLD_MULTIPLIER 0.5 // Enable to override 'HOLD_MULTIPLIER' for the X axis #endif #if AXIS_IS_TMC(X2) @@ -2699,6 +2700,7 @@ #define X2_RSENSE 0.11 #define X2_CHAIN_POS -1 //#define X2_INTERPOLATE true + //#define X2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Y) @@ -2708,6 +2710,7 @@ #define Y_RSENSE 0.11 #define Y_CHAIN_POS -1 //#define Y_INTERPOLATE true + //#define Y_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Y2) @@ -2717,6 +2720,7 @@ #define Y2_RSENSE 0.11 #define Y2_CHAIN_POS -1 //#define Y2_INTERPOLATE true + //#define Y2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z) @@ -2726,6 +2730,7 @@ #define Z_RSENSE 0.11 #define Z_CHAIN_POS -1 //#define Z_INTERPOLATE true + //#define Z_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z2) @@ -2735,6 +2740,7 @@ #define Z2_RSENSE 0.11 #define Z2_CHAIN_POS -1 //#define Z2_INTERPOLATE true + //#define Z2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z3) @@ -2744,6 +2750,7 @@ #define Z3_RSENSE 0.11 #define Z3_CHAIN_POS -1 //#define Z3_INTERPOLATE true + //#define Z3_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z4) @@ -2753,6 +2760,7 @@ #define Z4_RSENSE 0.11 #define Z4_CHAIN_POS -1 //#define Z4_INTERPOLATE true + //#define Z4_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(I) @@ -2762,6 +2770,7 @@ #define I_RSENSE 0.11 #define I_CHAIN_POS -1 //#define I_INTERPOLATE true + //#define I_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(J) @@ -2771,6 +2780,7 @@ #define J_RSENSE 0.11 #define J_CHAIN_POS -1 //#define J_INTERPOLATE true + //#define J_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(K) @@ -2780,6 +2790,7 @@ #define K_RSENSE 0.11 #define K_CHAIN_POS -1 //#define K_INTERPOLATE true + //#define K_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E0) @@ -2788,6 +2799,7 @@ #define E0_RSENSE 0.11 #define E0_CHAIN_POS -1 //#define E0_INTERPOLATE true + //#define E0_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E1) @@ -2796,6 +2808,7 @@ #define E1_RSENSE 0.11 #define E1_CHAIN_POS -1 //#define E1_INTERPOLATE true + //#define E1_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E2) @@ -2804,6 +2817,7 @@ #define E2_RSENSE 0.11 #define E2_CHAIN_POS -1 //#define E2_INTERPOLATE true + //#define E2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E3) @@ -2812,6 +2826,7 @@ #define E3_RSENSE 0.11 #define E3_CHAIN_POS -1 //#define E3_INTERPOLATE true + //#define E3_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E4) @@ -2820,6 +2835,7 @@ #define E4_RSENSE 0.11 #define E4_CHAIN_POS -1 //#define E4_INTERPOLATE true + //#define E4_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E5) @@ -2828,6 +2844,7 @@ #define E5_RSENSE 0.11 #define E5_CHAIN_POS -1 //#define E5_INTERPOLATE true + //#define E5_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E6) @@ -2836,6 +2853,7 @@ #define E6_RSENSE 0.11 #define E6_CHAIN_POS -1 //#define E6_INTERPOLATE true + //#define E6_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E7) @@ -2844,6 +2862,7 @@ #define E7_RSENSE 0.11 #define E7_CHAIN_POS -1 //#define E7_INTERPOLATE true + //#define E7_HOLD_MULTIPLIER 0.5 #endif /** diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 95c8f7737b311..a5c9d20eda9ea 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1861,231 +1861,332 @@ #undef Z3_STALL_SENSITIVITY #undef Z4_STALL_SENSITIVITY #endif - #if defined(X_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X) - #define X_SENSORLESS 1 - #endif - #if defined(X2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X2) - #define X2_SENSORLESS 1 - #endif - #if defined(Y_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y) - #define Y_SENSORLESS 1 - #endif - #if defined(Y2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y2) - #define Y2_SENSORLESS 1 - #endif - #if defined(Z_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z) - #define Z_SENSORLESS 1 - #endif - #if defined(Z2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z2) - #define Z2_SENSORLESS 1 - #endif - #if defined(Z3_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z3) - #define Z3_SENSORLESS 1 - #endif - #if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4) - #define Z4_SENSORLESS 1 - #endif - #if defined(I_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(I) - #define I_SENSORLESS 1 - #endif - #if defined(J_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(J) - #define J_SENSORLESS 1 - #endif - #if defined(K_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(K) - #define K_SENSORLESS 1 - #endif - #if AXIS_HAS_STEALTHCHOP(X) - #define X_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - #define X2_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - #define Y_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - #define Y2_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - #define Z_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - #define Z2_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - #define Z3_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - #define Z4_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(I) - #define I_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(J) - #define J_HAS_STEALTHCHOP 1 - #endif - #if AXIS_HAS_STEALTHCHOP(K) - #define K_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 0 && AXIS_HAS_STEALTHCHOP(E0) - #define E0_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1) - #define E1_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2) - #define E2_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3) - #define E3_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4) - #define E4_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5) - #define E5_HAS_STEALTHCHOP 1 - #endif - #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6) - #define E6_HAS_STEALTHCHOP 1 + #if AXIS_IS_TMC(X) + #if defined(X_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X) + #define X_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(X) + #define X_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) + #define X_SPI_SENSORLESS X_SENSORLESS + #endif + #ifndef X_INTERPOLATE + #define X_INTERPOLATE INTERPOLATE + #endif + #ifndef X_HOLD_MULTIPLIER + #define X_HOLD_MULTIPLIER HOLD_MULTIPLIER + #endif + #ifndef X_SLAVE_ADDRESS + #define X_SLAVE_ADDRESS 0 + #endif #endif - #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7) - #define E7_HAS_STEALTHCHOP 1 + + #if AXIS_IS_TMC(X2) + #if defined(X2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X2) + #define X2_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(X2) + #define X2_HAS_STEALTHCHOP 1 + #endif + #ifndef X2_INTERPOLATE + #define X2_INTERPOLATE X_INTERPOLATE + #endif + #ifndef X2_HOLD_MULTIPLIER + #define X2_HOLD_MULTIPLIER X_HOLD_MULTIPLIER + #endif + #ifndef X2_SLAVE_ADDRESS + #define X2_SLAVE_ADDRESS 0 + #endif #endif - #if ENABLED(SPI_ENDSTOPS) - #define X_SPI_SENSORLESS X_SENSORLESS - #if HAS_Y_AXIS + #if AXIS_IS_TMC(Y) + #if defined(Y_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y) + #define Y_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Y) + #define Y_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) #define Y_SPI_SENSORLESS Y_SENSORLESS #endif - #if HAS_Z_AXIS - #define Z_SPI_SENSORLESS Z_SENSORLESS + #ifndef Y_INTERPOLATE + #define Y_INTERPOLATE INTERPOLATE #endif - #if LINEAR_AXES >= 4 - #define I_SPI_SENSORLESS I_SENSORLESS + #ifndef Y_HOLD_MULTIPLIER + #define Y_HOLD_MULTIPLIER HOLD_MULTIPLIER #endif - #if LINEAR_AXES >= 5 - #define J_SPI_SENSORLESS J_SENSORLESS + #ifndef Y_SLAVE_ADDRESS + #define Y_SLAVE_ADDRESS 0 #endif - #if LINEAR_AXES >= 6 - #define K_SPI_SENSORLESS K_SENSORLESS + #if ENABLED(Y_DUAL_STEPPER_DRIVERS) + #if defined(Y2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y2) + #define Y2_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Y2) + #define Y2_HAS_STEALTHCHOP 1 + #endif + #ifndef Y2_INTERPOLATE + #define Y2_INTERPOLATE Y_INTERPOLATE + #endif + #ifndef Y2_HOLD_MULTIPLIER + #define Y2_HOLD_MULTIPLIER Y_HOLD_MULTIPLIER + #endif + #ifndef Y2_SLAVE_ADDRESS + #define Y2_SLAVE_ADDRESS 0 + #endif #endif #endif - #ifndef X_INTERPOLATE - #define X_INTERPOLATE INTERPOLATE - #endif - #ifndef X2_INTERPOLATE - #define X2_INTERPOLATE INTERPOLATE - #endif - #ifndef Y_INTERPOLATE - #define Y_INTERPOLATE INTERPOLATE - #endif - #ifndef Y2_INTERPOLATE - #define Y2_INTERPOLATE INTERPOLATE - #endif - #ifndef Z_INTERPOLATE - #define Z_INTERPOLATE INTERPOLATE - #endif - #ifndef Z2_INTERPOLATE - #define Z2_INTERPOLATE INTERPOLATE - #endif - #ifndef Z3_INTERPOLATE - #define Z3_INTERPOLATE INTERPOLATE - #endif - #ifndef Z4_INTERPOLATE - #define Z4_INTERPOLATE INTERPOLATE - #endif - #if LINEAR_AXES >= 4 && !defined(I_INTERPOLATE) - #define I_INTERPOLATE INTERPOLATE - #endif - #if LINEAR_AXES >= 5 && !defined(J_INTERPOLATE) - #define J_INTERPOLATE INTERPOLATE - #endif - #if LINEAR_AXES >= 6 && !defined(K_INTERPOLATE) - #define K_INTERPOLATE INTERPOLATE - #endif - #ifndef E0_INTERPOLATE - #define E0_INTERPOLATE INTERPOLATE - #endif - #ifndef E1_INTERPOLATE - #define E1_INTERPOLATE INTERPOLATE - #endif - #ifndef E2_INTERPOLATE - #define E2_INTERPOLATE INTERPOLATE - #endif - #ifndef E3_INTERPOLATE - #define E3_INTERPOLATE INTERPOLATE - #endif - #ifndef E4_INTERPOLATE - #define E4_INTERPOLATE INTERPOLATE - #endif - #ifndef E5_INTERPOLATE - #define E5_INTERPOLATE INTERPOLATE - #endif - #ifndef E6_INTERPOLATE - #define E6_INTERPOLATE INTERPOLATE - #endif - #ifndef E7_INTERPOLATE - #define E7_INTERPOLATE INTERPOLATE - #endif - #ifndef X_SLAVE_ADDRESS - #define X_SLAVE_ADDRESS 0 - #endif - #ifndef Y_SLAVE_ADDRESS - #define Y_SLAVE_ADDRESS 0 - #endif - #ifndef Z_SLAVE_ADDRESS - #define Z_SLAVE_ADDRESS 0 - #endif - #ifndef I_SLAVE_ADDRESS - #define I_SLAVE_ADDRESS 0 - #endif - #ifndef J_SLAVE_ADDRESS - #define J_SLAVE_ADDRESS 0 - #endif - #ifndef K_SLAVE_ADDRESS - #define K_SLAVE_ADDRESS 0 - #endif - #ifndef X2_SLAVE_ADDRESS - #define X2_SLAVE_ADDRESS 0 - #endif - #ifndef Y2_SLAVE_ADDRESS - #define Y2_SLAVE_ADDRESS 0 + + #if AXIS_IS_TMC(Z) + #if defined(Z_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z) + #define Z_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z) + #define Z_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) + #define Z_SPI_SENSORLESS Z_SENSORLESS + #endif + #ifndef Z_INTERPOLATE + #define Z_INTERPOLATE INTERPOLATE + #endif + #ifndef Z_HOLD_MULTIPLIER + #define Z_HOLD_MULTIPLIER HOLD_MULTIPLIER + #endif + #ifndef Z_SLAVE_ADDRESS + #define Z_SLAVE_ADDRESS 0 + #endif + #if NUM_Z_STEPPER_DRIVERS >= 2 + #if defined(Z2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z2) + #define Z2_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z2) + #define Z2_HAS_STEALTHCHOP 1 + #endif + #ifndef Z2_INTERPOLATE + #define Z2_INTERPOLATE Z_INTERPOLATE + #endif + #ifndef Z2_HOLD_MULTIPLIER + #define Z2_HOLD_MULTIPLIER Z_HOLD_MULTIPLIER + #endif + #ifndef Z2_SLAVE_ADDRESS + #define Z2_SLAVE_ADDRESS 0 + #endif + #endif + #if NUM_Z_STEPPER_DRIVERS >= 3 + #if defined(Z3_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z3) + #define Z3_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z3) + #define Z3_HAS_STEALTHCHOP 1 + #endif + #ifndef Z3_INTERPOLATE + #define Z3_INTERPOLATE Z_INTERPOLATE + #endif + #ifndef Z3_HOLD_MULTIPLIER + #define Z3_HOLD_MULTIPLIER Z_HOLD_MULTIPLIER + #endif + #ifndef Z3_SLAVE_ADDRESS + #define Z3_SLAVE_ADDRESS 0 + #endif + #endif + #if NUM_Z_STEPPER_DRIVERS >= 4 + #if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4) + #define Z4_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z4) + #define Z4_HAS_STEALTHCHOP 1 + #endif + #ifndef Z4_INTERPOLATE + #define Z4_INTERPOLATE Z_INTERPOLATE + #endif + #ifndef Z4_HOLD_MULTIPLIER + #define Z4_HOLD_MULTIPLIER Z_HOLD_MULTIPLIER + #endif + #ifndef Z4_SLAVE_ADDRESS + #define Z4_SLAVE_ADDRESS 0 + #endif + #endif #endif - #ifndef Z2_SLAVE_ADDRESS - #define Z2_SLAVE_ADDRESS 0 + + #if AXIS_IS_TMC(I) + #if defined(I_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(I) + #define I_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(I) + #define I_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) + #define I_SPI_SENSORLESS I_SENSORLESS + #endif + #ifndef I_INTERPOLATE + #define I_INTERPOLATE INTERPOLATE + #endif + #ifndef I_HOLD_MULTIPLIER + #define I_HOLD_MULTIPLIER HOLD_MULTIPLIER + #endif + #ifndef I_SLAVE_ADDRESS + #define I_SLAVE_ADDRESS 0 + #endif #endif - #ifndef Z3_SLAVE_ADDRESS - #define Z3_SLAVE_ADDRESS 0 + + #if AXIS_IS_TMC(J) + #if defined(J_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(J) + #define J_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(J) + #define J_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) + #define J_SPI_SENSORLESS J_SENSORLESS + #endif + #ifndef J_INTERPOLATE + #define J_INTERPOLATE INTERPOLATE + #endif + #ifndef J_HOLD_MULTIPLIER + #define J_HOLD_MULTIPLIER HOLD_MULTIPLIER + #endif + #ifndef J_SLAVE_ADDRESS + #define J_SLAVE_ADDRESS 0 + #endif #endif - #ifndef Z4_SLAVE_ADDRESS - #define Z4_SLAVE_ADDRESS 0 + + #if AXIS_IS_TMC(K) + #if defined(K_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(K) + #define K_SENSORLESS 1 + #endif + #if AXIS_HAS_STEALTHCHOP(K) + #define K_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) + #define K_SPI_SENSORLESS K_SENSORLESS + #endif + #ifndef K_INTERPOLATE + #define K_INTERPOLATE INTERPOLATE + #endif + #ifndef K_HOLD_MULTIPLIER + #define K_HOLD_MULTIPLIER HOLD_MULTIPLIER + #endif + #ifndef K_SLAVE_ADDRESS + #define K_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E0_SLAVE_ADDRESS - #define E0_SLAVE_ADDRESS 0 + + #if AXIS_IS_TMC(E0) + #if AXIS_HAS_STEALTHCHOP(E0) + #define E0_HAS_STEALTHCHOP 1 + #endif + #ifndef E0_INTERPOLATE + #define E0_INTERPOLATE INTERPOLATE + #endif + #ifndef E0_HOLD_MULTIPLIER + #define E0_HOLD_MULTIPLIER HOLD_MULTIPLIER + #endif + #ifndef E0_SLAVE_ADDRESS + #define E0_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E1_SLAVE_ADDRESS - #define E1_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E1) + #if AXIS_HAS_STEALTHCHOP(E1) + #define E1_HAS_STEALTHCHOP 1 + #endif + #ifndef E1_INTERPOLATE + #define E1_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E1_HOLD_MULTIPLIER + #define E1_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E1_SLAVE_ADDRESS + #define E1_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E2_SLAVE_ADDRESS - #define E2_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E2) + #if AXIS_HAS_STEALTHCHOP(E2) + #define E2_HAS_STEALTHCHOP 1 + #endif + #ifndef E2_INTERPOLATE + #define E2_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E2_HOLD_MULTIPLIER + #define E2_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E2_SLAVE_ADDRESS + #define E2_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E3_SLAVE_ADDRESS - #define E3_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E3) + #if AXIS_HAS_STEALTHCHOP(E3) + #define E3_HAS_STEALTHCHOP 1 + #endif + #ifndef E3_INTERPOLATE + #define E3_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E3_HOLD_MULTIPLIER + #define E3_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E3_SLAVE_ADDRESS + #define E3_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E4_SLAVE_ADDRESS - #define E4_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E4) + #if AXIS_HAS_STEALTHCHOP(E4) + #define E4_HAS_STEALTHCHOP 1 + #endif + #ifndef E4_INTERPOLATE + #define E4_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E4_HOLD_MULTIPLIER + #define E4_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E4_SLAVE_ADDRESS + #define E4_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E5_SLAVE_ADDRESS - #define E5_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E5) + #if AXIS_HAS_STEALTHCHOP(E5) + #define E5_HAS_STEALTHCHOP 1 + #endif + #ifndef E5_INTERPOLATE + #define E5_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E5_HOLD_MULTIPLIER + #define E5_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E5_SLAVE_ADDRESS + #define E5_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E6_SLAVE_ADDRESS - #define E6_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E6) + #if AXIS_HAS_STEALTHCHOP(E6) + #define E6_HAS_STEALTHCHOP 1 + #endif + #ifndef E6_INTERPOLATE + #define E6_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E6_HOLD_MULTIPLIER + #define E6_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E6_SLAVE_ADDRESS + #define E6_SLAVE_ADDRESS 0 + #endif #endif - #ifndef E7_SLAVE_ADDRESS - #define E7_SLAVE_ADDRESS 0 + #if AXIS_IS_TMC(E7) + #if AXIS_HAS_STEALTHCHOP(E7) + #define E7_HAS_STEALTHCHOP 1 + #endif + #ifndef E7_INTERPOLATE + #define E7_INTERPOLATE E0_INTERPOLATE + #endif + #ifndef E7_HOLD_MULTIPLIER + #define E7_HOLD_MULTIPLIER E0_HOLD_MULTIPLIER + #endif + #ifndef E7_SLAVE_ADDRESS + #define E7_SLAVE_ADDRESS 0 + #endif #endif -#endif +#endif // HAS_TRINAMIC_CONFIG #if ANY_AXIS_HAS(HW_SERIAL) #define HAS_TMC_HW_SERIAL 1 diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index e8ecbf1c762ae..7baa2108f06ac 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -38,7 +38,7 @@ enum StealthIndex : uint8_t { LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z, STEALTH_AXIS_I, STEALTH_AXIS_J, STEALTH_AXIS_K) }; -#define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE) +#define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE, ST##_HOLD_MULTIPLIER) // IC = TMC model number // ST = Stepper object letter @@ -200,7 +200,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2130) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { st.begin(); CHOPCONF_t chopconf{0}; @@ -212,7 +212,7 @@ enum StealthIndex : uint8_t { TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); - st.rms_current(mA, HOLD_MULTIPLIER); + st.rms_current(mA, hold_multiplier); st.microsteps(microsteps); st.iholddelay(10); st.TPOWERDOWN(128); // ~2s until driver lowers to hold current @@ -235,7 +235,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2160) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { st.begin(); CHOPCONF_t chopconf{0}; @@ -247,7 +247,7 @@ enum StealthIndex : uint8_t { TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); - st.rms_current(mA, HOLD_MULTIPLIER); + st.rms_current(mA, hold_multiplier); st.microsteps(microsteps); st.iholddelay(10); st.TPOWERDOWN(128); // ~2s until driver lowers to hold current @@ -604,7 +604,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2208) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { TMC2208_n::GCONF_t gconf{0}; gconf.pdn_disable = true; // Use UART gconf.mstep_reg_select = true; // Select microsteps with UART @@ -622,7 +622,7 @@ enum StealthIndex : uint8_t { TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); - st.rms_current(mA, HOLD_MULTIPLIER); + st.rms_current(mA, hold_multiplier); st.microsteps(microsteps); st.iholddelay(10); st.TPOWERDOWN(128); // ~2s until driver lowers to hold current @@ -646,7 +646,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2209) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { TMC2208_n::GCONF_t gconf{0}; gconf.pdn_disable = true; // Use UART gconf.mstep_reg_select = true; // Select microsteps with UART @@ -664,7 +664,7 @@ enum StealthIndex : uint8_t { TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); - st.rms_current(mA, HOLD_MULTIPLIER); + st.rms_current(mA, hold_multiplier); st.microsteps(microsteps); st.iholddelay(10); st.TPOWERDOWN(128); // ~2s until driver lowers to hold current @@ -688,7 +688,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2660) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t, const bool, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t, const bool, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { st.begin(); TMC2660_n::CHOPCONF_t chopconf{0}; @@ -710,7 +710,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC5130) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { st.begin(); CHOPCONF_t chopconf{0}; @@ -722,7 +722,7 @@ enum StealthIndex : uint8_t { TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); - st.rms_current(mA, HOLD_MULTIPLIER); + st.rms_current(mA, hold_multiplier); st.microsteps(microsteps); st.iholddelay(10); st.TPOWERDOWN(128); // ~2s until driver lowers to hold current @@ -745,7 +745,7 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC5160) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { + void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { st.begin(); CHOPCONF_t chopconf{0}; @@ -757,7 +757,7 @@ enum StealthIndex : uint8_t { TERN_(SQUARE_WAVE_STEPPING, chopconf.dedge = true); st.CHOPCONF(chopconf.sr); - st.rms_current(mA, HOLD_MULTIPLIER); + st.rms_current(mA, hold_multiplier); st.microsteps(microsteps); st.iholddelay(10); st.TPOWERDOWN(128); // ~2s until driver lowers to hold current From fca6d12093e0cadc0c95a0e4cabfd560e6b628a1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Dec 2021 03:27:45 -0600 Subject: [PATCH 188/273] =?UTF-8?q?=F0=9F=94=A7=20Move=20MOTHERBOARD=20clo?= =?UTF-8?q?ser=20to=20top?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index c425746bb5d1c..f0fc4dd7d608f 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -94,6 +94,11 @@ // @section machine +// Choose the name from boards.h that matches your setup +#ifndef MOTHERBOARD + #define MOTHERBOARD BOARD_RAMPS_14_EFB +#endif + /** * Select the serial port on the board to use for communication with the host. * This allows the connection of wireless adapters (for instance) to non-default port pins. @@ -137,11 +142,6 @@ // Enable the Bluetooth serial interface on AT90USB devices //#define BLUETOOTH -// Choose the name from boards.h that matches your setup -#ifndef MOTHERBOARD - #define MOTHERBOARD BOARD_RAMPS_14_EFB -#endif - // Name displayed in the LCD "Ready" message and Info menu //#define CUSTOM_MACHINE_NAME "3D Printer" From bdb071688e7a2e1eb900c26c59c20bca847ccfdc Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 26 Dec 2021 01:09:46 +0000 Subject: [PATCH 189/273] [cron] Bump distribution date (2021-12-26) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 596e910a1f61b..fca302288f67c 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 "2021-12-25" +//#define STRING_DISTRIBUTION_DATE "2021-12-26" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b43547ef53c11..d2b7a93775656 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 "2021-12-25" + #define STRING_DISTRIBUTION_DATE "2021-12-26" #endif /** From 4f0932e5c1647b00efff22a2a5f30a1fdd57cc19 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Dec 2021 20:00:48 -0600 Subject: [PATCH 190/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20`freeMemory`=20end?= =?UTF-8?q?less=20loop?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #23295 --- Marlin/src/HAL/AVR/HAL.h | 2 +- Marlin/src/HAL/DUE/HAL.h | 2 +- Marlin/src/HAL/LINUX/HAL.h | 2 +- Marlin/src/HAL/LPC1768/HAL.h | 2 +- Marlin/src/HAL/NATIVE_SIM/HAL.h | 2 +- Marlin/src/HAL/SAMD51/HAL.h | 2 +- Marlin/src/HAL/STM32/HAL.h | 2 +- Marlin/src/HAL/STM32F1/HAL.h | 2 +- Marlin/src/HAL/TEENSY31_32/HAL.h | 2 +- Marlin/src/HAL/TEENSY35_36/HAL.h | 2 +- Marlin/src/HAL/TEENSY40_41/HAL.h | 2 +- 11 files changed, 11 insertions(+), 11 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 9babe2d60352b..682374b4ac845 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -205,7 +205,7 @@ class MarlinHAL { static inline void clear_reset_source() { MCUSR = 0; } // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 0dd123acdd511..5d1d2cf236d70 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -196,7 +196,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 0bd8635c90454..c1b7a54997066 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -126,7 +126,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index ba0729590f5b9..f1cdbe6f078de 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -219,7 +219,7 @@ class MarlinHAL { static void clear_reset_source(); // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index bfbdaf211ff30..0798bdde393de 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -228,7 +228,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index 144bf9c08dfa1..9fcd73e9b64bf 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -176,7 +176,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index d71ccd796b2f2..c23ddf69bdaa8 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -226,7 +226,7 @@ class MarlinHAL { static void clear_reset_source(); // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 517c8f2cb808a..8fb4c9299ff59 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -270,7 +270,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index fdf914b1b02e2..a5f67a50f0aa1 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -155,7 +155,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 5506599cdf036..8ca76dc6368b3 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -160,7 +160,7 @@ class MarlinHAL { static inline void clear_reset_source() {} // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 4a0b5688d77cf..10263ecb394ae 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -182,7 +182,7 @@ class MarlinHAL { static void clear_reset_source(); // Free SRAM - static inline int freeMemory() { return freeMemory(); } + static inline int freeMemory() { return ::freeMemory(); } // // ADC Methods From d7af6199362f35db72579e16843239087689e145 Mon Sep 17 00:00:00 2001 From: kaidegit <60053077+kaidegit@users.noreply.github.com> Date: Sun, 26 Dec 2021 10:12:20 +0800 Subject: [PATCH 191/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20open=20for=20bin?= =?UTF-8?q?=20rename=20(#23351)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/PlatformIO/scripts/marlin.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py index 4830232d0bc50..2114a05fb388c 100644 --- a/buildroot/share/PlatformIO/scripts/marlin.py +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -51,7 +51,7 @@ def encrypt_mks(source, target, env, new_name): # If FIRMWARE_BIN is defined by config, override all import re patt = re.compile("^\\s*#define\\s+FIRMWARE_BIN\\s+\"?(.+)\"?") - with open(join("Marlin", "Configuration.h")) as f: + with open(join("Marlin", "Configuration.h"), encoding="utf-8") as f: for line in f: m = patt.search(line) if m != None: From 57315f02cbacea6a90c56349dc7e571e53692740 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Dec 2021 21:25:47 -0600 Subject: [PATCH 192/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20missing=20ADC=20me?= =?UTF-8?q?thod?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/DUE/HAL.h | 2 -- Marlin/src/HAL/ESP32/HAL.h | 3 --- Marlin/src/HAL/LINUX/HAL.h | 1 - Marlin/src/HAL/LPC1768/HAL.h | 2 -- Marlin/src/HAL/NATIVE_SIM/HAL.h | 1 - Marlin/src/HAL/SAMD51/HAL.h | 2 -- Marlin/src/HAL/STM32/HAL.h | 4 +--- Marlin/src/HAL/STM32F1/HAL.h | 2 -- Marlin/src/HAL/TEENSY31_32/HAL.h | 2 -- Marlin/src/HAL/TEENSY35_36/HAL.h | 2 -- Marlin/src/HAL/TEENSY40_41/HAL.h | 2 -- 11 files changed, 1 insertion(+), 22 deletions(-) diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 5d1d2cf236d70..96a59fcf3cbee 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -131,8 +131,6 @@ typedef Servo hal_servo_t; #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ANALOG_SELECT(ch) - // // Pin Mapping for M42, M43, M226 // diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 361c9032317df..138346b950a7d 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -85,9 +85,6 @@ void noTone(const pin_t _pin); void analogWrite(pin_t pin, int value); -// ADC -#define HAL_ANALOG_SELECT(pin) - // // Pin Mapping for M42, M43, M226 // diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index c1b7a54997066..a2a9692cbdcdf 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -82,7 +82,6 @@ extern MSerialT usb_serial; // ADC #define HAL_ADC_VREF 5.0 #define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(ch) hal.adc_enable(ch) // ------------------------ // Class Utilities diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index f1cdbe6f078de..e1ade3d9a72cb 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -133,8 +133,6 @@ extern DefaultSerial1 USBSerial; #define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t #define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL -#define HAL_ANALOG_SELECT(pin) hal.adc_enable(pin) - // // Pin Mapping for M42, M43, M226 // diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 0798bdde393de..50da5af2eb926 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -117,7 +117,6 @@ extern MSerialT serial_stream_3; #define HAL_ADC_VREF 5.0 #define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(ch) hal.adc_enable(ch) /* ---------------- Delay in cycles */ diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index 9fcd73e9b64bf..e9d4a70c3f193 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -106,8 +106,6 @@ typedef Servo hal_servo_t; // ADC // -#define HAL_ANALOG_SELECT(pin) - //#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values. #define HAL_ADC_VREF 3.3 #define HAL_ADC_RESOLUTION 10 // ... 12 diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index c23ddf69bdaa8..f9bf1c938aa50 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -142,8 +142,6 @@ typedef libServo hal_servo_t; // ADC // ------------------------ -#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) - #ifdef ADC_RESOLUTION #define HAL_ADC_RESOLUTION ADC_RESOLUTION #else @@ -240,7 +238,7 @@ class MarlinHAL { } // Called by Temperature::init for each sensor at startup - static void adc_enable(const pin_t pin); + static inline void adc_enable(const pin_t pin) { pinMode(pin, INPUT); } // Begin ADC sampling on the given channel static void adc_start(const pin_t pin) { adc_result = analogRead(pin); } diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 8fb4c9299ff59..bdbf4a1885ae7 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -188,8 +188,6 @@ extern uint16_t HAL_adc_result; // ADC // ------------------------ -#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG); - #ifdef ADC_RESOLUTION #define HAL_ADC_RESOLUTION ADC_RESOLUTION #else diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index a5f67a50f0aa1..0661b55f53a9d 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -105,8 +105,6 @@ uint32_t __get_PRIMASK(void); // CMSIS #define HAL_ADC_VREF 3.3 #define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(pin) - // // Pin Mapping for M42, M43, M226 // diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 8ca76dc6368b3..1cc465c4bbf2c 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -110,8 +110,6 @@ typedef int8_t pin_t; #define HAL_ADC_VREF 3.3 #define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(pin) - // // Pin Mapping for M42, M43, M226 // diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 10263ecb394ae..7bad143179098 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -129,8 +129,6 @@ typedef int8_t pin_t; #define HAL_ADC_RESOLUTION 10 #define HAL_ADC_FILTERED // turn off ADC oversampling -#define HAL_ANALOG_SELECT(pin) - // // Pin Mapping for M42, M43, M226 // From a47f559db15ad550930f0d49d352e73852ff900d Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Sun, 26 Dec 2021 10:36:09 +0700 Subject: [PATCH 193/273] =?UTF-8?q?=F0=9F=90=9B=20HAL=20refactor=20followu?= =?UTF-8?q?p=20(#23354)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/SAMD51/HAL.h | 2 +- Marlin/src/HAL/STM32/HAL_SPI.cpp | 2 +- Marlin/src/HAL/STM32F1/HAL.h | 2 +- Marlin/src/HAL/TEENSY31_32/HAL.h | 2 +- Marlin/src/HAL/TEENSY40_41/HAL.h | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index e9d4a70c3f193..a88ed9ba7988b 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -186,7 +186,7 @@ class MarlinHAL { static void adc_init(); // Called by Temperature::init for each sensor at startup - static void adc_enable(const uint8_t ch); + static inline void adc_enable(const uint8_t ch) {} // Begin ADC sampling on the given channel static void adc_start(const pin_t pin); diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 7737245de85b1..40d320d5e8220 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -104,7 +104,7 @@ static SPISettings spiConfig; uint8_t spiRec() { hal.isr_off(); // No interrupts during byte receive const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF); - hal.isr_off(); // Enable interrupts + hal.isr_on(); // Enable interrupts return data; } diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index bdbf4a1885ae7..9b973c3ea4fe3 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -280,7 +280,7 @@ class MarlinHAL { static void adc_init(); // Called by Temperature::init for each sensor at startup - static void adc_enable(const pin_t pin); + static inline void adc_enable(const pin_t pin) { pinMode(pin, INPUT_ANALOG); } // Begin ADC sampling on the given channel static void adc_start(const pin_t pin); diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 0661b55f53a9d..14f463708bce5 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -163,7 +163,7 @@ class MarlinHAL { static void adc_init(); // Called by Temperature::init for each sensor at startup - static void adc_enable(const pin_t ch); + static inline void adc_enable(const pin_t ch) {} // Begin ADC sampling on the given channel static void adc_start(const pin_t ch); diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 7bad143179098..b7a8070281634 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -192,7 +192,7 @@ class MarlinHAL { static void adc_init(); // Called by Temperature::init for each sensor at startup - static void adc_enable(const pin_t pin); + static inline void adc_enable(const pin_t pin) {} // Begin ADC sampling on the given channel static void adc_start(const pin_t pin); From 555c749fe2be922eaf3bd78a79ae3b89b012662f Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Sat, 25 Dec 2021 19:41:01 -0800 Subject: [PATCH 194/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20MKS=20Robin=20E3?= =?UTF-8?q?=20NeoPixel=20pin=20default=20(#23350)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) 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 c30bb0ac9e99f..e02d1db7863d5 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -64,11 +64,6 @@ #define Z_MIN_PROBE_PIN PB1 #endif -// LED driving pin -#ifndef NEOPIXEL_PIN - #define NEOPIXEL_PIN PA2 -#endif - // // Steppers // @@ -245,6 +240,11 @@ #endif #endif +// LED driving pin +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PA2 +#endif + // // SD Card // From 00e6e90648012ca0b954139f867a9a0201319209 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Dec 2021 22:10:47 -0600 Subject: [PATCH 195/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20adc=5Fstart=20for?= =?UTF-8?q?=20AVR,=20native?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #23295 --- Marlin/src/HAL/AVR/HAL.h | 10 ++++++---- Marlin/src/HAL/LINUX/HAL.h | 2 +- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 682374b4ac845..3dade7fa15585 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -229,12 +229,14 @@ class MarlinHAL { } // Begin ADC sampling on the given channel - static inline void adc_start(const pin_t ch) { + static inline void adc_start(const uint8_t ch) { #ifdef MUX5 - if (ch > 7) { ADCSRB = _BV(MUX5); return; } + ADCSRB = ch > 7 ? _BV(MUX5) : 0; + #else + ADCSRB = 0; #endif - ADCSRB = 0; - ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC); + ADMUX = _BV(REFS0) | (ch & 0x07); + SBI(ADCSRA, ADSC); } // Is the ADC ready for reading? diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index a2a9692cbdcdf..104c47ec61236 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -140,7 +140,7 @@ class MarlinHAL { static inline void adc_enable(const uint8_t) {} // Begin ADC sampling on the given channel - static inline void adc_start(const pin_t ch) { active_ch = ch; } + static inline void adc_start(const uint8_t ch) { active_ch = ch; } // Is the ADC ready for reading? static inline bool adc_ready() { return true; } From 6a8b9274a31d11c396ce1bc44b3a0b872a4606dc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Dec 2021 23:15:17 -0600 Subject: [PATCH 196/273] =?UTF-8?q?=E2=8F=AA=EF=B8=8F=20Refactor=20still?= =?UTF-8?q?=20needs=20work?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Reverting #23295 --- Marlin/src/HAL/AVR/HAL.cpp | 14 +- Marlin/src/HAL/AVR/HAL.h | 172 ++++++++------------- Marlin/src/HAL/AVR/MarlinSerial.cpp | 4 +- Marlin/src/HAL/AVR/fast_pwm.cpp | 11 +- Marlin/src/HAL/AVR/timers.h | 4 +- Marlin/src/HAL/DUE/HAL.cpp | 45 ++++-- Marlin/src/HAL/DUE/HAL.h | 134 ++++++---------- Marlin/src/HAL/DUE/MarlinSerial.cpp | 4 +- Marlin/src/HAL/DUE/timers.h | 2 +- Marlin/src/HAL/ESP32/HAL.cpp | 35 ++--- Marlin/src/HAL/ESP32/HAL.h | 145 +++++++----------- Marlin/src/HAL/ESP32/timers.h | 4 +- Marlin/src/HAL/LINUX/HAL.cpp | 39 +++-- Marlin/src/HAL/LINUX/HAL.h | 144 ++++++------------ Marlin/src/HAL/LINUX/arduino.cpp | 4 +- Marlin/src/HAL/LINUX/include/Arduino.h | 5 +- Marlin/src/HAL/LINUX/timers.h | 4 +- Marlin/src/HAL/LPC1768/HAL.cpp | 42 ++--- Marlin/src/HAL/LPC1768/HAL.h | 160 +++++++------------ Marlin/src/HAL/LPC1768/Servo.h | 3 +- Marlin/src/HAL/LPC1768/fast_pwm.cpp | 14 +- Marlin/src/HAL/LPC1768/main.cpp | 6 +- Marlin/src/HAL/LPC1768/timers.h | 2 +- Marlin/src/HAL/NATIVE_SIM/HAL.h | 172 ++++++++------------- Marlin/src/HAL/NATIVE_SIM/timers.h | 4 +- Marlin/src/HAL/SAMD51/HAL.cpp | 26 ++-- Marlin/src/HAL/SAMD51/HAL.h | 127 ++++++---------- Marlin/src/HAL/STM32/HAL.cpp | 28 ++-- Marlin/src/HAL/STM32/HAL.h | 177 ++++++++++----------- Marlin/src/HAL/STM32/HAL_SPI.cpp | 8 +- Marlin/src/HAL/STM32/eeprom_flash.cpp | 8 +- Marlin/src/HAL/STM32/fast_pwm.cpp | 4 +- Marlin/src/HAL/STM32/pinsDebug.h | 6 +- Marlin/src/HAL/STM32/timers.h | 4 +- Marlin/src/HAL/STM32F1/HAL.cpp | 190 ++++++++++++----------- Marlin/src/HAL/STM32F1/HAL.h | 184 ++++++++++------------ Marlin/src/HAL/STM32F1/Servo.h | 3 +- Marlin/src/HAL/STM32F1/fast_pwm.cpp | 8 +- Marlin/src/HAL/STM32F1/timers.h | 2 +- Marlin/src/HAL/TEENSY31_32/HAL.cpp | 79 +++++----- Marlin/src/HAL/TEENSY31_32/HAL.h | 131 +++++----------- Marlin/src/HAL/TEENSY31_32/timers.h | 2 +- Marlin/src/HAL/TEENSY35_36/HAL.cpp | 110 +++++++------- Marlin/src/HAL/TEENSY35_36/HAL.h | 133 +++++----------- Marlin/src/HAL/TEENSY35_36/timers.h | 2 +- Marlin/src/HAL/TEENSY40_41/HAL.cpp | 194 ++++++++++++------------ Marlin/src/HAL/TEENSY40_41/HAL.h | 148 ++++++------------ Marlin/src/HAL/TEENSY40_41/timers.h | 2 +- Marlin/src/HAL/shared/HAL.cpp | 36 ----- Marlin/src/HAL/shared/HAL_spi_L6470.cpp | 8 +- Marlin/src/MarlinCore.cpp | 48 +++--- Marlin/src/feature/caselight.cpp | 2 +- Marlin/src/feature/controllerfan.cpp | 2 +- Marlin/src/feature/e_parser.h | 4 +- Marlin/src/feature/leds/leds.cpp | 2 +- Marlin/src/feature/spindle_laser.cpp | 10 +- Marlin/src/feature/spindle_laser.h | 2 +- Marlin/src/gcode/control/M42.cpp | 4 +- Marlin/src/gcode/gcode_d.cpp | 10 +- Marlin/src/inc/SanityCheck.h | 7 - Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 4 +- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 2 +- Marlin/src/module/endstops.cpp | 2 +- Marlin/src/module/planner.cpp | 6 +- Marlin/src/module/servo.cpp | 2 +- Marlin/src/module/servo.h | 2 +- Marlin/src/module/stepper.cpp | 10 +- Marlin/src/module/temperature.cpp | 112 +++++++------- ini/native.ini | 4 +- 69 files changed, 1279 insertions(+), 1749 deletions(-) delete mode 100644 Marlin/src/HAL/shared/HAL.cpp diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index 2b6d2bdbcf074..d7bf2a6f6fbb8 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -36,7 +36,7 @@ // ------------------------ // Don't initialize/override variable (which would happen in .init4) -uint8_t MarlinHAL::reset_reason __attribute__((section(".noinit"))); +uint8_t reset_reason __attribute__((section(".noinit"))); // ------------------------ // Public functions @@ -45,22 +45,22 @@ uint8_t MarlinHAL::reset_reason __attribute__((section(".noinit"))); __attribute__((naked)) // Don't output function pro- and epilogue __attribute__((used)) // Output the function, even if "not used" __attribute__((section(".init3"))) // Put in an early user definable section -void save_reset_reason() { +void HAL_save_reset_reason() { #if ENABLED(OPTIBOOT_RESET_REASON) __asm__ __volatile__( A("STS %0, r2") - : "=m"(hal.reset_reason) + : "=m"(reset_reason) ); #else - hal.reset_reason = MCUSR; + reset_reason = MCUSR; #endif // Clear within 16ms since WDRF bit enables a 16ms watchdog timer -> Boot loop - hal.clear_reset_source(); + MCUSR = 0; wdt_disable(); } -void MarlinHAL::init() { +void HAL_init() { // Init Servo Pins #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) #if HAS_SERVO_0 @@ -77,7 +77,7 @@ void MarlinHAL::init() { #endif } -void MarlinHAL::reboot() { +void HAL_reboot() { #if ENABLED(USE_WATCHDOG) while (1) { /* run out the watchdog */ } #else diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 3dade7fa15585..2217f239d64ea 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -74,8 +74,9 @@ #define CRITICAL_SECTION_START() unsigned char _sreg = SREG; cli() #define CRITICAL_SECTION_END() SREG = _sreg #endif - -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment +#define ISRS_ENABLED() TEST(SREG, SREG_I) +#define ENABLE_ISRS() sei() +#define DISABLE_ISRS() cli() // ------------------------ // Types @@ -83,16 +84,16 @@ typedef int8_t pin_t; -// Use shared/servos.cpp #define SHARED_SERVOS HAS_SERVOS - -class Servo; -typedef Servo hal_servo_t; +#define HAL_SERVO_LIB Servo // ------------------------ -// Serial ports +// Public Variables // ------------------------ +extern uint8_t reset_reason; + +// Serial ports #ifdef USBCON #include "../../core/serial_hook.h" typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; @@ -141,31 +142,20 @@ typedef Servo hal_servo_t; #endif #endif -// -// ADC -// -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 +// ------------------------ +// Public functions +// ------------------------ -// -// Pin Mapping for M42, M43, M226 -// -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +void HAL_init(); -#define HAL_SENSITIVE_PINS 0, 1, +//void cli(); -#ifdef __AVR_AT90USB1286__ - #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) -#endif +//void _delay_ms(const int delay); -// AVR compatibility -#define strtof strtod +inline void HAL_clear_reset_source() { } +inline uint8_t HAL_get_reset_source() { return reset_reason; } -// ------------------------ -// Class Utilities -// ------------------------ +void HAL_reboot(); #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -176,91 +166,63 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: +// ADC +#ifdef DIDR2 + #define HAL_ANALOG_SELECT(ind) do{ if (ind < 8) SBI(DIDR0, ind); else SBI(DIDR2, ind & 0x07); }while(0) +#else + #define HAL_ANALOG_SELECT(ind) SBI(DIDR0, ind); +#endif - // Earliest possible init, before setup() - MarlinHAL() {} +inline void HAL_adc_init() { + ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07; + DIDR0 = 0; + #ifdef DIDR2 + DIDR2 = 0; + #endif +} - static void init(); // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 +#define SET_ADMUX_ADCSRA(ch) ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC) +#ifdef MUX5 + #define HAL_START_ADC(ch) if (ch > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(ch) +#else + #define HAL_START_ADC(ch) ADCSRB = 0; SET_ADMUX_ADCSRA(ch) +#endif - static inline bool isr_state() { return TEST(SREG, SREG_I); } - static inline void isr_on() { sei(); } - static inline void isr_off() { cli(); } +#define HAL_ADC_VREF 5.0 +#define HAL_ADC_RESOLUTION 10 +#define HAL_READ_ADC() ADC +#define HAL_ADC_READY() !TEST(ADCSRA, ADSC) - static inline void delay_ms(const int ms) { _delay_ms(ms); } +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) - // Tasks, called from idle() - static inline void idletask() {} +#define HAL_SENSITIVE_PINS 0, 1, - // Reset - static uint8_t reset_reason; - static inline uint8_t get_reset_source() { return reset_reason; } - static inline void clear_reset_source() { MCUSR = 0; } +#ifdef __AVR_AT90USB1286__ + #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) +#endif - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } +// AVR compatibility +#define strtof strtod - // - // ADC Methods - // +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment - // Called by Temperature::init once at startup - static inline void adc_init() { - ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07; - DIDR0 = 0; - #ifdef DIDR2 - DIDR2 = 0; - #endif - } +/** + * set_pwm_frequency + * Sets the frequency of the timer corresponding to the provided pin + * as close as possible to the provided desired frequency. Internally + * calculates the required waveform generation mode, prescaler and + * resolution values required and sets the timer registers accordingly. + * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B) + * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings) + */ +void set_pwm_frequency(const pin_t pin, int f_desired); - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const uint8_t ch) { - #ifdef DIDR2 - if (ch > 7) { SBI(DIDR2, ch & 0x07); return; } - #endif - SBI(DIDR0, ch); - } - - // Begin ADC sampling on the given channel - static inline void adc_start(const uint8_t ch) { - #ifdef MUX5 - ADCSRB = ch > 7 ? _BV(MUX5) : 0; - #else - ADCSRB = 0; - #endif - ADMUX = _BV(REFS0) | (ch & 0x07); - SBI(ADCSRA, ADSC); - } - - // Is the ADC ready for reading? - static inline bool adc_ready() { return !TEST(ADCSRA, ADSC); } - - // The current value of the ADC register - static inline __typeof__(ADC) adc_value() { return ADC; } - - /** - * Set the PWM duty cycle for the pin to the given value. - * Optionally invert the duty cycle [default = false] - * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); - - /** - * Set the frequency of the timer for the given pin as close as - * possible to the provided desired frequency. Internally calculate - * the required waveform generation mode, prescaler, and resolution - * values and set timer registers accordingly. - * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B) - * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings) - */ - static void set_pwm_frequency(const pin_t pin, int f_desired); -}; - -extern MarlinHAL hal; +/** + * set_pwm_duty + * Set the PWM duty cycle of the provided pin to the provided value + * Optionally allows inverting the duty cycle [default = false] + * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] + */ +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index 986462437c8f5..cd8bf5e6903b8 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -486,7 +486,7 @@ void MarlinSerial::write(const uint8_t c) { const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); // If global interrupts are disabled (as the result of being called from an ISR)... - if (!hal.isr_state()) { + if (!ISRS_ENABLED()) { // Make room by polling if it is possible to transmit, and do so! while (i == tx_buffer.tail) { @@ -534,7 +534,7 @@ void MarlinSerial::flushTX() { if (!_written) return; // If global interrupts are disabled (as the result of being called from an ISR)... - if (!hal.isr_state()) { + if (!ISRS_ENABLED()) { // Wait until everything was transmitted - We must do polling, as interrupts are disabled while (tx_buffer.head != tx_buffer.tail || !B_TXC) { diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index 0053b44c3c7b4..804e5fad30709 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -35,9 +35,10 @@ struct Timer { }; /** - * Get the timer information and register for a pin. - * Return a Timer struct containing this information. - * Used by set_pwm_frequency, set_pwm_duty + * get_pwm_timer + * Get the timer information and register of the provided pin. + * Return a Timer struct containing this information. + * Used by set_pwm_frequency, set_pwm_duty */ Timer get_pwm_timer(const pin_t pin) { uint8_t q = 0; @@ -149,7 +150,7 @@ Timer get_pwm_timer(const pin_t pin) { return timer; } -void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { +void set_pwm_frequency(const pin_t pin, int f_desired) { Timer timer = get_pwm_timer(pin); if (timer.n == 0) return; // Don't proceed if protected timer or not recognized uint16_t size; @@ -229,7 +230,7 @@ void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { #endif // NEEDS_HARDWARE_PWM -void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { #if NEEDS_HARDWARE_PWM // If v is 0 or v_size (max), digitalWrite to LOW or HIGH. diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index e1fcbf52d6d8e..36b04eae0d1ff 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -109,8 +109,8 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) { * (otherwise, characters will be lost due to UART overflow). * Then: Stepper, Endstops, Temperature, and -finally- all others. */ -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) /* 18 cycles maximum latency */ #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp index 20b711b1b05eb..a3985652e71dd 100644 --- a/Marlin/src/HAL/DUE/HAL.cpp +++ b/Marlin/src/HAL/DUE/HAL.cpp @@ -34,7 +34,7 @@ // Public Variables // ------------------------ -uint16_t MarlinHAL::adc_result; +uint16_t HAL_adc_result; // ------------------------ // Public functions @@ -42,7 +42,8 @@ uint16_t MarlinHAL::adc_result; TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -void MarlinHAL::init() { +// HAL initialization task +void HAL_init() { // Initialize the USB stack #if ENABLED(SDSUPPORT) OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up @@ -51,17 +52,21 @@ void MarlinHAL::init() { TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler } -void MarlinHAL::init_board() { - #ifdef BOARD_INIT - BOARD_INIT(); - #endif +// HAL idle task +void HAL_idletask() { + // Perform USB stack housekeeping + usb_task_idle(); } -void MarlinHAL::idletask() { - usb_task_idle(); // Perform USB stack housekeeping -} +// Disable interrupts +void cli() { noInterrupts(); } + +// Enable interrupts +void sei() { interrupts(); } + +void HAL_clear_reset_source() { } -uint8_t MarlinHAL::get_reset_source() { +uint8_t HAL_get_reset_source() { switch ((RSTC->RSTC_SR >> 8) & 0x07) { case 0: return RST_POWER_ON; case 1: return RST_BACKUP; @@ -72,7 +77,12 @@ uint8_t MarlinHAL::get_reset_source() { } } -void MarlinHAL::reboot() { rstc_start_software_reset(RSTC); } +void HAL_reboot() { rstc_start_software_reset(RSTC); } + +void _delay_ms(const int delay_ms) { + // Todo: port for Due? + delay(delay_ms); +} extern "C" { extern unsigned int _ebss; // end of bss section @@ -84,6 +94,19 @@ int freeMemory() { return (int)&free_memory - (heap_end ?: (int)&_ebss); } +// ------------------------ +// ADC +// ------------------------ + +void HAL_adc_start_conversion(const uint8_t ch) { + HAL_adc_result = analogRead(ch); +} + +uint16_t HAL_adc_get_result() { + // nop + return HAL_adc_result; +} + // Forward the default serial ports #if USING_HW_SERIAL0 DefaultSerial1 MSerial0(false, Serial); diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 96a59fcf3cbee..96ab5d9808ac1 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -38,10 +38,6 @@ #include "../../core/serial_hook.h" -// ------------------------ -// Serial ports -// ------------------------ - typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; @@ -101,38 +97,60 @@ extern DefaultSerial4 MSerial3; #include "MarlinSerial.h" #include "MarlinSerialUSB.h" -// ------------------------ -// Types -// ------------------------ +// On AVR this is in math.h? +#define square(x) ((x)*(x)) typedef int8_t pin_t; -// Use shared/servos.cpp #define SHARED_SERVOS HAS_SERVOS -class Servo; -typedef Servo hal_servo_t; +#define HAL_SERVO_LIB Servo // // Interrupts // -#define sei() noInterrupts() -#define cli() interrupts() +#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_PRIMASK()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() + +void cli(); // Disable interrupts +void sei(); // Enable interrupts + +void HAL_clear_reset_source(); // clear reset reason +uint8_t HAL_get_reset_source(); // get reset reason -#define CRITICAL_SECTION_START() const bool _irqon = hal.isr_state(); hal.isr_off() -#define CRITICAL_SECTION_END() if (_irqon) hal.isr_on() +void HAL_reboot(); // // ADC // -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 +extern uint16_t HAL_adc_result; // result of last ADC conversion #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif +#define HAL_ANALOG_SELECT(ch) + +inline void HAL_adc_init() {}//todo + +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) +#define HAL_READ_ADC() HAL_adc_result +#define HAL_ADC_READY() true + +void HAL_adc_start_conversion(const uint8_t ch); +uint16_t HAL_adc_get_result(); + // -// Pin Mapping for M42, M43, M226 +// PWM +// +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + +// +// Pin Map // #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin @@ -141,18 +159,27 @@ typedef Servo hal_servo_t; // // Tone // +void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// ------------------------ -// Class Utilities -// ------------------------ +// Enable hooks into idle and setup for HAL +#define HAL_IDLETASK 1 +void HAL_idletask(); +void HAL_init(); + +// +// Utility functions +// +void _delay_ms(const int delay); #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" #endif +int freeMemory(); + #pragma GCC diagnostic pop #ifdef __cplusplus @@ -162,70 +189,3 @@ char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s #ifdef __cplusplus } #endif - -// Return free RAM between end of heap (or end bss) and whatever is current -int freeMemory(); - -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static void init(); // Called early in setup() - static void init_board(); // Called less early in setup() - static void reboot(); // Software reset - - static inline bool isr_state() { return !__get_PRIMASK(); } - static inline void isr_on() { __enable_irq(); } - static inline void isr_off() { __disable_irq(); } - - static inline void delay_ms(const int ms) { delay(ms); } - - // Tasks, called from idle() - static void idletask(); - - // Reset - static uint8_t get_reset_source(); - static inline void clear_reset_source() {} - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // - - static uint16_t adc_result; - - // Called by Temperature::init once at startup - static inline void adc_init() {} - - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const int ch) {} - - // Begin ADC sampling on the given channel - static inline void adc_start(const uint8_t ch) { adc_result = analogRead(ch); } - - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } - - // The current value of the ADC register - static inline uint16_t adc_value() { return adc_result; } - - /** - * Set the PWM duty cycle for the pin to the given value. - * No inverting the duty cycle in this HAL. - * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL. - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } - -}; - -extern MarlinHAL hal; diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index 638f7a100722d..fe62ff5607d51 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -406,7 +406,7 @@ size_t MarlinSerial::write(const uint8_t c) { const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); // If global interrupts are disabled (as the result of being called from an ISR)... - if (!hal.isr_state()) { + if (!ISRS_ENABLED()) { // Make room by polling if it is possible to transmit, and do so! while (i == tx_buffer.tail) { @@ -454,7 +454,7 @@ void MarlinSerial::flushTX() { if (!_written) return; // If global interrupts are disabled (as the result of being called from an ISR)... - if (!hal.isr_state()) { + if (!ISRS_ENABLED()) { // Wait until everything was transmitted - We must do polling, as interrupts are disabled while (tx_buffer.head != tx_buffer.tail || !(HWUART->UART_SR & UART_SR_TXEMPTY)) { diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index bcfd07e268c57..e2932ff36f91b 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -125,4 +125,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR; } -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 604acae8dd5b9..810e386894ec4 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -52,7 +52,7 @@ // Externs // ------------------------ -portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED; +portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED; // ------------------------ // Local defines @@ -64,7 +64,7 @@ portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED; // Public Variables // ------------------------ -uint16_t MarlinHAL::adc_result; +uint16_t HAL_adc_result; // ------------------------ // Private Variables @@ -95,22 +95,20 @@ volatile int numPWMUsed = 0, #endif #if ENABLED(USE_ESP32_EXIO) - HardwareSerial YSerial2(2); void Write_EXIO(uint8_t IO, uint8_t v) { - if (hal.isr_state()) { - hal.isr_off(); + if (ISRS_ENABLED()) { + DISABLE_ISRS(); YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); - hal.isr_on(); + ENABLE_ISRS(); } else YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); } - #endif -void MarlinHAL::init_board() { +void HAL_init_board() { #if ENABLED(USE_ESP32_TASK_WDT) esp_task_wdt_init(10, true); #endif @@ -156,24 +154,27 @@ void MarlinHAL::init_board() { #endif } -void MarlinHAL::idletask() { +void HAL_idletask() { #if BOTH(WIFISUPPORT, OTASUPPORT) OTA_handle(); #endif TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask()); } -uint8_t MarlinHAL::get_reset_source() { return rtc_get_reset_reason(1); } +void HAL_clear_reset_source() { } + +uint8_t HAL_get_reset_source() { return rtc_get_reset_reason(1); } -void MarlinHAL::reboot() { ESP.restart(); } +void HAL_reboot() { ESP.restart(); } + +void _delay_ms(int delay_ms) { delay(delay_ms); } // return free memory between end of heap (or end bss) and whatever is current -int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); } +int freeMemory() { return ESP.getFreeHeap(); } // ------------------------ // ADC // ------------------------ - #define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL adc1_channel_t get_channel(int pin) { @@ -195,7 +196,7 @@ void adc1_set_attenuation(adc1_channel_t chan, adc_atten_t atten) { } } -void MarlinHAL::adc_init() { +void HAL_adc_init() { // Configure ADC adc1_config_width(ADC_WIDTH_12Bit); @@ -225,11 +226,11 @@ void MarlinHAL::adc_init() { } } -void MarlinHAL::adc_start(const pin_t pin) { - const adc1_channel_t chan = get_channel(pin); +void HAL_adc_start_conversion(const uint8_t adc_pin) { + const adc1_channel_t chan = get_channel(adc_pin); uint32_t mv; esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv); - adc_result = mv * 1023.0 / 3300.0; + HAL_adc_result = mv * 1023.0 / 3300.0; // Change the attenuation level based on the new reading adc_atten_t atten; diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 138346b950a7d..8473e3c4e4693 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -49,6 +49,8 @@ // Defines // ------------------------ +extern portMUX_TYPE spinlock; + #define MYSERIAL1 flushableSerial #if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) @@ -63,6 +65,9 @@ #define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock) #define CRITICAL_SECTION_END() portEXIT_CRITICAL(&spinlock) +#define ISRS_ENABLED() (spinlock.owner == portMUX_FREE_VAL) +#define ENABLE_ISRS() if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock) +#define DISABLE_ISRS() portENTER_CRITICAL(&spinlock) // ------------------------ // Types @@ -70,8 +75,14 @@ typedef int16_t pin_t; -class Servo; -typedef Servo hal_servo_t; +#define HAL_SERVO_LIB Servo + +// ------------------------ +// Public Variables +// ------------------------ + +/** result of last ADC conversion */ +extern uint16_t HAL_adc_result; // ------------------------ // Public functions @@ -80,18 +91,59 @@ typedef Servo hal_servo_t; // // Tone // +void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); +// clear reset reason +void HAL_clear_reset_source(); + +// reset reason +uint8_t HAL_get_reset_source(); + +void HAL_reboot(); + +void _delay_ms(int delay); + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +int freeMemory(); + +#pragma GCC diagnostic pop + void analogWrite(pin_t pin, int value); -// -// Pin Mapping for M42, M43, M226 -// +// ADC +#define HAL_ANALOG_SELECT(pin) + +void HAL_adc_init(); + +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_result +#define HAL_ADC_READY() true + +void HAL_adc_start_conversion(const uint8_t adc_pin); + +// PWM +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + +// Pin Map #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +// Enable hooks into idle and setup for HAL +#define HAL_IDLETASK 1 +#define BOARD_INIT() HAL_init_board(); +void HAL_idletask(); +inline void HAL_init() {} +void HAL_init_board(); + #if ENABLED(USE_ESP32_EXIO) void Write_EXIO(uint8_t IO, uint8_t v); #endif @@ -136,86 +188,3 @@ FORCE_INLINE static void DELAY_CYCLES(uint32_t x) { } } - -// ------------------------ -// Class Utilities -// ------------------------ - -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif - -int freeMemory(); - -#pragma GCC diagnostic pop - -void _delay_ms(const int ms); - -// ------------------------ -// MarlinHAL Class -// ------------------------ - -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static inline void init() {} // Called early in setup() - static void init_board(); // Called less early in setup() - static void reboot(); // Restart the firmware - - static portMUX_TYPE spinlock; - static inline bool isr_state() { return spinlock.owner == portMUX_FREE_VAL; } - static inline void isr_on() { if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock); } - static inline void isr_off() { portENTER_CRITICAL(&spinlock); } - - static inline void delay_ms(const int ms) { _delay_ms(ms); } - - // Tasks, called from idle() - static void idletask(); - - // Reset - static uint8_t get_reset_source(); - static inline void clear_reset_source() {} - - // Free SRAM - static int freeMemory(); - - // - // ADC Methods - // - - static uint16_t adc_result; - - // Called by Temperature::init once at startup - static void adc_init(); - - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t pin) {} - - // Begin ADC sampling on the given channel - static void adc_start(const pin_t pin); - - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } - - // The current value of the ADC register - static inline uint16_t adc_value() { return adc_result; } - - /** - * Set the PWM duty cycle for the pin to the given value. - * No inverting the duty cycle in this HAL. - * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL. - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } - -}; - -extern MarlinHAL hal; diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index efae594f6cd85..266169848daf7 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -136,5 +136,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp index 91739aaa7b06d..0b679170ef171 100644 --- a/Marlin/src/HAL/LINUX/HAL.cpp +++ b/Marlin/src/HAL/LINUX/HAL.cpp @@ -24,12 +24,6 @@ #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" -extern MarlinHAL hal; - -// ------------------------ -// Serial ports -// ------------------------ - MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true)); // U8glib required functions @@ -43,21 +37,42 @@ extern "C" { //************************// // return free heap space -int freeMemory() { return 0; } +int freeMemory() { + return 0; +} // ------------------------ // ADC // ------------------------ -uint8_t MarlinHAL::active_ch = 0; +void HAL_adc_init() { -uint16_t MarlinHAL::adc_value() { - const pin_t pin = analogInputToDigitalPin(active_ch); +} + +void HAL_adc_enable_channel(const uint8_t ch) { + +} + +uint8_t active_ch = 0; +void HAL_adc_start_conversion(const uint8_t ch) { + active_ch = ch; +} + +bool HAL_adc_finished() { + return true; +} + +uint16_t HAL_adc_get_result() { + pin_t pin = analogInputToDigitalPin(active_ch); if (!VALID_PIN(pin)) return 0; - const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); + uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); return data; // return 10bit value as Marlin expects } -void MarlinHAL::reboot() { /* Reset the application state and GPIO */ } +void HAL_pwm_init() { + +} + +void HAL_reboot() { /* Reset the application state and GPIO */ } #endif // __PLAT_LINUX__ diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 104c47ec61236..d7d3a92b73b95 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -21,42 +21,25 @@ */ #pragma once -#include -#include -#include -#undef min -#undef max -#include - -#include "hardware/Clock.h" - -#include "../shared/Marduino.h" -#include "../shared/math_32bit.h" -#include "../shared/HAL_SPI.h" -#include "fastio.h" -#include "watchdog.h" -#include "serial.h" - -// ------------------------ -// Defines -// ------------------------ - #define CPU_32_BIT -#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp #define F_CPU 100000000UL #define SystemCoreClock F_CPU +#include +#include +#include -#define DELAY_CYCLES(x) Clock::delayCycles(x) +#undef min +#undef max -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 +#include -void _printf(const char *format, ...); +void _printf (const char *format, ...); void _putc(uint8_t c); uint8_t _getc(); +//extern "C" volatile uint32_t _millis; + //arduino: Print.h #define DEC 10 #define HEX 16 @@ -66,27 +49,36 @@ uint8_t _getc(); #define B01 1 #define B10 2 -// ------------------------ -// Serial ports -// ------------------------ +#include "hardware/Clock.h" + +#include "../shared/Marduino.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" +#include "fastio.h" +#include "watchdog.h" +#include "serial.h" + +#define SHARED_SERVOS HAS_SERVOS extern MSerialT usb_serial; #define MYSERIAL1 usb_serial +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + // // Interrupts // #define CRITICAL_SECTION_START() #define CRITICAL_SECTION_END() +#define ISRS_ENABLED() +#define ENABLE_ISRS() +#define DISABLE_ISRS() -// ADC -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 - -// ------------------------ -// Class Utilities -// ------------------------ +inline void HAL_init() {} +// Utility functions #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" @@ -96,67 +88,29 @@ int freeMemory(); #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static inline void init() {} // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Reset the application state and GPIO - - static inline bool isr_state() { return true; } - static inline void isr_on() {} - static inline void isr_off() {} - - static inline void delay_ms(const int ms) { _delay_ms(ms); } - - // Tasks, called from idle() - static inline void idletask() {} - - // Reset - static constexpr uint8_t reset_reason = RST_POWER_ON; - static inline uint8_t get_reset_source() { return reset_reason; } - static inline void clear_reset_source() {} - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // - - static uint8_t active_ch; - - // Called by Temperature::init once at startup - static inline void adc_init() {} - - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const uint8_t) {} - - // Begin ADC sampling on the given channel - static inline void adc_start(const uint8_t ch) { active_ch = ch; } +// ADC +#define HAL_ADC_VREF 5.0 +#define HAL_ADC_RESOLUTION 10 +#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) +#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } +void HAL_adc_init(); +void HAL_adc_enable_channel(const uint8_t ch); +void HAL_adc_start_conversion(const uint8_t ch); +uint16_t HAL_adc_get_result(); - // The current value of the ADC register - static uint16_t adc_value(); +// PWM +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - /** - * Set the PWM duty cycle for the pin to the given value. - * No option to change the resolution or invert the duty cycle. - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } +// Reset source +inline void HAL_clear_reset_source(void) {} +inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } - static inline void set_pwm_frequency(const pin_t, int) {} -}; +void HAL_reboot(); // Reset the application state and GPIO -extern MarlinHAL hal; +/* ---------------- Delay in cycles */ +FORCE_INLINE static void DELAY_CYCLES(uint64_t x) { + Clock::delayCycles(x); +} diff --git a/Marlin/src/HAL/LINUX/arduino.cpp b/Marlin/src/HAL/LINUX/arduino.cpp index 075b4ccde2f4d..4b56d02a389c2 100644 --- a/Marlin/src/HAL/LINUX/arduino.cpp +++ b/Marlin/src/HAL/LINUX/arduino.cpp @@ -31,7 +31,9 @@ void cli() { } // Disable void sei() { } // Enable // Time functions -void _delay_ms(const int ms) { delay(ms); } +void _delay_ms(const int delay_ms) { + delay(delay_ms); +} uint32_t millis() { return (uint32_t)Clock::millis(); diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h index 49e04d0cb7d37..d4086e259a2f1 100644 --- a/Marlin/src/HAL/LINUX/include/Arduino.h +++ b/Marlin/src/HAL/LINUX/include/Arduino.h @@ -59,6 +59,7 @@ typedef uint8_t byte; #endif #define sq(v) ((v) * (v)) +#define square(v) sq(v) #define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value))) //Interrupts @@ -73,8 +74,8 @@ extern "C" { } // Time functions -extern "C" void delay(const int ms); -void _delay_ms(const int ms); +extern "C" void delay(const int milis); +void _delay_ms(const int delay); void delayMicroseconds(unsigned long); uint32_t millis(); diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index 2d2a95774c1b0..a98ceb6f391d9 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -92,5 +92,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index 541848b08acc3..cee9cfc5f744c 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -31,7 +31,7 @@ DefaultSerial1 USBSerial(false, UsbSerial); -uint32_t MarlinHAL::adc_result = 0; +uint32_t HAL_adc_reading = 0; // U8glib required functions extern "C" { @@ -41,6 +41,8 @@ extern "C" { void u8g_Delay(uint16_t val) { delay(val); } } +//************************// + // return free heap space int freeMemory() { char stack_end; @@ -52,33 +54,33 @@ int freeMemory() { return result; } -void MarlinHAL::reboot() { NVIC_SystemReset(); } - -uint8_t MarlinHAL::get_reset_source() { - #if ENABLED(USE_WATCHDOG) - if (watchdog_timed_out()) return RST_WATCHDOG; - #endif - return RST_POWER_ON; -} - -void MarlinHAL::clear_reset_source() { - TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); +// scan command line for code +// return index into pin map array if found and the pin is valid. +// return dval if not found or not a valid pin. +int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { + const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100; + const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2; + return ind > -1 ? ind : dval; } void flashFirmware(const int16_t) { delay(500); // Give OS time to disconnect USB_Connect(false); // USB clear connection delay(1000); // Give OS time to notice - hal.reboot(); + HAL_reboot(); } -// For M42/M43, scan command line for pin code -// return index into pin map array if found and the pin is valid. -// return dval if not found or not a valid pin. -int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { - const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100; - const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2; - return ind > -1 ? ind : dval; +void HAL_clear_reset_source(void) { + TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); } +uint8_t HAL_get_reset_source(void) { + #if ENABLED(USE_WATCHDOG) + if (watchdog_timed_out()) return RST_WATCHDOG; + #endif + return RST_POWER_ON; +} + +void HAL_reboot() { NVIC_SystemReset(); } + #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index e1ade3d9a72cb..348ea6b21a040 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -28,6 +28,8 @@ #define CPU_32_BIT +void HAL_init(); + #include #include #include @@ -45,9 +47,12 @@ extern "C" volatile uint32_t _millis; #include #include -// ------------------------ -// Serial ports -// ------------------------ +// +// Default graphical display delays +// +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1; extern DefaultSerial1 USBSerial; @@ -109,12 +114,26 @@ extern DefaultSerial1 USBSerial; // // Interrupts // +#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_PRIMASK()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() + +// +// Utility functions +// +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif -#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (irqon) __enable_irq() +int freeMemory(); + +#pragma GCC diagnostic pop // -// ADC +// ADC API // #define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift), @@ -133,9 +152,20 @@ extern DefaultSerial1 USBSerial; #define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t #define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL -// -// Pin Mapping for M42, M43, M226 -// +using FilteredADC = LPC176x::ADC; +extern uint32_t HAL_adc_reading; +[[gnu::always_inline]] inline void HAL_adc_start_conversion(const pin_t pin) { + HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits +} +[[gnu::always_inline]] inline uint16_t HAL_adc_get_result() { + return HAL_adc_reading; +} + +#define HAL_adc_init() +#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin) +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() (true) // Test whether the pin is valid constexpr bool VALID_PIN(const pin_t pin) { @@ -162,104 +192,32 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); // P0.6 thru P0.9 are for the onboard SD card #define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09, -// ------------------------ -// Defines -// ------------------------ +#define HAL_IDLETASK 1 +void HAL_idletask(); #define PLATFORM_M997_SUPPORT void flashFirmware(const int16_t); #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment -// Default graphical display delays -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -// ------------------------ -// Class Utilities -// ------------------------ - -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif - -int freeMemory(); - -#pragma GCC diagnostic pop - -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static void init(); // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return !__get_PRIMASK(); } - static inline void isr_on() { __enable_irq(); } - static inline void isr_off() { __disable_irq(); } - - static inline void delay_ms(const int ms) { _delay_ms(ms); } - - // Tasks, called from idle() - static void idletask(); - - // Reset - static uint8_t get_reset_source(); - static void clear_reset_source(); - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // - - using FilteredADC = LPC176x::ADC; - - // Called by Temperature::init once at startup - static inline void adc_init() {} - - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t pin) { - FilteredADC::enable_channel(pin); - } - - // Begin ADC sampling on the given pin - static uint32_t adc_result; - FORCE_INLINE static void adc_start(const pin_t pin) { - adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits - } - - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } - - // The current value of the ADC register - FORCE_INLINE static uint16_t adc_value() { - return (uint16_t)adc_result; - } +/** + * set_pwm_frequency + * Set the frequency of the timer corresponding to the provided pin + * All Hardware PWM pins run at the same frequency and all + * Software PWM pins run at the same frequency + */ +void set_pwm_frequency(const pin_t pin, int f_desired); - /** - * Set the PWM duty cycle for the pin to the given value. - * Optionally invert the duty cycle [default = false] - * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); +/** + * set_pwm_duty + * Set the PWM duty cycle of the provided pin to the provided value + * Optionally allows inverting the duty cycle [default = false] + * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] + */ +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); - /** - * Set the frequency of the timer corresponding to the provided pin - * All Hardware PWM pins will run at the same frequency and - * All Software PWM pins will run at the same frequency - */ - static void set_pwm_frequency(const pin_t pin, int f_desired); -}; +// Reset source +void HAL_clear_reset_source(void); +uint8_t HAL_get_reset_source(void); -extern MarlinHAL hal; +void HAL_reboot(); diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h index f02f503a67daa..eb12fd20f4d87 100644 --- a/Marlin/src/HAL/LPC1768/Servo.h +++ b/Marlin/src/HAL/LPC1768/Servo.h @@ -65,5 +65,4 @@ class libServo: public Servo { } }; -class libServo; -typedef libServo hal_servo_t; +#define HAL_SERVO_LIB libServo diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp index 91e92a1575015..eae0e36b0b0e3 100644 --- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp +++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp @@ -21,17 +21,21 @@ */ #ifdef TARGET_LPC1768 -#include "../../inc/MarlinConfig.h" +#include "../../inc/MarlinConfigPre.h" #include -void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!LPC176x::pin_is_valid(pin)) return; if (LPC176x::pwm_attach_pin(pin)) LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size); // map 1-254 onto PWM range } -void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { - LPC176x::pwm_set_frequency(pin, f_desired); -} +#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM + + void set_pwm_frequency(const pin_t pin, int f_desired) { + LPC176x::pwm_set_frequency(pin, f_desired); + } + +#endif #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index 419c99793fb8a..ef0dc42c78cad 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -48,7 +48,7 @@ void SysTick_Callback() { disk_timerproc(); } TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -void MarlinHAL::init() { +void HAL_init() { // Init LEDs #if PIN_EXISTS(LED) @@ -130,7 +130,7 @@ void MarlinHAL::init() { const millis_t usb_timeout = millis() + 2000; while (!USB_Configuration && PENDING(millis(), usb_timeout)) { delay(50); - idletask(); + HAL_idletask(); #if PIN_EXISTS(LED) TOGGLE(LED_PIN); // Flash quickly during USB initialization #endif @@ -142,7 +142,7 @@ void MarlinHAL::init() { } // HAL idle task -void MarlinHAL::idletask() { +void HAL_idletask() { #if HAS_SHARED_MEDIA // If Marlin is using the SD card we need to lock it to prevent access from // a PC via USB. diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index c6d7bc632e2ed..78e856db28578 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -170,4 +170,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 50da5af2eb926..436b4b4daa265 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -21,10 +21,18 @@ */ #pragma once +#define CPU_32_BIT +#define HAL_IDLETASK +void HAL_idletask(); + +#define F_CPU 100000000 +#define SystemCoreClock F_CPU #include #include + #undef min #undef max + #include #include "pinmapping.h" @@ -32,6 +40,8 @@ void _printf (const char *format, ...); void _putc(uint8_t c); uint8_t _getc(); +//extern "C" volatile uint32_t _millis; + //arduino: Print.h #define DEC 10 #define HEX 16 @@ -48,23 +58,7 @@ uint8_t _getc(); #include "watchdog.h" #include "serial.h" -// ------------------------ -// Defines -// ------------------------ - -#define CPU_32_BIT -#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp - -#define F_CPU 100000000 -#define SystemCoreClock F_CPU - -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -// ------------------------ -// Serial ports -// ------------------------ +#define SHARED_SERVOS HAS_SERVOS extern MSerialT serial_stream_0; extern MSerialT serial_stream_1; @@ -104,19 +98,49 @@ extern MSerialT serial_stream_3; #endif #endif -// ------------------------ -// Interrupts -// ------------------------ +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +// +// Interrupts +// #define CRITICAL_SECTION_START() #define CRITICAL_SECTION_END() +#define ISRS_ENABLED() +#define ENABLE_ISRS() +#define DISABLE_ISRS() -// ------------------------ -// ADC -// ------------------------ +inline void HAL_init() {} + +// Utility functions +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-function" +int freeMemory(); +#pragma GCC diagnostic pop +// ADC #define HAL_ADC_VREF 5.0 #define HAL_ADC_RESOLUTION 10 +#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) +#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true + +void HAL_adc_init(); +void HAL_adc_enable_channel(const uint8_t ch); +void HAL_adc_start_conversion(const uint8_t ch); +uint16_t HAL_adc_get_result(); + +// PWM +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + +// Reset source +inline void HAL_clear_reset_source(void) {} +inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } + +void HAL_reboot(); /* ---------------- Delay in cycles */ @@ -135,22 +159,29 @@ constexpr inline std::size_t strlen_constexpr(const char* str) { // https://github.com/gcc-mirror/gcc/blob/5c7634a0e5f202935aa6c11b6ea953b8bf80a00a/libstdc%2B%2B-v3/include/bits/char_traits.h#L329 if (str != nullptr) { std::size_t i = 0; - while (str[i] != '\0') ++i; + while (str[i] != '\0') { + ++i; + } + return i; } + return 0; } constexpr inline int strncmp_constexpr(const char* lhs, const char* rhs, std::size_t count) { // https://github.com/gcc-mirror/gcc/blob/13b9cbfc32fe3ac4c81c4dd9c42d141c8fb95db4/libstdc%2B%2B-v3/include/bits/char_traits.h#L655 - if (lhs == nullptr || rhs == nullptr) + if (lhs == nullptr || rhs == nullptr) { return rhs != nullptr ? -1 : 1; + } - for (std::size_t i = 0; i < count; ++i) + for (std::size_t i = 0; i < count; ++i) { if (lhs[i] != rhs[i]) { return lhs[i] < rhs[i] ? -1 : 1; - else if (lhs[i] == '\0') + } else if (lhs[i] == '\0') { return 0; + } + } return 0; } @@ -162,11 +193,14 @@ constexpr inline const char* strstr_constexpr(const char* str, const char* targe do { char sc = {}; do { - if ((sc = *str++) == '\0') return nullptr; + if ((sc = *str++) == '\0') { + return nullptr; + } } while (sc != c); } while (strncmp_constexpr(str, target, len) != 0); --str; } + return str; } @@ -177,88 +211,12 @@ constexpr inline char* strstr_constexpr(char* str, const char* target) { do { char sc = {}; do { - if ((sc = *str++) == '\0') return nullptr; + if ((sc = *str++) == '\0') { + return nullptr; + } } while (sc != c); } while (strncmp_constexpr(str, target, len) != 0); --str; } return str; } - -// ------------------------ -// Class Utilities -// ------------------------ - -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif - -int freeMemory(); - -#pragma GCC diagnostic pop - -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static inline void init() {} // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return true; } - static inline void isr_on() {} - static inline void isr_off() {} - - static inline void delay_ms(const int ms) { _delay_ms(ms); } - - // Tasks, called from idle() - static void idletask(); - - // Reset - static constexpr uint8_t reset_reason = RST_POWER_ON; - static inline uint8_t get_reset_source() { return reset_reason; } - static inline void clear_reset_source() {} - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // - - static uint8_t active_ch; - - // Called by Temperature::init once at startup - static void adc_init(); - - // Called by Temperature::init for each sensor at startup - static void adc_enable(const uint8_t ch); - - // Begin ADC sampling on the given channel - static void adc_start(const uint8_t ch); - - // Is the ADC ready for reading? - static bool adc_ready(); - - // The current value of the ADC register - static uint16_t adc_value(); - - /** - * Set the PWM duty cycle for the pin to the given value. - * No option to invert the duty cycle [default = false] - * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } - -}; - -extern MarlinHAL hal; diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index be38d583b6861..cedfdb62d631f 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -87,5 +87,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index f0383251283d0..8baad31bc7512 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -106,7 +106,7 @@ // Private Variables // ------------------------ -uint16_t MarlinHAL::adc_result; +uint16_t HAL_adc_result; #if ADC_IS_REQUIRED @@ -402,7 +402,7 @@ uint16_t MarlinHAL::adc_result; // ------------------------ // HAL initialization task -void MarlinHAL::init() { +void HAL_init() { TERN_(DMA_IS_REQUIRED, dma_init()); #if ENABLED(SDSUPPORT) #if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT) @@ -412,9 +412,17 @@ void MarlinHAL::init() { #endif } +// HAL idle task +/* +void HAL_idletask() { +} +*/ + +void HAL_clear_reset_source() { } + #pragma push_macro("WDT") #undef WDT // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define -uint8_t MarlinHAL::get_reset_source() { +uint8_t HAL_get_reset_source() { RSTC_RCAUSE_Type resetCause; resetCause.reg = REG_RSTC_RCAUSE; @@ -428,7 +436,7 @@ uint8_t MarlinHAL::get_reset_source() { } #pragma pop_macro("WDT") -void MarlinHAL::reboot() { NVIC_SystemReset(); } +void HAL_reboot() { NVIC_SystemReset(); } extern "C" { void * _sbrk(int incr); @@ -446,7 +454,7 @@ int freeMemory() { // ADC // ------------------------ -void MarlinHAL::adc_init() { +void HAL_adc_init() { #if ADC_IS_REQUIRED memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results)); // Fill result with invalid values @@ -483,17 +491,17 @@ void MarlinHAL::adc_init() { #endif // ADC_IS_REQUIRED } -void MarlinHAL::adc_start(const pin_t pin) { +void HAL_adc_start_conversion(const uint8_t adc_pin) { #if ADC_IS_REQUIRED LOOP_L_N(pi, COUNT(adc_pins)) { - if (pin == adc_pins[pi]) { - adc_result = HAL_adc_results[pi]; + if (adc_pin == adc_pins[pi]) { + HAL_adc_result = HAL_adc_results[pi]; return; } } #endif - adc_result = 0xFFFF; + HAL_adc_result = 0xFFFF; } #endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index a88ed9ba7988b..c262752a8d66a 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -89,29 +89,51 @@ typedef int8_t pin_t; -#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp -class Servo; -typedef Servo hal_servo_t; +#define SHARED_SERVOS HAS_SERVOS +#define HAL_SERVO_LIB Servo // // Interrupts // -#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (irqon) __enable_irq() +#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_PRIMASK()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() -#define cli() __disable_irq() // Disable interrupts -#define sei() __enable_irq() // Enable interrupts +#define cli() __disable_irq() // Disable interrupts +#define sei() __enable_irq() // Enable interrupts + +void HAL_clear_reset_source(); // clear reset reason +uint8_t HAL_get_reset_source(); // get reset reason + +void HAL_reboot(); // // ADC // +extern uint16_t HAL_adc_result; // Most recent ADC conversion + +#define HAL_ANALOG_SELECT(pin) + +void HAL_adc_init(); //#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values. #define HAL_ADC_VREF 3.3 #define HAL_ADC_RESOLUTION 10 // ... 12 +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_result +#define HAL_ADC_READY() true + +void HAL_adc_start_conversion(const uint8_t adc_pin); // -// Pin Mapping for M42, M43, M226 +// PWM +// +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + +// +// Pin Map // #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin @@ -120,92 +142,35 @@ typedef Servo hal_servo_t; // // Tone // +void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// ------------------------ -// Class Utilities -// ------------------------ +// Enable hooks into idle and setup for HAL +void HAL_init(); +/* +#define HAL_IDLETASK 1 +void HAL_idletask(); +*/ + +// +// Utility functions +// +FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" #endif +int freeMemory(); + +#pragma GCC diagnostic pop + #ifdef __cplusplus extern "C" { #endif - char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s); - -extern "C" int freeMemory(); - #ifdef __cplusplus } #endif - -#pragma GCC diagnostic pop - -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static void init(); // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return !__get_PRIMASK(); } - static inline void isr_on() { sei(); } - static inline void isr_off() { cli(); } - - static inline void delay_ms(const int ms) { delay(ms); } - - // Tasks, called from idle() - static inline void idletask() {} - - // Reset - static uint8_t get_reset_source(); - static inline void clear_reset_source() {} - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // - - static uint16_t adc_result; - - // Called by Temperature::init once at startup - static void adc_init(); - - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const uint8_t ch) {} - - // Begin ADC sampling on the given channel - static void adc_start(const pin_t pin); - - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } - - // The current value of the ADC register - static uint16_t adc_value() { return adc_result; } - - /** - * Set the PWM duty cycle for the pin to the given value. - * No option to invert the duty cycle [default = false] - * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false) { - analogWrite(pin, v); - } - -}; - -extern MarlinHAL hal; diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index 324a78316a2d7..0920a72ec1bcd 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -53,18 +53,16 @@ // Public Variables // ------------------------ -uint16_t MarlinHAL::adc_result; +uint16_t HAL_adc_result; // ------------------------ // Public functions // ------------------------ -#if ENABLED(POSTMORTEM_DEBUGGING) - extern void install_min_serial(); -#endif +TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); // HAL initialization task -void MarlinHAL::init() { +void HAL_init() { // Ensure F_CPU is a constant expression. // If the compiler breaks here, it means that delay code that should compute at compile time will not work. // So better safe than sorry here. @@ -105,7 +103,7 @@ void MarlinHAL::init() { } // HAL idle task -void MarlinHAL::idletask() { +void HAL_idletask() { #if HAS_SHARED_MEDIA // Stm32duino currently doesn't have a "loop/idle" method CDC_resume_receive(); @@ -113,9 +111,9 @@ void MarlinHAL::idletask() { #endif } -void MarlinHAL::reboot() { NVIC_SystemReset(); } +void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } -uint8_t MarlinHAL::get_reset_source() { +uint8_t HAL_get_reset_source() { return #ifdef RCC_FLAG_IWDGRST // Some sources may not exist... RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) ? RST_WATCHDOG : @@ -139,14 +137,24 @@ uint8_t MarlinHAL::get_reset_source() { ; } -void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } +void HAL_reboot() { NVIC_SystemReset(); } + +void _delay_ms(const int delay_ms) { delay(delay_ms); } extern "C" { extern unsigned int _ebss; // end of bss section } +// ------------------------ +// ADC +// ------------------------ + +// TODO: Make sure this doesn't cause any delay +void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); } +uint16_t HAL_adc_get_result() { return HAL_adc_result; } + // Reset the system to initiate a firmware flash -WEAK void flashFirmware(const int16_t) { hal.reboot(); } +WEAK void flashFirmware(const int16_t) { HAL_reboot(); } // Maple Compatibility volatile uint32_t systick_uptime_millis = 0; diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index f9bf1c938aa50..adaf14223f324 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -44,9 +44,9 @@ #define CPU_ST7920_DELAY_2 40 #define CPU_ST7920_DELAY_3 340 -// ------------------------ -// Serial ports -// ------------------------ +// +// Serial Ports +// #ifdef USBCON #include #include "../../core/serial_hook.h" @@ -115,14 +115,17 @@ #define analogInputToDigitalPin(p) (p) #endif -// -// Interrupts -// -#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (irqon) __enable_irq() +#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_PRIMASK()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() #define cli() __disable_irq() #define sei() __enable_irq() +// On AVR this is in math.h? +#define square(x) ((x)*(x)) + // ------------------------ // Types // ------------------------ @@ -133,61 +136,43 @@ typedef int16_t pin_t; #endif -class libServo; -typedef libServo hal_servo_t; +#define HAL_SERVO_LIB libServo #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos() // ------------------------ -// ADC +// Public Variables // ------------------------ -#ifdef ADC_RESOLUTION - #define HAL_ADC_RESOLUTION ADC_RESOLUTION -#else - #define HAL_ADC_RESOLUTION 12 -#endif - -#define HAL_ADC_VREF 3.3 +// result of last ADC conversion +extern uint16_t HAL_adc_result; -// -// Pin Mapping for M42, M43, M226 -// -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +// ------------------------ +// Public functions +// ------------------------ -#ifdef STM32F1xx - #define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE) - #define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE) - #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG -#endif +// Memory related +#define __bss_end __bss_end__ -#define PLATFORM_M997_SUPPORT -void flashFirmware(const int16_t); +// Enable hooks into setup for HAL +void HAL_init(); +#define HAL_IDLETASK 1 +void HAL_idletask(); -// Maple Compatibility -typedef void (*systickCallback_t)(void); -void systick_attach_callback(systickCallback_t cb); -void HAL_SYSTICK_Callback(); +// Clear reset reason +void HAL_clear_reset_source(); -extern volatile uint32_t systick_uptime_millis; +// Reset reason +uint8_t HAL_get_reset_source(); -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment +void HAL_reboot(); -// ------------------------ -// Class Utilities -// ------------------------ - -// Memory related -#define __bss_end __bss_end__ +void _delay_ms(const int delay); extern "C" char* _sbrk(int incr); #pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif +#pragma GCC diagnostic ignored "-Wunused-function" static inline int freeMemory() { volatile char top; @@ -196,72 +181,62 @@ static inline int freeMemory() { #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static void init(); // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return !__get_PRIMASK(); } - static inline void isr_on() { sei(); } - static inline void isr_off() { cli(); } - - static inline void delay_ms(const int ms) { delay(ms); } +// +// ADC +// - // Tasks, called from idle() - static void idletask(); +#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) - // Reset - static uint8_t get_reset_source(); - static void clear_reset_source(); +#ifdef ADC_RESOLUTION + #define HAL_ADC_RESOLUTION ADC_RESOLUTION +#else + #define HAL_ADC_RESOLUTION 12 +#endif - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } +#define HAL_ADC_VREF 3.3 +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_result +#define HAL_ADC_READY() true - // - // ADC Methods - // +inline void HAL_adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); } - static uint16_t adc_result; +void HAL_adc_start_conversion(const uint8_t adc_pin); - // Called by Temperature::init once at startup - static inline void adc_init() { - analogReadResolution(HAL_ADC_RESOLUTION); - } +uint16_t HAL_adc_get_result(); - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t pin) { pinMode(pin, INPUT); } +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) - // Begin ADC sampling on the given channel - static void adc_start(const pin_t pin) { adc_result = analogRead(pin); } +#ifdef STM32F1xx + #define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE) + #define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE) + #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG +#endif - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } +#define PLATFORM_M997_SUPPORT +void flashFirmware(const int16_t); - // The current value of the ADC register - static uint16_t adc_value() { return adc_result; } +// Maple Compatibility +typedef void (*systickCallback_t)(void); +void systick_attach_callback(systickCallback_t cb); +void HAL_SYSTICK_Callback(); - /** - * Set the PWM duty cycle for the pin to the given value. - * Optionally invert the duty cycle [default = false] - * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] - */ - static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); +extern volatile uint32_t systick_uptime_millis; - /** - * Set the frequency of the timer for the given pin. - * All Timer PWM pins run at the same frequency. - */ - static void set_pwm_frequency(const pin_t pin, int f_desired); +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment -}; +/** + * set_pwm_frequency + * Set the frequency of the timer corresponding to the provided pin + * All Timer PWM pins run at the same frequency + */ +void set_pwm_frequency(const pin_t pin, int f_desired); -extern MarlinHAL hal; +/** + * set_pwm_duty + * Set the PWM duty cycle of the provided pin to the provided value + * Optionally allows inverting the duty cycle [default = false] + * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] + */ +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 40d320d5e8220..8ee4761647856 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -102,9 +102,9 @@ static SPISettings spiConfig; // Soft SPI receive byte uint8_t spiRec() { - hal.isr_off(); // No interrupts during byte receive + DISABLE_ISRS(); // No interrupts during byte receive const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF); - hal.isr_on(); // Enable interrupts + ENABLE_ISRS(); // Enable interrupts return data; } @@ -116,9 +116,9 @@ static SPISettings spiConfig; // Soft SPI send byte void spiSend(uint8_t data) { - hal.isr_off(); // No interrupts during byte send + DISABLE_ISRS(); // No interrupts during byte send HAL_SPI_STM32_SpiTransfer_Mode_3(data); // Don't care what is received - hal.isr_on(); // Enable interrupts + ENABLE_ISRS(); // Enable interrupts } // Soft SPI send block diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 7c8cc8dd21e18..252b057362c99 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -174,9 +174,9 @@ bool PersistentStore::access_finish() { UNLOCK_FLASH(); TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); - hal.isr_off(); + DISABLE_ISRS(); status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError); - hal.isr_on(); + ENABLE_ISRS(); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); if (status != HAL_OK) { DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status); @@ -229,9 +229,9 @@ bool PersistentStore::access_finish() { // output. Servo output still glitches with interrupts disabled, but recovers after the // erase. TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); - hal.isr_off(); + DISABLE_ISRS(); eeprom_buffer_flush(); - hal.isr_on(); + ENABLE_ISRS(); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); eeprom_data_written = false; diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index f6d0481c05c1d..b1bea5ce20eb8 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -29,7 +29,7 @@ // Array to support sticky frequency sets per timer static uint16_t timer_freq[TIMER_NUM]; -void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer const PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); @@ -56,7 +56,7 @@ void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume(); } -void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { +void set_pwm_frequency(const pin_t pin, int f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer const PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index a7f022a0b62dd..73d850fc43132 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -115,6 +115,7 @@ const XrefInfo pin_xref[] PROGMEM = { #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define PRINT_PORT(ANUM) port_print(ANUM) #define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine +#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num // x is a variable used to search pin_array #define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) @@ -122,11 +123,6 @@ const XrefInfo pin_xref[] PROGMEM = { #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin -// -// Pin Mapping for M43 -// -#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num - #ifndef M43_NEVER_TOUCH #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP) #ifdef KILL_PIN diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 6828998198af1..aad543229e164 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -116,5 +116,5 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha } } -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_prologue(T) +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index efc513cf94d29..f29b30536146e 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -79,7 +79,7 @@ #define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ // ------------------------ -// Serial ports +// Public Variables // ------------------------ #if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE @@ -112,21 +112,72 @@ #endif #endif +uint16_t HAL_adc_result; + // ------------------------ -// ADC +// Private Variables // ------------------------ +STM32ADC adc(ADC1); -uint16_t analogRead(pin_t pin) { - const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG; - return is_analog ? analogRead(uint8_t(pin)) : 0; -} - -// Wrapper to maple unprotected analogWrite -void analogWrite(pin_t pin, int pwm_val8) { - if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8); -} - -uint16_t MarlinHAL::adc_result; +const uint8_t adc_pins[] = { + #if HAS_TEMP_ADC_0 + TEMP_0_PIN, + #endif + #if HAS_TEMP_ADC_PROBE + TEMP_PROBE_PIN, + #endif + #if HAS_HEATED_BED + TEMP_BED_PIN, + #endif + #if HAS_TEMP_CHAMBER + TEMP_CHAMBER_PIN, + #endif + #if HAS_TEMP_COOLER + TEMP_COOLER_PIN, + #endif + #if HAS_TEMP_ADC_1 + TEMP_1_PIN, + #endif + #if HAS_TEMP_ADC_2 + TEMP_2_PIN, + #endif + #if HAS_TEMP_ADC_3 + TEMP_3_PIN, + #endif + #if HAS_TEMP_ADC_4 + TEMP_4_PIN, + #endif + #if HAS_TEMP_ADC_5 + TEMP_5_PIN, + #endif + #if HAS_TEMP_ADC_6 + TEMP_6_PIN, + #endif + #if HAS_TEMP_ADC_7 + TEMP_7_PIN, + #endif + #if ENABLED(FILAMENT_WIDTH_SENSOR) + FILWIDTH_PIN, + #endif + #if HAS_ADC_BUTTONS + ADC_KEYPAD_PIN, + #endif + #if HAS_JOY_ADC_X + JOY_X_PIN, + #endif + #if HAS_JOY_ADC_Y + JOY_Y_PIN, + #endif + #if HAS_JOY_ADC_Z + JOY_Z_PIN, + #endif + #if ENABLED(POWER_MONITOR_CURRENT) + POWER_MONITOR_CURRENT_PIN, + #endif + #if ENABLED(POWER_MONITOR_VOLTAGE) + POWER_MONITOR_VOLTAGE_PIN, + #endif +}; enum TempPinIndex : char { #if HAS_TEMP_ADC_0 @@ -194,16 +245,15 @@ uint16_t HAL_adc_results[ADC_PIN_COUNT]; // ------------------------ // Private functions // ------------------------ - static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); // only values 0..7 are used + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ - reg_value = SCB->AIRCR; // read old register configuration - reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); // clear bits to change + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ reg_value = (reg_value | ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8)); // Insert write key & priority group + (PriorityGroupTmp << 8)); /* Insert write key & priority group */ SCB->AIRCR = reg_value; } @@ -211,8 +261,6 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { // Public functions // ------------------------ -void flashFirmware(const int16_t) { hal.reboot(); } - // // Leave PA11/PA12 intact if USBSerial is not used // @@ -232,11 +280,7 @@ void flashFirmware(const int16_t) { hal.reboot(); } TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -// ------------------------ -// MarlinHAL class -// ------------------------ - -void MarlinHAL::init() { +void HAL_init() { NVIC_SetPriorityGrouping(0x3); #if PIN_EXISTS(LED) OUT_WRITE(LED_PIN, LOW); @@ -255,7 +299,7 @@ void MarlinHAL::init() { } // HAL idle task -void MarlinHAL::idletask() { +void HAL_idletask() { #if HAS_SHARED_MEDIA // If Marlin is using the SD card we need to lock it to prevent access from // a PC via USB. @@ -270,7 +314,14 @@ void MarlinHAL::idletask() { #endif } -void MarlinHAL::reboot() { nvic_sys_reset(); } +void HAL_clear_reset_source() { } + +/** + * TODO: Check this and change or remove. + */ +uint8_t HAL_get_reset_source() { return RST_POWER_ON; } + +void _delay_ms(const int delay_ms) { delay(delay_ms); } extern "C" { extern unsigned int _ebss; // end of bss section @@ -304,70 +355,11 @@ extern "C" { } */ +// ------------------------ // ADC - +// ------------------------ // Init the AD in continuous capture mode -void MarlinHAL::adc_init() { - static const uint8_t adc_pins[] = { - #if HAS_TEMP_ADC_0 - TEMP_0_PIN, - #endif - #if HAS_TEMP_ADC_PROBE - TEMP_PROBE_PIN, - #endif - #if HAS_HEATED_BED - TEMP_BED_PIN, - #endif - #if HAS_TEMP_CHAMBER - TEMP_CHAMBER_PIN, - #endif - #if HAS_TEMP_COOLER - TEMP_COOLER_PIN, - #endif - #if HAS_TEMP_ADC_1 - TEMP_1_PIN, - #endif - #if HAS_TEMP_ADC_2 - TEMP_2_PIN, - #endif - #if HAS_TEMP_ADC_3 - TEMP_3_PIN, - #endif - #if HAS_TEMP_ADC_4 - TEMP_4_PIN, - #endif - #if HAS_TEMP_ADC_5 - TEMP_5_PIN, - #endif - #if HAS_TEMP_ADC_6 - TEMP_6_PIN, - #endif - #if HAS_TEMP_ADC_7 - TEMP_7_PIN, - #endif - #if ENABLED(FILAMENT_WIDTH_SENSOR) - FILWIDTH_PIN, - #endif - #if HAS_ADC_BUTTONS - ADC_KEYPAD_PIN, - #endif - #if HAS_JOY_ADC_X - JOY_X_PIN, - #endif - #if HAS_JOY_ADC_Y - JOY_Y_PIN, - #endif - #if HAS_JOY_ADC_Z - JOY_Z_PIN, - #endif - #if ENABLED(POWER_MONITOR_CURRENT) - POWER_MONITOR_CURRENT_PIN, - #endif - #if ENABLED(POWER_MONITOR_VOLTAGE) - POWER_MONITOR_VOLTAGE_PIN, - #endif - }; - static STM32ADC adc(ADC1); +void HAL_adc_init() { // configure the ADC adc.calibrate(); #if F_CPU > 72000000 @@ -382,10 +374,10 @@ void MarlinHAL::adc_init() { adc.startConversion(); } -void MarlinHAL::adc_start(const pin_t pin) { +void HAL_adc_start_conversion(const uint8_t adc_pin) { //TEMP_PINS pin_index; TempPinIndex pin_index; - switch (pin) { + switch (adc_pin) { default: return; #if HAS_TEMP_ADC_0 case TEMP_0_PIN: pin_index = TEMP_0; break; @@ -448,4 +440,20 @@ void MarlinHAL::adc_start(const pin_t pin) { HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits } +uint16_t HAL_adc_get_result() { return HAL_adc_result; } + +uint16_t analogRead(pin_t pin) { + const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG; + return is_analog ? analogRead(uint8_t(pin)) : 0; +} + +// Wrapper to maple unprotected analogWrite +void analogWrite(pin_t pin, int pwm_val8) { + if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8); +} + +void HAL_reboot() { nvic_sys_reset(); } + +void flashFirmware(const int16_t) { HAL_reboot(); } + #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 9b973c3ea4fe3..153cfe8ac89e6 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -66,10 +66,6 @@ #endif #endif -// ------------------------ -// Serial ports -// ------------------------ - #ifdef SERIAL_USB typedef ForwardSerial1Class< USBSerial > DefaultSerial1; extern DefaultSerial1 MSerial0; @@ -145,6 +141,11 @@ #endif #endif +// Set interrupt grouping for this MCU +void HAL_init(); +#define HAL_IDLETASK 1 +void HAL_idletask(); + /** * TODO: review this to return 1 for pins that are not analog input */ @@ -157,7 +158,15 @@ #define NO_COMPILE_TIME_PWM #endif -// Reset Reason +#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); (void)__iCliRetVal() +#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal() +#define ISRS_ENABLED() (!__get_primask()) +#define ENABLE_ISRS() ((void)__iSeiRetVal()) +#define DISABLE_ISRS() ((void)__iCliRetVal()) + +// On AVR this is in math.h? +#define square(x) ((x)*(x)) + #define RST_POWER_ON 1 #define RST_EXTERNAL 2 #define RST_BROWN_OUT 4 @@ -172,67 +181,47 @@ typedef int8_t pin_t; -// Result of last ADC conversion -extern uint16_t HAL_adc_result; - // ------------------------ -// Interrupts +// Public Variables // ------------------------ -#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); (void)__iCliRetVal() -#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal() -#define cli() noInterrupts() -#define sei() interrupts() +// Result of last ADC conversion +extern uint16_t HAL_adc_result; // ------------------------ -// ADC +// Public functions // ------------------------ -#ifdef ADC_RESOLUTION - #define HAL_ADC_RESOLUTION ADC_RESOLUTION -#else - #define HAL_ADC_RESOLUTION 12 -#endif - -#define HAL_ADC_VREF 3.3 +// Disable interrupts +#define cli() noInterrupts() -uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first -void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? +// Enable interrupts +#define sei() interrupts() -// -// Pin Mapping for M42, M43, M226 -// -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +// Memory related +#define __bss_end __bss_end__ -#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY) -#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE) +// Clear reset reason +void HAL_clear_reset_source(); -#define PLATFORM_M997_SUPPORT -void flashFirmware(const int16_t); +// Reset reason +uint8_t HAL_get_reset_source(); -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment -#ifndef PWM_FREQUENCY - #define PWM_FREQUENCY 1000 // Default PWM Frequency -#endif +void HAL_reboot(); -// ------------------------ -// Class Utilities -// ------------------------ +void _delay_ms(const int delay); -// Memory related -#define __bss_end __bss_end__ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-function" -void _delay_ms(const int ms); +/* +extern "C" { + int freeMemory(); +} +*/ extern "C" char* _sbrk(int incr); -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif - static inline int freeMemory() { volatile char top; return &top - _sbrk(0); @@ -240,71 +229,58 @@ static inline int freeMemory() { #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static void init(); // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return !__get_primask(); } - static inline void isr_on() { ((void)__iSeiRetVal()); } - static inline void isr_off() { ((void)__iCliRetVal()); } - - static inline void delay_ms(const int ms) { delay(ms); } - - // Tasks, called from idle() - static void idletask(); - - // Reset - static inline uint8_t get_reset_source() { return RST_POWER_ON; } - static inline void clear_reset_source() {} +// +// ADC +// - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } +#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG); - // - // ADC Methods - // +void HAL_adc_init(); - static uint16_t adc_result; +#ifdef ADC_RESOLUTION + #define HAL_ADC_RESOLUTION ADC_RESOLUTION +#else + #define HAL_ADC_RESOLUTION 12 +#endif - // Called by Temperature::init once at startup - static void adc_init(); +#define HAL_ADC_VREF 3.3 +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_result +#define HAL_ADC_READY() true - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t pin) { pinMode(pin, INPUT_ANALOG); } +void HAL_adc_start_conversion(const uint8_t adc_pin); +uint16_t HAL_adc_get_result(); - // Begin ADC sampling on the given channel - static void adc_start(const pin_t pin); +uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first +void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) - // The current value of the ADC register - static uint16_t adc_value() { return adc_result; } +#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY) +#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE) - /** - * Set the PWM duty cycle for the pin to the given value. - * Optionally invert the duty cycle [default = false] - * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] - * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false); +#define PLATFORM_M997_SUPPORT +void flashFirmware(const int16_t); - /** - * Set the frequency of the timer for the given pin. - * All Timer PWM pins run at the same frequency. - */ - static void set_pwm_frequency(const pin_t pin, int f_desired); +#ifndef PWM_FREQUENCY + #define PWM_FREQUENCY 1000 // Default PWM Frequency +#endif +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment -}; +/** + * set_pwm_frequency + * Set the frequency of the timer corresponding to the provided pin + * All Timer PWM pins run at the same frequency + */ +void set_pwm_frequency(const pin_t pin, int f_desired); -extern MarlinHAL hal; +/** + * set_pwm_duty + * Set the PWM duty cycle of the provided pin to the provided value + * Optionally allows inverting the duty cycle [default = false] + * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] + * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. + */ +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); diff --git a/Marlin/src/HAL/STM32F1/Servo.h b/Marlin/src/HAL/STM32F1/Servo.h index 745a1c93f07d4..b6143de81d62a 100644 --- a/Marlin/src/HAL/STM32F1/Servo.h +++ b/Marlin/src/HAL/STM32F1/Servo.h @@ -35,8 +35,7 @@ #define SERVO_DEFAULT_MIN_ANGLE 0 #define SERVO_DEFAULT_MAX_ANGLE 180 -class libServo; -typedef libServo hal_servo_t; +#define HAL_SERVO_LIB libServo class libServo { public: diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp index 11a1a107123e6..98d56bc5e9319 100644 --- a/Marlin/src/HAL/STM32F1/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp @@ -21,9 +21,11 @@ */ #ifdef __STM32F1__ -#include "../../inc/MarlinConfig.h" +#include "../../inc/MarlinConfigPre.h" #include +#include "HAL.h" +#include "timers.h" #define NR_TIMERS TERN(STM32_XL_DENSITY, 14, 8) // Maple timers, 14 for STM32_XL_DENSITY (F/G chips), 8 for HIGH density (C D E) @@ -36,7 +38,7 @@ inline uint8_t timer_and_index_for_pin(const pin_t pin, timer_dev **timer_ptr) { return 0; } -void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!PWM_PIN(pin)) return; timer_dev *timer; UNUSED(timer); @@ -49,7 +51,7 @@ void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode } -void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) { +void set_pwm_frequency(const pin_t pin, int f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer timer_dev *timer; UNUSED(timer); diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 0cd807fc84799..f9ab6d13d3741 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -188,7 +188,7 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_epilogue(T) // No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple. // Needed here to reset ARPE=0 for stepper timer diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp index b923ab77b1f12..f08cf799e9e8b 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL.cpp @@ -31,10 +31,6 @@ #include -// ------------------------ -// Serial ports -// ------------------------ - #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -44,32 +40,33 @@ #endif USBSerialType USBSerial(false, SerialUSB); -// ------------------------ -// Class Utilities -// ------------------------ +uint16_t HAL_adc_result; -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; +static const uint8_t pin2sc1a[] = { + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13 + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9) + 31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33 + 0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13) + 26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0. +}; - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; - } -} +/* + // disable interrupts + void cli() { noInterrupts(); } -// ------------------------ -// MarlinHAL Class -// ------------------------ + // enable interrupts + void sei() { interrupts(); } +*/ + +void HAL_adc_init() { + analog_init(); + while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish + NVIC_ENABLE_IRQ(IRQ_FTM1); +} -void MarlinHAL::reboot() { _reboot_Teensyduino_(); } +void HAL_clear_reset_source() { } -uint8_t MarlinHAL::get_reset_source() { +uint8_t HAL_get_reset_source() { switch (RCM_SRS0) { case 128: return RST_POWER_ON; break; case 64: return RST_EXTERNAL; break; @@ -81,25 +78,25 @@ uint8_t MarlinHAL::get_reset_source() { return 0; } -// ADC +void HAL_reboot() { _reboot_Teensyduino_(); } -void MarlinHAL::adc_init() { - analog_init(); - while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish - NVIC_ENABLE_IRQ(IRQ_FTM1); -} +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; -void MarlinHAL::adc_start(const pin_t pin) { - static const uint8_t pin2sc1a[] = { - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13 - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9) - 31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33 - 0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13) - 26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0. - }; - ADC0_SC1A = pin2sc1a[pin]; + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } } -uint16_t MarlinHAL::adc_value() { return ADC0_RA; } +void HAL_adc_start_conversion(const uint8_t adc_pin) { ADC0_SC1A = pin2sc1a[adc_pin]; } + +uint16_t HAL_adc_get_result() { return ADC0_RA; } #endif // __MK20DX256__ diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 14f463708bce5..61d8b34604c52 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -36,9 +36,12 @@ #include -// ------------------------ -// Defines -// ------------------------ +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +//#undef MOTHERBOARD +//#define MOTHERBOARD BOARD_TEENSY31_32 #define IS_32BIT_TEENSY 1 #define IS_TEENSY_31_32 1 @@ -46,14 +49,6 @@ #define IS_TEENSY32 1 #endif -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -// ------------------------ -// Serial ports -// ------------------------ - #include "../../core/serial_hook.h" #define Serial0 Serial @@ -77,44 +72,31 @@ extern USBSerialType USBSerial; #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif -// ------------------------ -// Types -// ------------------------ - -class libServo; -typedef libServo hal_servo_t; +#define HAL_SERVO_LIB libServo typedef int8_t pin_t; -// ------------------------ -// Interrupts -// ------------------------ - -uint32_t __get_PRIMASK(void); // CMSIS -#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() -#define CRITICAL_SECTION_END() if (irqon) __enable_irq() - -// ------------------------ -// ADC -// ------------------------ - #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 +#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_PRIMASK()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() -// -// Pin Mapping for M42, M43, M226 -// -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +inline void HAL_init() {} -// ------------------------ -// Class Utilities -// ------------------------ +// Clear the reset reason +void HAL_clear_reset_source(); + +// Get the reason for the reset +uint8_t HAL_get_reset_source(); + +void HAL_reboot(); + +FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -125,64 +107,27 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static inline void init() {} // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return !__get_PRIMASK(); } - static inline void isr_on() { __enable_irq(); } - static inline void isr_off() { __disable_irq(); } - - static inline void delay_ms(const int ms) { delay(ms); } - - // Tasks, called from idle() - static inline void idletask() {} - - // Reset - static uint8_t get_reset_source(); - static inline void clear_reset_source() {} - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // +// ADC - // Called by Temperature::init once at startup - static void adc_init(); +void HAL_adc_init(); - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t ch) {} +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true - // Begin ADC sampling on the given channel - static void adc_start(const pin_t ch); +#define HAL_ANALOG_SELECT(pin) - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } +void HAL_adc_start_conversion(const uint8_t adc_pin); +uint16_t HAL_adc_get_result(); - // The current value of the ADC register - static uint16_t adc_value(); +// PWM - /** - * Set the PWM duty cycle for the pin to the given value. - * No option to invert the duty cycle [default = false] - * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } -}; +// Pin Map -extern MarlinHAL hal; +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 9fcbb6f232c93..3b073d63ab293 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -110,4 +110,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp index 54a5ad3855361..046c00b56ed53 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL.cpp @@ -31,10 +31,6 @@ #include -// ------------------------ -// Serial ports -// ------------------------ - #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -43,34 +39,42 @@ USBSerialType USBSerial(false, SerialUSB); -// ------------------------ -// Class Utilities -// ------------------------ - -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; - - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; - } +uint16_t HAL_adc_result, HAL_adc_select; + +static const uint8_t pin2sc1a[] = { + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13 + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9 + 255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only + 14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128, // 31-39 are A12-A20 + 255, 255, 255, 255, 255, 255, 255, 255, 255, // 40-48 are digital only + 10+128, 11+128, // 49-50 are A23-A24 + 255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only + 255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only + 3, 19+128, // 64-65 are A10-A11 + 23, 23+128,// 66-67 are A21-A22 (DAC pins) + 1, 1+128, // 68-69 are A25-A26 (unused USB host port on Teensy 3.5) + 26, // 70 is Temperature Sensor + 18+128 // 71 is Vref +}; + +/* + // disable interrupts + void cli() { noInterrupts(); } + + // enable interrupts + void sei() { interrupts(); } +*/ + +void HAL_adc_init() { + analog_init(); + while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish + while (ADC1_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish + NVIC_ENABLE_IRQ(IRQ_FTM1); } -// ------------------------ -// MarlinHAL Class -// ------------------------ +void HAL_clear_reset_source() { } -void MarlinHAL::reboot() { _reboot_Teensyduino_(); } - -// Reset - -uint8_t MarlinHAL::get_reset_source() { +uint8_t HAL_get_reset_source() { switch (RCM_SRS0) { case 128: return RST_POWER_ON; break; case 64: return RST_EXTERNAL; break; @@ -82,49 +86,41 @@ uint8_t MarlinHAL::get_reset_source() { return 0; } -// ADC +void HAL_reboot() { _reboot_Teensyduino_(); } -int8_t MarlinHAL::adc_select; +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; -void MarlinHAL::adc_init() { - analog_init(); - while (ADC0_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ } - while (ADC1_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ } - NVIC_ENABLE_IRQ(IRQ_FTM1); + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } } -void MarlinHAL::adc_start(const pin_t adc_pin) { - static const uint8_t pin2sc1a[] = { - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13 - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9 - 255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only - 14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128, // 31-39 are A12-A20 - 255, 255, 255, 255, 255, 255, 255, 255, 255, // 40-48 are digital only - 10+128, 11+128, // 49-50 are A23-A24 - 255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only - 255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only - 3, 19+128, // 64-65 are A10-A11 - 23, 23+128,// 66-67 are A21-A22 (DAC pins) - 1, 1+128, // 68-69 are A25-A26 (unused USB host port on Teensy 3.5) - 26, // 70 is Temperature Sensor - 18+128 // 71 is Vref - }; +void HAL_adc_start_conversion(const uint8_t adc_pin) { const uint16_t pin = pin2sc1a[adc_pin]; if (pin == 0xFF) { - adc_select = -1; // Digital only + // Digital only + HAL_adc_select = -1; } else if (pin & 0x80) { - adc_select = 1; + HAL_adc_select = 1; ADC1_SC1A = pin & 0x7F; } else { - adc_select = 0; + HAL_adc_select = 0; ADC0_SC1A = pin; } } -uint16_t MarlinHAL::adc_value() { - switch (adc_select) { +uint16_t HAL_adc_get_result() { + switch (HAL_adc_select) { case 0: return ADC0_RA; case 1: return ADC1_RA; } diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 1cc465c4bbf2c..892eb2d3c5b8f 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -37,6 +37,10 @@ #include #include +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + // ------------------------ // Defines // ------------------------ @@ -49,17 +53,6 @@ #define IS_TEENSY35 1 #endif -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -#undef sq -#define sq(x) ((x)*(x)) - -// ------------------------ -// Serial ports -// ------------------------ - #include "../../core/serial_hook.h" #define Serial0 Serial @@ -83,43 +76,34 @@ extern USBSerialType USBSerial; #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif -// ------------------------ -// Types -// ------------------------ - -class libServo; -typedef libServo hal_servo_t; +#define HAL_SERVO_LIB libServo typedef int8_t pin_t; -// ------------------------ -// Interrupts -// ------------------------ - -#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); __disable_irq() -#define CRITICAL_SECTION_END() if (irqon) __enable_irq() - -// ------------------------ -// ADC -// ------------------------ - #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 +#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_primask()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() -// -// Pin Mapping for M42, M43, M226 -// -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +#undef sq +#define sq(x) ((x)*(x)) -// ------------------------ -// Class Utilities -// ------------------------ +inline void HAL_init() {} + +// Clear reset reason +void HAL_clear_reset_source(); + +// Reset reason +uint8_t HAL_get_reset_source(); + +void HAL_reboot(); + +FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -130,66 +114,27 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static inline void init() {} // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return true; } - static inline void isr_on() { __enable_irq(); } - static inline void isr_off() { __disable_irq(); } - - static inline void delay_ms(const int ms) { delay(ms); } - - // Tasks, called from idle() - static inline void idletask() {} - - // Reset - static uint8_t get_reset_source(); - static inline void clear_reset_source() {} - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // - - static int8_t adc_select; +// ADC - // Called by Temperature::init once at startup - static void adc_init(); +void HAL_adc_init(); - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t) {} +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true - // Begin ADC sampling on the given channel - static void adc_start(const pin_t pin); +#define HAL_ANALOG_SELECT(pin) - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } +void HAL_adc_start_conversion(const uint8_t adc_pin); +uint16_t HAL_adc_get_result(); - // The current value of the ADC register - static uint16_t adc_value(); +// PWM - /** - * Set the PWM duty cycle for the pin to the given value. - * No option to invert the duty cycle [default = false] - * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } -}; +// Pin Map -extern MarlinHAL hal; +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 8af79d73928e5..6c342bbe0d252 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -109,4 +109,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index 68bd38f72ff89..270bee0dc9d45 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -33,10 +33,6 @@ #include "timers.h" #include -// ------------------------ -// Serial ports -// ------------------------ - #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -44,42 +40,75 @@ #endif USBSerialType USBSerial(false, SerialUSB); -// ------------------------ -// Class Utilities -// ------------------------ - -#define __bss_end _ebss - -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; - - // Doesn't work on Teensy 4.x - uint32_t freeMemory() { - uint32_t free_memory; - free_memory = ((uint32_t)&free_memory) - (((uint32_t)__brkval) ?: ((uint32_t)&__bss_end)); - return free_memory; - } +uint16_t HAL_adc_result, HAL_adc_select; + +static const uint8_t pin2sc1a[] = { + 0x07, // 0/A0 AD_B1_02 + 0x08, // 1/A1 AD_B1_03 + 0x0C, // 2/A2 AD_B1_07 + 0x0B, // 3/A3 AD_B1_06 + 0x06, // 4/A4 AD_B1_01 + 0x05, // 5/A5 AD_B1_00 + 0x0F, // 6/A6 AD_B1_10 + 0x00, // 7/A7 AD_B1_11 + 0x0D, // 8/A8 AD_B1_08 + 0x0E, // 9/A9 AD_B1_09 + 0x01, // 24/A10 AD_B0_12 + 0x02, // 25/A11 AD_B0_13 + 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 + 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 + 0x07, // 14/A0 AD_B1_02 + 0x08, // 15/A1 AD_B1_03 + 0x0C, // 16/A2 AD_B1_07 + 0x0B, // 17/A3 AD_B1_06 + 0x06, // 18/A4 AD_B1_01 + 0x05, // 19/A5 AD_B1_00 + 0x0F, // 20/A6 AD_B1_10 + 0x00, // 21/A7 AD_B1_11 + 0x0D, // 22/A8 AD_B1_08 + 0x0E, // 23/A9 AD_B1_09 + 0x01, // 24/A10 AD_B0_12 + 0x02, // 25/A11 AD_B0_13 + 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 + 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 + #ifdef ARDUINO_TEENSY41 + 0xFF, // 28 + 0xFF, // 29 + 0xFF, // 30 + 0xFF, // 31 + 0xFF, // 32 + 0xFF, // 33 + 0xFF, // 34 + 0xFF, // 35 + 0xFF, // 36 + 0xFF, // 37 + 0x81, // 38/A14 AD_B1_12 - only on ADC2, 1 + 0x82, // 39/A15 AD_B1_13 - only on ADC2, 2 + 0x09, // 40/A16 AD_B1_04 + 0x0A, // 41/A17 AD_B1_05 + #endif +}; + +/* +// disable interrupts +void cli() { noInterrupts(); } + +// enable interrupts +void sei() { interrupts(); } +*/ + +void HAL_adc_init() { + analog_init(); + while (ADC1_GC & ADC_GC_CAL) ; + while (ADC2_GC & ADC_GC_CAL) ; } -// ------------------------ -// FastIO -// ------------------------ - -bool is_output(pin_t pin) { - const struct digital_pin_bitband_and_config_table_struct *p; - p = digital_pin_to_info_PGM + pin; - return (*(p->reg + 1) & p->mask); +void HAL_clear_reset_source() { + uint32_t reset_source = SRC_SRSR; + SRC_SRSR = reset_source; } -// ------------------------ -// MarlinHAL Class -// ------------------------ - -void MarlinHAL::reboot() { _reboot_Teensyduino_(); } - -uint8_t MarlinHAL::get_reset_source() { +uint8_t HAL_get_reset_source() { switch (SRC_SRSR & 0xFF) { case 1: return RST_POWER_ON; break; case 2: return RST_SOFTWARE; break; @@ -92,92 +121,57 @@ uint8_t MarlinHAL::get_reset_source() { return 0; } -void MarlinHAL::clear_reset_source() { - uint32_t reset_source = SRC_SRSR; - SRC_SRSR = reset_source; -} +void HAL_reboot() { _reboot_Teensyduino_(); } -// ADC +#define __bss_end _ebss -int8_t MarlinHAL::adc_select; +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; -void MarlinHAL::adc_init() { - analog_init(); - while (ADC1_GC & ADC_GC_CAL) { /* wait */ } - while (ADC2_GC & ADC_GC_CAL) { /* wait */ } + // Doesn't work on Teensy 4.x + uint32_t freeMemory() { + uint32_t free_memory; + if ((uint32_t)__brkval == 0) + free_memory = ((uint32_t)&free_memory) - ((uint32_t)&__bss_end); + else + free_memory = ((uint32_t)&free_memory) - ((uint32_t)__brkval); + return free_memory; + } } -void MarlinHAL::adc_start(const pin_t adc_pin) { - static const uint8_t pin2sc1a[] = { - 0x07, // 0/A0 AD_B1_02 - 0x08, // 1/A1 AD_B1_03 - 0x0C, // 2/A2 AD_B1_07 - 0x0B, // 3/A3 AD_B1_06 - 0x06, // 4/A4 AD_B1_01 - 0x05, // 5/A5 AD_B1_00 - 0x0F, // 6/A6 AD_B1_10 - 0x00, // 7/A7 AD_B1_11 - 0x0D, // 8/A8 AD_B1_08 - 0x0E, // 9/A9 AD_B1_09 - 0x01, // 24/A10 AD_B0_12 - 0x02, // 25/A11 AD_B0_13 - 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 - 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 - 0x07, // 14/A0 AD_B1_02 - 0x08, // 15/A1 AD_B1_03 - 0x0C, // 16/A2 AD_B1_07 - 0x0B, // 17/A3 AD_B1_06 - 0x06, // 18/A4 AD_B1_01 - 0x05, // 19/A5 AD_B1_00 - 0x0F, // 20/A6 AD_B1_10 - 0x00, // 21/A7 AD_B1_11 - 0x0D, // 22/A8 AD_B1_08 - 0x0E, // 23/A9 AD_B1_09 - 0x01, // 24/A10 AD_B0_12 - 0x02, // 25/A11 AD_B0_13 - 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 - 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 - #ifdef ARDUINO_TEENSY41 - 0xFF, // 28 - 0xFF, // 29 - 0xFF, // 30 - 0xFF, // 31 - 0xFF, // 32 - 0xFF, // 33 - 0xFF, // 34 - 0xFF, // 35 - 0xFF, // 36 - 0xFF, // 37 - 0x81, // 38/A14 AD_B1_12 - only on ADC2, 1 - 0x82, // 39/A15 AD_B1_13 - only on ADC2, 2 - 0x09, // 40/A16 AD_B1_04 - 0x0A, // 41/A17 AD_B1_05 - #endif - }; +void HAL_adc_start_conversion(const uint8_t adc_pin) { const uint16_t pin = pin2sc1a[adc_pin]; if (pin == 0xFF) { - adc_select = -1; // Digital only + HAL_adc_select = -1; // Digital only } else if (pin & 0x80) { - adc_select = 1; + HAL_adc_select = 1; ADC2_HC0 = pin & 0x7F; } else { - adc_select = 0; + HAL_adc_select = 0; ADC1_HC0 = pin; } } -uint16_t MarlinHAL::adc_value() { - switch (adc_select) { +uint16_t HAL_adc_get_result() { + switch (HAL_adc_select) { case 0: - while (!(ADC1_HS & ADC_HS_COCO0)) { /* wait */ } + while (!(ADC1_HS & ADC_HS_COCO0)) ; // wait return ADC1_R0; case 1: - while (!(ADC2_HS & ADC_HS_COCO0)) { /* wait */ } + while (!(ADC2_HS & ADC_HS_COCO0)) ; // wait return ADC2_R0; } return 0; } +bool is_output(pin_t pin) { + const struct digital_pin_bitband_and_config_table_struct *p; + p = digital_pin_to_info_PGM + pin; + return (*(p->reg + 1) & p->mask); +} + #endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index b7a8070281634..2b730768a8025 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -41,6 +41,10 @@ #include "../../feature/ethernet.h" #endif +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + // ------------------------ // Defines // ------------------------ @@ -51,23 +55,7 @@ #define IS_TEENSY41 1 #endif -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -#undef sq -#define sq(x) ((x)*(x)) - -// Don't place string constants in PROGMEM -#undef PSTR -#define PSTR(str) ({static const char *data = (str); &data[0];}) - -// ------------------------ -// Serial ports -// ------------------------ - #include "../../core/serial_hook.h" - #define Serial0 Serial #define _DECLARE_SERIAL(X) \ typedef ForwardSerial1Class DefaultSerial##X; \ @@ -101,47 +89,41 @@ extern USBSerialType USBSerial; #endif #endif -// ------------------------ -// Types -// ------------------------ - -class libServo; -typedef libServo hal_servo_t; +#define HAL_SERVO_LIB libServo typedef int8_t pin_t; -// ------------------------ -// Interrupts -// ------------------------ - -#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); __disable_irq() -#define CRITICAL_SECTION_END() if (irqon) __enable_irq() - -// ------------------------ -// ADC -// ------------------------ - #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_ADC_FILTERED // turn off ADC oversampling +#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_primask()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() -// -// Pin Mapping for M42, M43, M226 -// -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) +#undef sq +#define sq(x) ((x)*(x)) -// FastIO -bool is_output(pin_t pin); +// Don't place string constants in PROGMEM +#undef PSTR +#define PSTR(str) ({static const char *data = (str); &data[0];}) -// ------------------------ -// Class Utilities -// ------------------------ +// Enable hooks into idle and setup for HAL +#define HAL_IDLETASK 1 +FORCE_INLINE void HAL_idletask() {} +FORCE_INLINE void HAL_init() {} + +// Clear reset reason +void HAL_clear_reset_source(); + +// Reset reason +uint8_t HAL_get_reset_source(); + +void HAL_reboot(); + +FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -152,66 +134,30 @@ extern "C" uint32_t freeMemory(); #pragma GCC diagnostic pop -// ------------------------ -// MarlinHAL Class -// ------------------------ - -class MarlinHAL { -public: - - // Earliest possible init, before setup() - MarlinHAL() {} - - static inline void init() {} // Called early in setup() - static inline void init_board() {} // Called less early in setup() - static void reboot(); // Restart the firmware from 0x0 - - static inline bool isr_state() { return !__get_primask(); } - static inline void isr_on() { __enable_irq(); } - static inline void isr_off() { __disable_irq(); } - - static inline void delay_ms(const int ms) { delay(ms); } - - // Tasks, called from idle() - static inline void idletask() {} - - // Reset - static uint8_t get_reset_source(); - static void clear_reset_source(); - - // Free SRAM - static inline int freeMemory() { return ::freeMemory(); } - - // - // ADC Methods - // +// ADC - static int8_t adc_select; +void HAL_adc_init(); - // Called by Temperature::init once at startup - static void adc_init(); +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_FILTERED // turn off ADC oversampling +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true - // Called by Temperature::init for each sensor at startup - static inline void adc_enable(const pin_t pin) {} +#define HAL_ANALOG_SELECT(pin) - // Begin ADC sampling on the given channel - static void adc_start(const pin_t pin); +void HAL_adc_start_conversion(const uint8_t adc_pin); +uint16_t HAL_adc_get_result(); - // Is the ADC ready for reading? - static inline bool adc_ready() { return true; } +// PWM - // The current value of the ADC register - static uint16_t adc_value(); +inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - /** - * Set the PWM duty cycle for the pin to the given value. - * No option to invert the duty cycle [default = false] - * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] - */ - static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { - analogWrite(pin, v); - } +// Pin Map -}; +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -extern MarlinHAL hal; +bool is_output(pin_t pin); diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 77fe0953d3bd5..81cf67f7bc08a 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -114,4 +114,4 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); //void HAL_timer_isr_epilogue(const uint8_t timer_num) {} -#define HAL_timer_isr_epilogue(T) NOOP +#define HAL_timer_isr_epilogue(T) diff --git a/Marlin/src/HAL/shared/HAL.cpp b/Marlin/src/HAL/shared/HAL.cpp deleted file mode 100644 index a5fe407188db4..0000000000000 --- a/Marlin/src/HAL/shared/HAL.cpp +++ /dev/null @@ -1,36 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -/** - * HAL/shared/HAL.cpp - */ - -#include "../../inc/MarlinConfig.h" - -MarlinHAL hal; - -#if ENABLED(SOFT_RESET_VIA_SERIAL) - - // Global for use by e_parser.h - void HAL_reboot() { hal.reboot(); } - -#endif diff --git a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp index 5d4ce89b2748e..bd85dbe7bd7ef 100644 --- a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp +++ b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp @@ -92,9 +92,9 @@ uint8_t L64XX_Marlin::transfer_single(uint8_t data, int16_t ss_pin) { // First device in chain has data sent last extDigitalWrite(ss_pin, LOW); - hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips) + DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips) const uint8_t data_out = L6470_SpiTransfer_Mode_3(data); - hal.isr_on(); // Enable interrupts + ENABLE_ISRS(); // Enable interrupts extDigitalWrite(ss_pin, HIGH); return data_out; @@ -107,9 +107,9 @@ uint8_t L64XX_Marlin::transfer_chain(uint8_t data, int16_t ss_pin, uint8_t chain extDigitalWrite(ss_pin, LOW); for (uint8_t i = L64XX::chain[0]; !L64xxManager.spi_abort && i >= 1; i--) { // Send data unless aborted - hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips) + DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips) const uint8_t temp = L6470_SpiTransfer_Mode_3(uint8_t(i == chain_position ? data : dSPIN_NOP)); - hal.isr_on(); // Enable interrupts + ENABLE_ISRS(); // Enable interrupts if (i == chain_position) data_out = temp; } diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 009edeba2f581..5132d07e8711f 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -790,7 +790,7 @@ void idle(bool no_stepper_sleep/*=false*/) { #endif // Run HAL idle tasks - hal.idletask(); + TERN_(HAL_IDLETASK, HAL_idletask()); // Check network connection TERN_(HAS_ETHERNET, ethernet.check()); @@ -929,7 +929,7 @@ void minkill(const bool steppers_off/*=false*/) { watchdog_refresh(); // Reboot the board - hal.reboot(); + HAL_reboot(); #else @@ -1041,7 +1041,7 @@ inline void tmc_standby_setup() { * • L64XX Stepper Drivers (SPI) * • Stepper Driver Reset: DISABLE * • TMC Stepper Drivers (SPI) - * • Run hal.init_board() for additional pins setup + * • Run BOARD_INIT if defined * • ESP WiFi * - Get the Reset Reason and report it * - Print startup messages and diagnostics @@ -1119,8 +1119,8 @@ void setup() { tmc_standby_setup(); // TMC Low Power Standby pins must be set early or they're not usable // Check startup - does nothing if bootloader sets MCUSR to 0 - const byte mcu = hal.get_reset_source(); - hal.clear_reset_source(); + const byte mcu = HAL_get_reset_source(); + HAL_clear_reset_source(); #if ENABLED(MARLIN_DEV_MODE) auto log_current_ms = [&](PGM_P const msg) { @@ -1181,20 +1181,23 @@ void setup() { JTAGSWD_RESET(); #endif - // Disable any hardware debug to free up pins for IO - #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) + #if EITHER(DISABLE_DEBUG, DISABLE_JTAG) delay(10); - SETUP_LOG("JTAGSWD_DISABLE"); - JTAGSWD_DISABLE(); - #elif ENABLED(DISABLE_JTAG) && defined(JTAG_DISABLE) - delay(10); - SETUP_LOG("JTAG_DISABLE"); - JTAG_DISABLE(); + // Disable any hardware debug to free up pins for IO + #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) + SETUP_LOG("JTAGSWD_DISABLE"); + JTAGSWD_DISABLE(); + #elif defined(JTAG_DISABLE) + SETUP_LOG("JTAG_DISABLE"); + JTAG_DISABLE(); + #else + #error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board." + #endif #endif TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime - SETUP_RUN(hal.init()); + SETUP_RUN(HAL_init()); // Init and disable SPI thermocouples; this is still needed #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0)) @@ -1240,16 +1243,19 @@ void setup() { SETUP_RUN(tmc_init_cs_pins()); #endif - SETUP_RUN(hal.init_board()); + #ifdef BOARD_INIT + SETUP_LOG("BOARD_INIT"); + BOARD_INIT(); + #endif SETUP_RUN(esp_wifi_init()); // Report Reset Reason - if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP); - if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET); + if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP); + if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET); if (mcu & RST_BROWN_OUT) SERIAL_ECHOLNPGM(STR_BROWNOUT_RESET); - if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET); - if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); + if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET); + if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); // Identify myself as Marlin x.x.x SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION); @@ -1260,7 +1266,7 @@ void setup() { ); #endif SERIAL_ECHO_MSG(" Compiled: " __DATE__); - SERIAL_ECHO_MSG(STR_FREE_MEMORY, hal.freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); + SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); // Some HAL need precise delay adjustment calibrate_delay_loop(); @@ -1532,7 +1538,7 @@ void setup() { #endif #if ENABLED(USE_WATCHDOG) - SETUP_RUN(watchdog_init()); // Reinit watchdog after hal.get_reset_source call + SETUP_RUN(watchdog_init()); // Reinit watchdog after HAL_get_reset_source call #endif #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index a58cb66affc78..59832fd6edd7c 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -69,7 +69,7 @@ void CaseLight::update(const bool sflag) { #if CASELIGHT_USES_BRIGHTNESS if (pin_is_pwm()) - hal.set_pwm_duty(pin_t(CASE_LIGHT_PIN), ( + set_pwm_duty(pin_t(CASE_LIGHT_PIN), ( #if CASE_LIGHT_MAX_PWM == 255 n10ct #else diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index f42bf52ae40a0..59ba665e11144 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -76,7 +76,7 @@ void ControllerFan::update() { thermalManager.soft_pwm_controller_speed = speed; #else if (PWM_PIN(CONTROLLER_FAN_PIN)) - hal.set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); + set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); else WRITE(CONTROLLER_FAN_PIN, speed > 0); #endif diff --git a/Marlin/src/feature/e_parser.h b/Marlin/src/feature/e_parser.h index fda1ba144bc4d..1dee0cf7550c1 100644 --- a/Marlin/src/feature/e_parser.h +++ b/Marlin/src/feature/e_parser.h @@ -41,9 +41,7 @@ extern bool wait_for_user, wait_for_heatup; void quickresume_stepper(); #endif -#if ENABLED(SOFT_RESET_VIA_SERIAL) - void HAL_reboot(); -#endif +void HAL_reboot(); class EmergencyParser { diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 0a4b5114769de..17d790b8cc9a2 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -123,7 +123,7 @@ void LEDLights::set_color(const LEDColor &incol // If the pins can do PWM then their intensity will be set. #define _UPDATE_RGBW(C,c) do { \ if (PWM_PIN(RGB_LED_##C##_PIN)) \ - hal.set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \ + set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \ else \ WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \ }while(0) diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 2840a92c58383..cde2b47d90aad 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -66,10 +66,10 @@ void SpindleLaser::init() { #endif #if ENABLED(SPINDLE_LASER_USE_PWM) SET_PWM(SPINDLE_LASER_PWM_PIN); - hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed + set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed #endif #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY) - hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); + set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY); #endif #if ENABLED(AIR_EVACUATION) @@ -90,10 +90,10 @@ void SpindleLaser::init() { * @param ocr Power value */ void SpindleLaser::_set_ocr(const uint8_t ocr) { - #if BOTH(NEEDS_HARDWARE_PWM, HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY - hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); + #if NEEDS_HARDWARE_PWM && SPINDLE_LASER_FREQUENCY + set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); #endif - hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); + set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); } void SpindleLaser::set_ocr(const uint8_t ocr) { diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 0415c9c8bb1ca..95d60ae486748 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -103,7 +103,7 @@ class SpindleLaser { static void init(); #if ENABLED(MARLIN_DEV_MODE) - static inline void refresh_frequency() { hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } + static inline void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } #endif // Modifying this function should update everywhere diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 807681831723d..77c0ccc49b0f8 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -126,10 +126,10 @@ void GcodeSuite::M42() { extDigitalWrite(pin, pin_status); #ifdef ARDUINO_ARCH_STM32 - // A simple I/O will be set to 0 by hal.set_pwm_duty() + // A simple I/O will be set to 0 by set_pwm_duty() if (pin_status <= 1 && !PWM_PIN(pin)) return; #endif - hal.set_pwm_duty(pin, pin_status); + set_pwm_duty(pin, pin_status); } #endif // DIRECT_PIN_CONTROL diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index 2dd1de00013b4..204455e65ec60 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -38,7 +38,7 @@ #include "../sd/cardreader.h" #include "../MarlinCore.h" // for kill -void dump_delay_accuracy_check(); +extern void dump_delay_accuracy_check(); /** * Dn: G-code for development and testing @@ -54,7 +54,7 @@ void GcodeSuite::D(const int16_t dcode) { for (;;) { /* loop forever (watchdog reset) */ } case 0: - hal.reboot(); + HAL_reboot(); break; case 10: @@ -74,7 +74,7 @@ void GcodeSuite::D(const int16_t dcode) { settings.reset(); settings.save(); #endif - hal.reboot(); + HAL_reboot(); } break; case 2: { // D2 Read / Write SRAM @@ -189,12 +189,12 @@ void GcodeSuite::D(const int16_t dcode) { SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")"); thermalManager.disable_all_heaters(); delay(1000); // Allow time to print - hal.isr_off(); + DISABLE_ISRS(); // Use a low-level delay that does not rely on interrupts to function // Do not spin forever, to avoid thermal risks if heaters are enabled and // watchdog does not work. for (int i = 10000; i--;) DELAY_US(1000UL); - hal.isr_on(); + ENABLE_ISRS(); SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset."); } break; diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 6ee58f769bde3..c8ac48f7cff53 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3850,10 +3850,3 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #undef _TEST_PWM #undef _LINEAR_AXES_STR #undef _LOGICAL_AXES_STR - -// JTAG support in the HAL -#if ENABLED(DISABLE_DEBUG) && !defined(JTAGSWD_DISABLE) - #error "DISABLE_DEBUG is not supported for the selected MCU/Board." -#elif ENABLED(DISABLE_JTAG) && !defined(JTAG_DISABLE) - #error "DISABLE_JTAG is not supported for the selected MCU/Board." -#endif diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 61db2db9209b0..59c74148adef3 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -282,9 +282,9 @@ void MarlinUI::init_lcd() { #if PIN_EXISTS(LCD_RESET) // Perform a clean hardware reset with needed delays OUT_WRITE(LCD_RESET_PIN, LOW); - hal.delay_ms(5); + _delay_ms(5); WRITE(LCD_RESET_PIN, HIGH); - hal.delay_ms(5); + _delay_ms(5); u8g.begin(); #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 64a65bb6863be..d1a9ba7077fda 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -2149,7 +2149,7 @@ void RebootPrinter() { thermalManager.disable_all_heaters(); planner.finish_and_disable(); DWIN_RebootScreen(); - hal.reboot(); + HAL_reboot(); } void Goto_InfoMenu(){ diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index df6a857803508..7a2cefdd4cea3 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -1345,7 +1345,7 @@ void Endstops::update() { ES_REPORT_CHANGE(K_MAX); #endif SERIAL_ECHOLNPGM("\n"); - hal.set_pwm_duty(pin_t(LED_PIN), local_LED_status); + set_pwm_duty(pin_t(LED_PIN), local_LED_status); local_LED_status ^= 255; old_live_state_local = live_state_local; } diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 752834c6ab996..45ccdd1702ef8 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1264,7 +1264,7 @@ void Planner::recalculate() { #if ENABLED(FAN_SOFT_PWM) #define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F); #else - #define _FAN_SET(F) hal.set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); + #define _FAN_SET(F) set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); #endif #define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0) @@ -1400,8 +1400,8 @@ void Planner::check_axes_activity() { TERN_(AUTOTEMP, autotemp_task()); #if ENABLED(BARICUDA) - TERN_(HAS_HEATER_1, hal.set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); - TERN_(HAS_HEATER_2, hal.set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); + TERN_(HAS_HEATER_1, set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); + TERN_(HAS_HEATER_2, set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); #endif } diff --git a/Marlin/src/module/servo.cpp b/Marlin/src/module/servo.cpp index 96d5ba9da837e..231efe84e1f2c 100644 --- a/Marlin/src/module/servo.cpp +++ b/Marlin/src/module/servo.cpp @@ -30,7 +30,7 @@ #include "servo.h" -hal_servo_t servo[NUM_SERVOS]; +HAL_SERVO_LIB servo[NUM_SERVOS]; #if ENABLED(EDITABLE_SERVO_ANGLES) uint16_t servo_angles[NUM_SERVOS][2]; diff --git a/Marlin/src/module/servo.h b/Marlin/src/module/servo.h index cd55a317a2751..73dbbdddb7297 100644 --- a/Marlin/src/module/servo.h +++ b/Marlin/src/module/servo.h @@ -112,5 +112,5 @@ #define MOVE_SERVO(I, P) servo[I].move(P) #define DETACH_SERVO(I) servo[I].detach() -extern hal_servo_t servo[NUM_SERVOS]; +extern HAL_SERVO_LIB servo[NUM_SERVOS]; void servo_init(); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 0f47d66791c4d..c100051f98087 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1474,7 +1474,7 @@ void Stepper::isr() { #ifndef __AVR__ // Disable interrupts, to avoid ISR preemption while we reprogram the period // (AVR enters the ISR with global interrupts disabled, so no need to do it here) - hal.isr_off(); + DISABLE_ISRS(); #endif // Program timer compare for the maximum period, so it does NOT @@ -1492,7 +1492,7 @@ void Stepper::isr() { hal_timer_t min_ticks; do { // Enable ISRs to reduce USART processing latency - hal.isr_on(); + ENABLE_ISRS(); if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses @@ -1576,7 +1576,7 @@ void Stepper::isr() { * is less than the current count due to something preempting between the * read and the write of the new period value). */ - hal.isr_off(); + DISABLE_ISRS(); /** * Get the current tick value + margin @@ -1611,7 +1611,7 @@ void Stepper::isr() { HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(next_isr_ticks)); // Don't forget to finally reenable interrupts - hal.isr_on(); + ENABLE_ISRS(); } #if MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE @@ -3261,7 +3261,7 @@ void Stepper::report_positions() { #elif HAS_MOTOR_CURRENT_PWM - #define _WRITE_CURRENT_PWM(P) hal.set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) + #define _WRITE_CURRENT_PWM(P) set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) switch (driver) { case 0: #if PIN_EXISTS(MOTOR_CURRENT_PWM_X) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 1960dc5d9b526..dccdc55034fd0 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -326,7 +326,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0) #endif #if ENABLED(FAST_PWM_FAN) - #define SET_FAST_PWM_FREQ(P) hal.set_pwm_frequency(pin_t(P), FAST_PWM_FAN_FREQUENCY) + #define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY) #else #define SET_FAST_PWM_FREQ(P) NOOP #endif @@ -813,7 +813,7 @@ volatile bool Temperature::raw_temps_ready = false; } // Run HAL idle tasks - hal.idletask(); + TERN_(HAL_IDLETASK, HAL_idletask()); // Run UI update TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update()); @@ -912,7 +912,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #define _UPDATE_AUTO_FAN(P,D,A) do{ \ if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \ - hal.set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ + set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ else \ WRITE(P##_AUTO_FAN_PIN, D); \ }while(0) @@ -2326,73 +2326,73 @@ void Temperature::init() { TERN_(HAS_MAXTC_SW_SPI, max_tc_spi.init()); - hal.adc_init(); + HAL_adc_init(); #if HAS_TEMP_ADC_0 - hal.adc_enable(TEMP_0_PIN); + HAL_ANALOG_SELECT(TEMP_0_PIN); #endif #if HAS_TEMP_ADC_1 - hal.adc_enable(TEMP_1_PIN); + HAL_ANALOG_SELECT(TEMP_1_PIN); #endif #if HAS_TEMP_ADC_2 - hal.adc_enable(TEMP_2_PIN); + HAL_ANALOG_SELECT(TEMP_2_PIN); #endif #if HAS_TEMP_ADC_3 - hal.adc_enable(TEMP_3_PIN); + HAL_ANALOG_SELECT(TEMP_3_PIN); #endif #if HAS_TEMP_ADC_4 - hal.adc_enable(TEMP_4_PIN); + HAL_ANALOG_SELECT(TEMP_4_PIN); #endif #if HAS_TEMP_ADC_5 - hal.adc_enable(TEMP_5_PIN); + HAL_ANALOG_SELECT(TEMP_5_PIN); #endif #if HAS_TEMP_ADC_6 - hal.adc_enable(TEMP_6_PIN); + HAL_ANALOG_SELECT(TEMP_6_PIN); #endif #if HAS_TEMP_ADC_7 - hal.adc_enable(TEMP_7_PIN); + HAL_ANALOG_SELECT(TEMP_7_PIN); #endif #if HAS_JOY_ADC_X - hal.adc_enable(JOY_X_PIN); + HAL_ANALOG_SELECT(JOY_X_PIN); #endif #if HAS_JOY_ADC_Y - hal.adc_enable(JOY_Y_PIN); + HAL_ANALOG_SELECT(JOY_Y_PIN); #endif #if HAS_JOY_ADC_Z - hal.adc_enable(JOY_Z_PIN); + HAL_ANALOG_SELECT(JOY_Z_PIN); #endif #if HAS_JOY_ADC_EN SET_INPUT_PULLUP(JOY_EN_PIN); #endif #if HAS_TEMP_ADC_BED - hal.adc_enable(TEMP_BED_PIN); + HAL_ANALOG_SELECT(TEMP_BED_PIN); #endif #if HAS_TEMP_ADC_CHAMBER - hal.adc_enable(TEMP_CHAMBER_PIN); + HAL_ANALOG_SELECT(TEMP_CHAMBER_PIN); #endif #if HAS_TEMP_ADC_COOLER - hal.adc_enable(TEMP_COOLER_PIN); + HAL_ANALOG_SELECT(TEMP_COOLER_PIN); #endif #if HAS_TEMP_ADC_PROBE - hal.adc_enable(TEMP_PROBE_PIN); + HAL_ANALOG_SELECT(TEMP_PROBE_PIN); #endif #if HAS_TEMP_ADC_BOARD - hal.adc_enable(TEMP_BOARD_PIN); + HAL_ANALOG_SELECT(TEMP_BOARD_PIN); #endif #if HAS_TEMP_ADC_REDUNDANT - hal.adc_enable(TEMP_REDUNDANT_PIN); + HAL_ANALOG_SELECT(TEMP_REDUNDANT_PIN); #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - hal.adc_enable(FILWIDTH_PIN); + HAL_ANALOG_SELECT(FILWIDTH_PIN); #endif #if HAS_ADC_BUTTONS - hal.adc_enable(ADC_KEYPAD_PIN); + HAL_ANALOG_SELECT(ADC_KEYPAD_PIN); #endif #if ENABLED(POWER_MONITOR_CURRENT) - hal.adc_enable(POWER_MONITOR_CURRENT_PIN); + HAL_ANALOG_SELECT(POWER_MONITOR_CURRENT_PIN); #endif #if ENABLED(POWER_MONITOR_VOLTAGE) - hal.adc_enable(POWER_MONITOR_VOLTAGE_PIN); + HAL_ANALOG_SELECT(POWER_MONITOR_VOLTAGE_PIN); #endif HAL_timer_start(MF_TIMER_TEMP, TEMP_TIMER_FREQUENCY); @@ -3333,8 +3333,8 @@ void Temperature::isr() { * This gives each ADC 0.9765ms to charge up. */ #define ACCUMULATE_ADC(obj) do{ \ - if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; \ - else obj.sample(hal.adc_value()); \ + if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; \ + else obj.sample(HAL_READ_ADC()); \ }while(0) ADCSensorState next_sensor_state = adc_sensor_state < SensorsReady ? (ADCSensorState)(int(adc_sensor_state) + 1) : StartSampling; @@ -3366,115 +3366,115 @@ void Temperature::isr() { break; #if HAS_TEMP_ADC_0 - case PrepareTemp_0: hal.adc_start(TEMP_0_PIN); break; + case PrepareTemp_0: HAL_START_ADC(TEMP_0_PIN); break; case MeasureTemp_0: ACCUMULATE_ADC(temp_hotend[0]); break; #endif #if HAS_TEMP_ADC_BED - case PrepareTemp_BED: hal.adc_start(TEMP_BED_PIN); break; + case PrepareTemp_BED: HAL_START_ADC(TEMP_BED_PIN); break; case MeasureTemp_BED: ACCUMULATE_ADC(temp_bed); break; #endif #if HAS_TEMP_ADC_CHAMBER - case PrepareTemp_CHAMBER: hal.adc_start(TEMP_CHAMBER_PIN); break; + case PrepareTemp_CHAMBER: HAL_START_ADC(TEMP_CHAMBER_PIN); break; case MeasureTemp_CHAMBER: ACCUMULATE_ADC(temp_chamber); break; #endif #if HAS_TEMP_ADC_COOLER - case PrepareTemp_COOLER: hal.adc_start(TEMP_COOLER_PIN); break; + case PrepareTemp_COOLER: HAL_START_ADC(TEMP_COOLER_PIN); break; case MeasureTemp_COOLER: ACCUMULATE_ADC(temp_cooler); break; #endif #if HAS_TEMP_ADC_PROBE - case PrepareTemp_PROBE: hal.adc_start(TEMP_PROBE_PIN); break; + case PrepareTemp_PROBE: HAL_START_ADC(TEMP_PROBE_PIN); break; case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break; #endif #if HAS_TEMP_ADC_BOARD - case PrepareTemp_BOARD: hal.adc_start(TEMP_BOARD_PIN); break; + case PrepareTemp_BOARD: HAL_START_ADC(TEMP_BOARD_PIN); break; case MeasureTemp_BOARD: ACCUMULATE_ADC(temp_board); break; #endif #if HAS_TEMP_ADC_REDUNDANT - case PrepareTemp_REDUNDANT: hal.adc_start(TEMP_REDUNDANT_PIN); break; + case PrepareTemp_REDUNDANT: HAL_START_ADC(TEMP_REDUNDANT_PIN); break; case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break; #endif #if HAS_TEMP_ADC_1 - case PrepareTemp_1: hal.adc_start(TEMP_1_PIN); break; + case PrepareTemp_1: HAL_START_ADC(TEMP_1_PIN); break; case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break; #endif #if HAS_TEMP_ADC_2 - case PrepareTemp_2: hal.adc_start(TEMP_2_PIN); break; + case PrepareTemp_2: HAL_START_ADC(TEMP_2_PIN); break; case MeasureTemp_2: ACCUMULATE_ADC(temp_hotend[2]); break; #endif #if HAS_TEMP_ADC_3 - case PrepareTemp_3: hal.adc_start(TEMP_3_PIN); break; + case PrepareTemp_3: HAL_START_ADC(TEMP_3_PIN); break; case MeasureTemp_3: ACCUMULATE_ADC(temp_hotend[3]); break; #endif #if HAS_TEMP_ADC_4 - case PrepareTemp_4: hal.adc_start(TEMP_4_PIN); break; + case PrepareTemp_4: HAL_START_ADC(TEMP_4_PIN); break; case MeasureTemp_4: ACCUMULATE_ADC(temp_hotend[4]); break; #endif #if HAS_TEMP_ADC_5 - case PrepareTemp_5: hal.adc_start(TEMP_5_PIN); break; + case PrepareTemp_5: HAL_START_ADC(TEMP_5_PIN); break; case MeasureTemp_5: ACCUMULATE_ADC(temp_hotend[5]); break; #endif #if HAS_TEMP_ADC_6 - case PrepareTemp_6: hal.adc_start(TEMP_6_PIN); break; + case PrepareTemp_6: HAL_START_ADC(TEMP_6_PIN); break; case MeasureTemp_6: ACCUMULATE_ADC(temp_hotend[6]); break; #endif #if HAS_TEMP_ADC_7 - case PrepareTemp_7: hal.adc_start(TEMP_7_PIN); break; + case PrepareTemp_7: HAL_START_ADC(TEMP_7_PIN); break; case MeasureTemp_7: ACCUMULATE_ADC(temp_hotend[7]); break; #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - case Prepare_FILWIDTH: hal.adc_start(FILWIDTH_PIN); break; + case Prepare_FILWIDTH: HAL_START_ADC(FILWIDTH_PIN); break; case Measure_FILWIDTH: - if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state - else filwidth.accumulate(hal.adc_value()); + if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state + else filwidth.accumulate(HAL_READ_ADC()); break; #endif #if ENABLED(POWER_MONITOR_CURRENT) case Prepare_POWER_MONITOR_CURRENT: - hal.adc_start(POWER_MONITOR_CURRENT_PIN); + HAL_START_ADC(POWER_MONITOR_CURRENT_PIN); break; case Measure_POWER_MONITOR_CURRENT: - if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state - else power_monitor.add_current_sample(hal.adc_value()); + if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state + else power_monitor.add_current_sample(HAL_READ_ADC()); break; #endif #if ENABLED(POWER_MONITOR_VOLTAGE) case Prepare_POWER_MONITOR_VOLTAGE: - hal.adc_start(POWER_MONITOR_VOLTAGE_PIN); + HAL_START_ADC(POWER_MONITOR_VOLTAGE_PIN); break; case Measure_POWER_MONITOR_VOLTAGE: - if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state - else power_monitor.add_voltage_sample(hal.adc_value()); + if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state + else power_monitor.add_voltage_sample(HAL_READ_ADC()); break; #endif #if HAS_JOY_ADC_X - case PrepareJoy_X: hal.adc_start(JOY_X_PIN); break; + case PrepareJoy_X: HAL_START_ADC(JOY_X_PIN); break; case MeasureJoy_X: ACCUMULATE_ADC(joystick.x); break; #endif #if HAS_JOY_ADC_Y - case PrepareJoy_Y: hal.adc_start(JOY_Y_PIN); break; + case PrepareJoy_Y: HAL_START_ADC(JOY_Y_PIN); break; case MeasureJoy_Y: ACCUMULATE_ADC(joystick.y); break; #endif #if HAS_JOY_ADC_Z - case PrepareJoy_Z: hal.adc_start(JOY_Z_PIN); break; + case PrepareJoy_Z: HAL_START_ADC(JOY_Z_PIN); break; case MeasureJoy_Z: ACCUMULATE_ADC(joystick.z); break; #endif @@ -3482,12 +3482,12 @@ void Temperature::isr() { #ifndef ADC_BUTTON_DEBOUNCE_DELAY #define ADC_BUTTON_DEBOUNCE_DELAY 16 #endif - case Prepare_ADC_KEY: hal.adc_start(ADC_KEYPAD_PIN); break; + case Prepare_ADC_KEY: HAL_START_ADC(ADC_KEYPAD_PIN); break; case Measure_ADC_KEY: - if (!hal.adc_ready()) + if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // redo this state else if (ADCKey_count < ADC_BUTTON_DEBOUNCE_DELAY) { - raw_ADCKey_value = hal.adc_value(); + raw_ADCKey_value = HAL_READ_ADC(); if (raw_ADCKey_value <= 900UL * HAL_ADC_RANGE / 1024UL) { NOMORE(current_ADCKey_raw, raw_ADCKey_value); ADCKey_count++; diff --git a/ini/native.ini b/ini/native.ini index eba34afc83948..fe5fe3a5d05ad 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -34,14 +34,14 @@ src_filter = ${common.default_src_filter} + [simulator_common] platform = native framework = -build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/u8g +build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/include -IMarlin/src/HAL/NATIVE_SIM/u8g src_build_flags = -Wall -Wno-expansion-to-defined -Wcast-align release_flags = -g0 -O3 -flto debug_build_flags = -fstack-protector-strong -g -g3 -ggdb lib_compat_mode = off src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} - MarlinSimUI=https://github.com/thinkyhead/MarlinSimUI/archive/updated_marlin_hal_2093.zip + MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/master.zip Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip extra_scripts = ${common.extra_scripts} From 7762df7251f1da3be2933670084b416d4a06c89f Mon Sep 17 00:00:00 2001 From: EvilGremlin <22657714+EvilGremlin@users.noreply.github.com> Date: Sun, 26 Dec 2021 09:46:13 +0300 Subject: [PATCH 197/273] =?UTF-8?q?=F0=9F=94=A7=20Check=20Chiron=20LCD=20r?= =?UTF-8?q?equirements=20(#23353)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-Authored-By: EvilGremlin <22657714+EvilGremlin@users.noreply.github.com> --- Marlin/src/inc/SanityCheck.h | 14 ++++++++++++++ .../src/lcd/extui/anycubic_chiron/chiron_tft.cpp | 2 +- .../ftdi_eve_touch_ui/generic/about_screen.cpp | 4 ++-- 3 files changed, 17 insertions(+), 3 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index c8ac48f7cff53..ab1a6adec5601 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2765,6 +2765,20 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Please select only one of CHIRON_TFT_STANDARD or CHIRON_TFT_NEW." #endif +#if ENABLED(ANYCUBIC_LCD_CHIRON) + #if !defined(BEEPER_PIN) + #error "ANYCUBIC_LCD_CHIRON requires BEEPER_PIN" + #elif DISABLED(SDSUPPORT) + #error "ANYCUBIC_LCD_CHIRON requires SDSUPPORT" + #elif TEMP_SENSOR_BED == 0 + #error "ANYCUBIC_LCD_CHIRON requires heatbed (TEMP_SENSOR_BED)" + #elif NONE(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL, MESH_BED_LEVELING) + #error "ANYCUBIC_LCD_CHIRON requires one of: AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL or MESH_BED_LEVELING" + #elif DISABLED(BABYSTEPPING) + #error "ANYCUBIC_LCD_CHIRON requires BABYSTEPPING" + #endif +#endif + #if EITHER(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 diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index 9f558e3a98677..6db5972fa70f1 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -243,7 +243,7 @@ void ChironTFT::StatusChange(const char * const msg) { case AC_printer_probing: { // If probing completes ok save the mesh and park // Ignore the custom machine name - if (strcmp_P(msg + strlen(CUSTOM_MACHINE_NAME), MARLIN_msg_ready) == 0) { + if (strcmp_P(msg + strlen(MACHINE_NAME), MARLIN_msg_ready) == 0) { injectCommands(F("M500\nG27")); SendtoTFTLN(AC_msg_probing_complete); printer_state = AC_printer_idle; 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 6cb85e47c49c8..43e5c333651a3 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 @@ -69,8 +69,8 @@ void AboutScreen::onRedraw(draw_mode_t) { #endif draw_text_box(cmd, HEADING_POS, - #ifdef CUSTOM_MACHINE_NAME - F(CUSTOM_MACHINE_NAME) + #ifdef MACHINE_NAME + F(MACHINE_NAME) #else GET_TEXT_F(MSG_ABOUT_TOUCH_PANEL_1) #endif From 56ac68172796d03c15235738fcb234c48167d807 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 26 Dec 2021 03:20:29 -0600 Subject: [PATCH 198/273] =?UTF-8?q?=F0=9F=8E=A8=20Pins=20and=20SDIO=20clea?= =?UTF-8?q?nup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../{Sd2Card_sdio_stm32duino.cpp => sdio.cpp} | 10 +- Marlin/src/HAL/STM32/sdio.h | 29 +++ Marlin/src/pins/stm32f4/pins_ANET_ET4.h | 15 +- .../src/pins/stm32f4/pins_BLACK_STM32F407VE.h | 18 +- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 7 - .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 10 - .../src/pins/stm32f4/pins_STEVAL_3DP001V1.h | 219 +++++++++--------- 7 files changed, 147 insertions(+), 161 deletions(-) rename Marlin/src/HAL/STM32/{Sd2Card_sdio_stm32duino.cpp => sdio.cpp} (98%) create mode 100644 Marlin/src/HAL/STM32/sdio.h diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/sdio.cpp similarity index 98% rename from Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp rename to Marlin/src/HAL/STM32/sdio.cpp index 54e1820c78e6b..18b4434dfa73e 100644 --- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp +++ b/Marlin/src/HAL/STM32/sdio.cpp @@ -28,6 +28,8 @@ #if ENABLED(SDIO_SUPPORT) +#include "sdio.h" + #include #include @@ -49,14 +51,6 @@ #error "SDIO only supported with STM32F103xE, STM32F103xG, STM32F4xx, or STM32F7xx." #endif -// Fixed -#define SDIO_D0_PIN PC8 -#define SDIO_D1_PIN PC9 -#define SDIO_D2_PIN PC10 -#define SDIO_D3_PIN PC11 -#define SDIO_CK_PIN PC12 -#define SDIO_CMD_PIN PD2 - SD_HandleTypeDef hsd; // create SDIO structure // F4 supports one DMA for RX and another for TX, but Marlin will never // do read and write at same time, so we use the same DMA for both. diff --git a/Marlin/src/HAL/STM32/sdio.h b/Marlin/src/HAL/STM32/sdio.h new file mode 100644 index 0000000000000..cf5539c3c76d8 --- /dev/null +++ b/Marlin/src/HAL/STM32/sdio.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define SDIO_D0_PIN PC8 +#define SDIO_D1_PIN PC9 +#define SDIO_D2_PIN PC10 +#define SDIO_D3_PIN PC11 +#define SDIO_CK_PIN PC12 +#define SDIO_CMD_PIN PD2 diff --git a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h index eb3af65f32eb7..43aefe97f51df 100644 --- a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h +++ b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h @@ -203,19 +203,12 @@ #if ENABLED(SDSUPPORT) - #define SDIO_D0_PIN PC8 - #define SDIO_D1_PIN PC9 - #define SDIO_D2_PIN PC10 - #define SDIO_D3_PIN PC11 - #define SDIO_CK_PIN PC12 - #define SDIO_CMD_PIN PD2 - #if DISABLED(SDIO_SUPPORT) #define SOFTWARE_SPI - #define SDSS SDIO_D3_PIN - #define SD_SCK_PIN SDIO_CK_PIN - #define SD_MISO_PIN SDIO_D0_PIN - #define SD_MOSI_PIN SDIO_CMD_PIN + #define SDSS PC11 + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 #endif #ifndef SD_DETECT_PIN diff --git a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h index d8a83bef3a891..061680aa79cd0 100644 --- a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h +++ b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h @@ -140,25 +140,17 @@ // // Onboard SD support // -#define SDIO_D0_PIN PC8 -#define SDIO_D1_PIN PC9 -#define SDIO_D2_PIN PC10 -#define SDIO_D3_PIN PC11 -#define SDIO_CK_PIN PC12 -#define SDIO_CMD_PIN PD2 - #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif #if SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD - - #ifndef SDIO_SUPPORT + #if DISABLED(SDIO_SUPPORT) #define SOFTWARE_SPI // Use soft SPI for onboard SD - #define SDSS SDIO_D3_PIN - #define SD_SCK_PIN SDIO_CK_PIN - #define SD_MISO_PIN SDIO_D0_PIN - #define SD_MOSI_PIN SDIO_CMD_PIN + #define SDSS PC11 + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index d1f38f5c8098f..e63b534effa5f 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -338,13 +338,6 @@ #if SD_CONNECTION_IS(ONBOARD) #define SDIO_SUPPORT // Use SDIO for onboard SD - #define SDIO_D0_PIN PC8 - #define SDIO_D1_PIN PC9 - #define SDIO_D2_PIN PC10 - #define SDIO_D3_PIN PC11 - #define SDIO_CK_PIN PC12 - #define SDIO_CMD_PIN PD2 - //#define SDIO_CLOCK 48000000 #define SD_DETECT_PIN PC4 #elif SD_CONNECTION_IS(CUSTOM_CABLE) 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 196ca46319989..6d23bc8b208eb 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 @@ -365,24 +365,14 @@ // Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 // #if SD_CONNECTION_IS(LCD) - #define SDSS EXP2_07_PIN #define SD_SS_PIN SDSS #define SD_SCK_PIN EXP2_09_PIN #define SD_MISO_PIN EXP2_10_PIN #define SD_MOSI_PIN EXP2_05_PIN #define SD_DETECT_PIN EXP2_04_PIN - #elif SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT // Use SDIO for onboard SD - #define SDIO_D0_PIN PC8 - #define SDIO_D1_PIN PC9 - #define SDIO_D2_PIN PC10 - #define SDIO_D3_PIN PC11 - #define SDIO_CK_PIN PC12 - #define SDIO_CMD_PIN PD2 - #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif diff --git a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h index 7ccb57e2387b1..98d222087839c 100644 --- a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h +++ b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h @@ -48,13 +48,13 @@ // // Limit Switches // -#define X_MIN_PIN 39 // PD8 X_STOP -#define Y_MIN_PIN 40 // PD9 Y_STOP -#define Z_MIN_PIN 41 // PD10 Z_STOP +#define X_MIN_PIN PD8 // X_STOP +#define Y_MIN_PIN PD9 // Y_STOP +#define Z_MIN_PIN PD10 // Z_STOP -#define X_MAX_PIN 44 // PD0 W_STOP -#define Y_MAX_PIN 43 // PA8 V_STOP -#define Z_MAX_PIN 42 // PD11 U_STOP +#define X_MAX_PIN PD0 // W_STOP +#define Y_MAX_PIN PA8 // V_STOP +#define Z_MAX_PIN PD11 // U_STOP // // Z Probe (when not Z_MIN_PIN) @@ -66,64 +66,64 @@ // // Filament runout // -//#define FIL_RUNOUT_PIN 53 // PA3 BED_THE +//#define FIL_RUNOUT_PIN PA3 // BED_THE // // Steppers // -#define X_STEP_PIN 61 // PE14 X_PWM -#define X_DIR_PIN 62 // PE15 X_DIR -#define X_ENABLE_PIN 60 // PE13 X_RES -#define X_CS_PIN 16 // PA4 SPI_CS +#define X_STEP_PIN PE14 // X_PWM +#define X_DIR_PIN PE15 // X_DIR +#define X_ENABLE_PIN PE13 // X_RES +#define X_CS_PIN PA4 // SPI_CS -#define Y_STEP_PIN 64 // PB10 Y_PWM -#define Y_DIR_PIN 65 // PE9 Y_DIR -#define Y_ENABLE_PIN 63 // PE10 Y_RES -#define Y_CS_PIN 16 // PA4 SPI_CS +#define Y_STEP_PIN PB10 // Y_PWM +#define Y_DIR_PIN PE9 // Y_DIR +#define Y_ENABLE_PIN PE10 // Y_RES +#define Y_CS_PIN PA4 // SPI_CS -#define Z_STEP_PIN 67 // PC6 Z_PWM -#define Z_DIR_PIN 68 // PC0 Z_DIR -#define Z_ENABLE_PIN 66 // PC15 Z_RES -#define Z_CS_PIN 16 // PA4 SPI_CS +#define Z_STEP_PIN PC6 // Z_PWM +#define Z_DIR_PIN PC0 // Z_DIR +#define Z_ENABLE_PIN PC15 // Z_RES +#define Z_CS_PIN PA4 // SPI_CS -#define E0_STEP_PIN 71 // PD12 E1_PW -#define E0_DIR_PIN 70 // PC13 E1_DIR -#define E0_ENABLE_PIN 69 // PC14 E1_RE -#define E0_CS_PIN 16 // PA4 SPI_CS +#define E0_STEP_PIN PD12 // E1_PW +#define E0_DIR_PIN PC13 // E1_DIR +#define E0_ENABLE_PIN PC14 // E1_RE +#define E0_CS_PIN PA4 // SPI_CS -#define E1_STEP_PIN 73 // PE5 E2_PWM -#define E1_DIR_PIN 74 // PE6 E2_DIR -#define E1_ENABLE_PIN 72 // PE4 E2_RESE -#define E1_CS_PIN 16 // PA4 SPI_CS +#define E1_STEP_PIN PE5 // E2_PWM +#define E1_DIR_PIN PE6 // E2_DIR +#define E1_ENABLE_PIN PE4 // E2_RESE +#define E1_CS_PIN PA4 // SPI_CS -#define E2_STEP_PIN 77 // PB8 E3_PWM -#define E2_DIR_PIN 76 // PE2 E3_DIR -#define E2_ENABLE_PIN 75 // PE3 E3_RESE -#define E2_CS_PIN 16 // PA4 SPI_CS +#define E2_STEP_PIN PB8 // E3_PWM +#define E2_DIR_PIN PE2 // E3_DIR +#define E2_ENABLE_PIN PE3 // E3_RESE +#define E2_CS_PIN PA4 // SPI_CS // needed to pass a sanity check -#define X2_CS_PIN 16 // PA4 SPI_CS -#define Y2_CS_PIN 16 // PA4 SPI_CS -#define Z2_CS_PIN 16 // PA4 SPI_CS -#define Z3_CS_PIN 16 // PA4 SPI_CS -#define E3_CS_PIN 16 // PA4 SPI_CS -#define E4_CS_PIN 16 // PA4 SPI_CS -#define E5_CS_PIN 16 // PA4 SPI_CS +#define X2_CS_PIN PA4 // SPI_CS +#define Y2_CS_PIN PA4 // SPI_CS +#define Z2_CS_PIN PA4 // SPI_CS +#define Z3_CS_PIN PA4 // SPI_CS +#define E3_CS_PIN PA4 // SPI_CS +#define E4_CS_PIN PA4 // SPI_CS +#define E5_CS_PIN PA4 // SPI_CS #if HAS_L64XX - #define L6470_CHAIN_SCK_PIN 17 // PA5 - #define L6470_CHAIN_MISO_PIN 18 // PA6 - #define L6470_CHAIN_MOSI_PIN 19 // PA7 - #define L6470_CHAIN_SS_PIN 16 // PA4 + #define L6470_CHAIN_SCK_PIN PA5 + #define L6470_CHAIN_MISO_PIN PA6 + #define L6470_CHAIN_MOSI_PIN PA7 + #define L6470_CHAIN_SS_PIN PA4 //#define SD_SCK_PIN L6470_CHAIN_SCK_PIN //#define SD_MISO_PIN L6470_CHAIN_MISO_PIN //#define SD_MOSI_PIN L6470_CHAIN_MOSI_PIN #else - //#define SD_SCK_PIN 13 // PB13 SPI_S - //#define SD_MISO_PIN 12 // PB14 SPI_M - //#define SD_MOSI_PIN 11 // PB15 SPI_M + //#define SD_SCK_PIN PB13 // SPI_S + //#define SD_MISO_PIN PB14 // SPI_M + //#define SD_MOSI_PIN PB15 // SPI_M #endif /** @@ -144,114 +144,109 @@ // // Temperature Sensors // -#define TEMP_0_PIN 3 // Analog input 3, digital pin 54 PA0 E1_THERMISTOR -#define TEMP_1_PIN 4 // Analog input 4, digital pin 55 PA1 E2_THERMISTOR -#define TEMP_2_PIN 5 // Analog input 5, digital pin 56 PA2 E3_THERMISTOR -#define TEMP_BED_PIN 0 // Analog input 0, digital pin 51 PC2 BED_THERMISTOR_1 -#define TEMP_BED_1_PIN 1 // Analog input 1, digital pin 52 PC3 BED_THERMISTOR_2 -#define TEMP_BED_2_PIN 2 // Analog input 2, digital pin 53 PA3 BED_THERMISTOR_3 +#define TEMP_0_PIN PA0 // Analog input 3, digital pin 54 PA0 E1_THERMISTOR +#define TEMP_1_PIN PA1 // Analog input 4, digital pin 55 PA1 E2_THERMISTOR +#define TEMP_2_PIN PA2 // Analog input 5, digital pin 56 PA2 E3_THERMISTOR +#define TEMP_BED_PIN PC2 // Analog input 0, digital pin 51 PC2 BED_THERMISTOR_1 +#define TEMP_BED_1_PIN PC3 // Analog input 1, digital pin 52 PC3 BED_THERMISTOR_2 +#define TEMP_BED_2_PIN PA3 // Analog input 2, digital pin 53 PA3 BED_THERMISTOR_3 // // Heaters / Fans // -#define HEATER_0_PIN 48 // PC7 E1_HEAT_PWM -#define HEATER_1_PIN 49 // PB0 E2_HEAT_PWM -#define HEATER_2_PIN 50 // PB1 E3_HEAT_PWM -#define HEATER_BED_PIN 46 // PD14 (BED_HEAT_1 FET -#define HEATER_BED_1_PIN 45 // PD13 (BED_HEAT_2 FET -#define HEATER_BED_2_PIN 47 // PD15 (BED_HEAT_3 FET +#define HEATER_0_PIN PC7 // E1_HEAT_PWM +#define HEATER_1_PIN PB0 // E2_HEAT_PWM +#define HEATER_2_PIN PB1 // E3_HEAT_PWM +#define HEATER_BED_PIN PD14 // (BED_HEAT_1 FET +#define HEATER_BED_1_PIN PD13 // (BED_HEAT_2 FET +#define HEATER_BED_2_PIN PD15 // (BED_HEAT_3 FET -#define FAN_PIN 57 // PC4 E1_FAN PWM pin, Part cooling fan FET -#define FAN1_PIN 58 // PC5 E2_FAN PWM pin, Extruder fan FET -#define FAN2_PIN 59 // PE8 E3_FAN PWM pin, Controller fan FET +#define FAN_PIN PC4 // E1_FAN PWM pin, Part cooling fan FET +#define FAN1_PIN PC5 // E2_FAN PWM pin, Extruder fan FET +#define FAN2_PIN PE8 // E3_FAN PWM pin, Controller fan FET #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 58 // FAN1_PIN + #define E0_AUTO_FAN_PIN PC5 // FAN1_PIN #endif // // Misc functions // -#define LED_PIN -1 // 9 // PE1 green LED Heart beat -#define PS_ON_PIN -1 -#define KILL_PIN -1 -#define POWER_LOSS_PIN -1 // PWR_LOSS / nAC_FAULT +#define LED_PIN -1 // 9 // PE1 green LED Heart beat +#define PS_ON_PIN -1 +#define KILL_PIN -1 +#define POWER_LOSS_PIN -1 // PWR_LOSS / nAC_FAULT // // LCD / Controller // -//#define SD_DETECT_PIN 66 // PA15 SD_CA -//#define BEEPER_PIN 24 // PC9 SDIO_D1 -//#define LCD_PINS_RS 65 // PE9 Y_DIR -//#define LCD_PINS_ENABLE 59 // PE8 E3_FAN -//#define LCD_PINS_D4 10 // PB12 SPI_C -//#define LCD_PINS_D5 13 // PB13 SPI_S -//#define LCD_PINS_D6 12 // PB14 SPI_M -//#define LCD_PINS_D7 11 // PB15 SPI_M -//#define BTN_EN1 57 // PC4 E1_FAN -//#define BTN_EN2 58 // PC5 E2_FAN -//#define BTN_ENC 52 // PC3 BED_THE +//#define SD_DETECT_PIN PA15 // SD_CA +//#define BEEPER_PIN PC9 // SDIO_D1 +//#define LCD_PINS_RS PE9 // Y_DIR +//#define LCD_PINS_ENABLE PE8 // E3_FAN +//#define LCD_PINS_D4 PB12 // SPI_C +//#define LCD_PINS_D5 PB13 // SPI_S +//#define LCD_PINS_D6 PB14 // SPI_M +//#define LCD_PINS_D7 PB15 // SPI_M +//#define BTN_EN1 PC4 // E1_FAN +//#define BTN_EN2 PC5 // E2_FAN +//#define BTN_ENC PC3 // BED_THE // // Extension pins // -//#define EXT0_PIN 49 // PB0 E2_HEAT -//#define EXT1_PIN 50 // PB1 E3_HEAT -//#define EXT2_PIN // PB2 not used (tied to ground -//#define EXT3_PIN 39 // PD8 X_STOP -//#define EXT4_PIN 40 // PD9 Y_STOP -//#define EXT5_PIN 41 // PD10 Z_STOP -//#define EXT6_PIN 42 // PD11 -//#define EXT7_PIN 71 // PD12 E1_PW -//#define EXT8_PIN 64 // PB10 Y_PWM +//#define EXT0_PIN PB0 //E2_HEAT +//#define EXT1_PIN PB1 //E3_HEAT +//#define EXT2_PIN PB2 //not used (tied to ground +//#define EXT3_PIN PD8 //X_STOP +//#define EXT4_PIN PD9 //Y_STOP +//#define EXT5_PIN PD10 //Z_STOP +//#define EXT6_PIN PD11 +//#define EXT7_PIN PD12 //E1_PW +//#define EXT8_PIN PB10 //Y_PWM // WIFI -// 2 // PD3 CTS -// 3 // PD4 RTS -// 4 // PD5 TX -// 5 // PD6 RX -// 6 // PB5 WIFI_WAKEUP -// 7 // PE11 WIFI_RESET -// 8 // PE12 WIFI_BOOT +// PD3 CTS +// PD4 RTS +// PD5 TX +// PD6 RX +// PB5 WIFI_WAKEUP +// PE11 WIFI_RESET +// PE12 WIFI_BOOT // I2C USER -// 14 // PB7 SDA -// 15 // PB6 SCL +// PB7 SDA +// PB6 SCL // JTAG -// 20 // PA13 JTAG_TMS/SWDIO -// 21 // PA14 JTAG_TCK/SWCLK -// 22 // PB3 JTAG_TDO/SWO +// PA13 JTAG_TMS/SWDIO +// PA14 JTAG_TCK/SWCLK +// PB3 JTAG_TDO/SWO // // Onboard SD support // -#define SDIO_D0_PIN 23 // PC8 SDIO_D0 -#define SDIO_D1_PIN 24 // PC9 SDIO_D1 -//#define SD_CARD_DETECT_PIN 25 // PA15 SD_CARD_DETECT -#define SDIO_D2_PIN 26 // PC10 SDIO_D2 -#define SDIO_D3_PIN 27 // PC11 SDIO_D3 -#define SDIO_CK_PIN 28 // PC12 SDIO_CK -#define SDIO_CMD_PIN 29 // PD2 SDIO_CMD - #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif #if SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT // Use SDIO for onboard SD - #ifndef SDIO_SUPPORT + #define SDIO_SUPPORT // Use SDIO for onboard SD + #if DISABLED(SDIO_SUPPORT) #define SOFTWARE_SPI // Use soft SPI for onboard SD - #define SDSS SDIO_D3_PIN - #define SD_SCK_PIN SDIO_CK_PIN - #define SD_MISO_PIN SDIO_D0_PIN - #define SD_MOSI_PIN SDIO_CMD_PIN + #define SDSS PC11 + #define SD_SCK_PIN PC12 + #define SD_MISO_PIN PC8 + #define SD_MOSI_PIN PD2 #endif + + //#define SD_CARD_DETECT_PIN PA15 // SD_CARD_DETECT + #endif #ifndef SDSS - #define SDSS 16 // PA4 SPI_CS + #define SDSS PA4 // SPI_CS #endif // OTG From 7d462915b325c5590bfcdc1debe3bc40c87e9fcd Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 27 Dec 2021 01:05:53 +0000 Subject: [PATCH 199/273] [cron] Bump distribution date (2021-12-27) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index fca302288f67c..0310f0974928c 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 "2021-12-26" +//#define STRING_DISTRIBUTION_DATE "2021-12-27" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index d2b7a93775656..97ccbdbaa547f 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 "2021-12-26" + #define STRING_DISTRIBUTION_DATE "2021-12-27" #endif /** From 9345eedb6453e047d65ef0e9a06f63dad7f769fc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Dec 2021 14:19:55 -0600 Subject: [PATCH 200/273] =?UTF-8?q?=F0=9F=8E=A8=20Clean=20up=20ST=20Eval?= =?UTF-8?q?=203DP001=20V1=20pins?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../src/pins/stm32f4/pins_STEVAL_3DP001V1.h | 260 ++++++++---------- 1 file changed, 116 insertions(+), 144 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h index 98d222087839c..0b527a6fdb782 100644 --- a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h +++ b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h @@ -60,13 +60,13 @@ // Z Probe (when not Z_MIN_PIN) // //#ifndef Z_MIN_PROBE_PIN -// #define Z_MIN_PROBE_PIN 16 // PA4 +// #define Z_MIN_PROBE_PIN PA4 // SPI1_CS //#endif // // Filament runout // -//#define FIL_RUNOUT_PIN PA3 // BED_THE +//#define FIL_RUNOUT_PIN PA3 // BED_THERMISTOR_3 // // Steppers @@ -74,56 +74,56 @@ #define X_STEP_PIN PE14 // X_PWM #define X_DIR_PIN PE15 // X_DIR -#define X_ENABLE_PIN PE13 // X_RES -#define X_CS_PIN PA4 // SPI_CS +#define X_ENABLE_PIN PE13 // X_RESET +#define X_CS_PIN PA4 // SPI1_CS #define Y_STEP_PIN PB10 // Y_PWM #define Y_DIR_PIN PE9 // Y_DIR -#define Y_ENABLE_PIN PE10 // Y_RES -#define Y_CS_PIN PA4 // SPI_CS +#define Y_ENABLE_PIN PE10 // Y_RESET +#define Y_CS_PIN PA4 // SPI1_CS #define Z_STEP_PIN PC6 // Z_PWM #define Z_DIR_PIN PC0 // Z_DIR -#define Z_ENABLE_PIN PC15 // Z_RES -#define Z_CS_PIN PA4 // SPI_CS +#define Z_ENABLE_PIN PC15 // Z_RESET +#define Z_CS_PIN PA4 // SPI1_CS #define E0_STEP_PIN PD12 // E1_PW #define E0_DIR_PIN PC13 // E1_DIR -#define E0_ENABLE_PIN PC14 // E1_RE -#define E0_CS_PIN PA4 // SPI_CS +#define E0_ENABLE_PIN PC14 // E1_RESET +#define E0_CS_PIN PA4 // SPI1_CS #define E1_STEP_PIN PE5 // E2_PWM #define E1_DIR_PIN PE6 // E2_DIR -#define E1_ENABLE_PIN PE4 // E2_RESE -#define E1_CS_PIN PA4 // SPI_CS +#define E1_ENABLE_PIN PE4 // E2_RESET +#define E1_CS_PIN PA4 // SPI1_CS #define E2_STEP_PIN PB8 // E3_PWM #define E2_DIR_PIN PE2 // E3_DIR -#define E2_ENABLE_PIN PE3 // E3_RESE -#define E2_CS_PIN PA4 // SPI_CS +#define E2_ENABLE_PIN PE3 // E3_RESET +#define E2_CS_PIN PA4 // SPI1_CS // needed to pass a sanity check -#define X2_CS_PIN PA4 // SPI_CS -#define Y2_CS_PIN PA4 // SPI_CS -#define Z2_CS_PIN PA4 // SPI_CS -#define Z3_CS_PIN PA4 // SPI_CS -#define E3_CS_PIN PA4 // SPI_CS -#define E4_CS_PIN PA4 // SPI_CS -#define E5_CS_PIN PA4 // SPI_CS +#define X2_CS_PIN PA4 // SPI1_CS +#define Y2_CS_PIN PA4 // SPI1_CS +#define Z2_CS_PIN PA4 // SPI1_CS +#define Z3_CS_PIN PA4 // SPI1_CS +#define E3_CS_PIN PA4 // SPI1_CS +#define E4_CS_PIN PA4 // SPI1_CS +#define E5_CS_PIN PA4 // SPI1_CS #if HAS_L64XX - #define L6470_CHAIN_SCK_PIN PA5 - #define L6470_CHAIN_MISO_PIN PA6 - #define L6470_CHAIN_MOSI_PIN PA7 - #define L6470_CHAIN_SS_PIN PA4 + #define L6470_CHAIN_SCK_PIN PA5 // SPI1_SCK + #define L6470_CHAIN_MISO_PIN PA6 // SPI1_MISO + #define L6470_CHAIN_MOSI_PIN PA7 // SPI1_MOSI + #define L6470_CHAIN_SS_PIN PA4 // SPI1_CS //#define SD_SCK_PIN L6470_CHAIN_SCK_PIN //#define SD_MISO_PIN L6470_CHAIN_MISO_PIN //#define SD_MOSI_PIN L6470_CHAIN_MOSI_PIN #else - //#define SD_SCK_PIN PB13 // SPI_S - //#define SD_MISO_PIN PB14 // SPI_M - //#define SD_MOSI_PIN PB15 // SPI_M + //#define SD_SCK_PIN PB13 // SPI2_SCK + //#define SD_MISO_PIN PB14 // SPI2_MISO + //#define SD_MOSI_PIN PB15 // SPI2_MOSI #endif /** @@ -144,12 +144,12 @@ // // Temperature Sensors // -#define TEMP_0_PIN PA0 // Analog input 3, digital pin 54 PA0 E1_THERMISTOR -#define TEMP_1_PIN PA1 // Analog input 4, digital pin 55 PA1 E2_THERMISTOR -#define TEMP_2_PIN PA2 // Analog input 5, digital pin 56 PA2 E3_THERMISTOR -#define TEMP_BED_PIN PC2 // Analog input 0, digital pin 51 PC2 BED_THERMISTOR_1 -#define TEMP_BED_1_PIN PC3 // Analog input 1, digital pin 52 PC3 BED_THERMISTOR_2 -#define TEMP_BED_2_PIN PA3 // Analog input 2, digital pin 53 PA3 BED_THERMISTOR_3 +#define TEMP_0_PIN PA0 // Analog Input 3 +#define TEMP_1_PIN PA1 // Analog Input 4 +#define TEMP_2_PIN PA2 // Analog Input 5 +#define TEMP_BED_PIN PC2 // Analog Input 0 +#define TEMP_BED_1_PIN PC3 // Analog Input 1 +#define TEMP_BED_2_PIN PA3 // Analog Input 2 // // Heaters / Fans @@ -157,9 +157,9 @@ #define HEATER_0_PIN PC7 // E1_HEAT_PWM #define HEATER_1_PIN PB0 // E2_HEAT_PWM #define HEATER_2_PIN PB1 // E3_HEAT_PWM -#define HEATER_BED_PIN PD14 // (BED_HEAT_1 FET -#define HEATER_BED_1_PIN PD13 // (BED_HEAT_2 FET -#define HEATER_BED_2_PIN PD15 // (BED_HEAT_3 FET +#define HEATER_BED_PIN PD14 // BED_HEAT_1 FET +#define HEATER_BED_1_PIN PD13 // BED_HEAT_2 FET +#define HEATER_BED_2_PIN PD15 // BED_HEAT_3 FET #define FAN_PIN PC4 // E1_FAN PWM pin, Part cooling fan FET #define FAN1_PIN PC5 // E2_FAN PWM pin, Extruder fan FET @@ -172,7 +172,7 @@ // // Misc functions // -#define LED_PIN -1 // 9 // PE1 green LED Heart beat +#define LED_PIN -1 // PE1 Green LED Heartbeat #define PS_ON_PIN -1 #define KILL_PIN -1 #define POWER_LOSS_PIN -1 // PWR_LOSS / nAC_FAULT @@ -180,30 +180,30 @@ // // LCD / Controller // -//#define SD_DETECT_PIN PA15 // SD_CA +//#define SD_DETECT_PIN PA15 // SD_CARD_DETECT //#define BEEPER_PIN PC9 // SDIO_D1 //#define LCD_PINS_RS PE9 // Y_DIR //#define LCD_PINS_ENABLE PE8 // E3_FAN -//#define LCD_PINS_D4 PB12 // SPI_C -//#define LCD_PINS_D5 PB13 // SPI_S -//#define LCD_PINS_D6 PB14 // SPI_M -//#define LCD_PINS_D7 PB15 // SPI_M +//#define LCD_PINS_D4 PB12 // SPI2_CS +//#define LCD_PINS_D5 PB13 // SPI2_SCK +//#define LCD_PINS_D6 PB14 // SPI2_MISO +//#define LCD_PINS_D7 PB15 // SPI2_MOSI //#define BTN_EN1 PC4 // E1_FAN //#define BTN_EN2 PC5 // E2_FAN -//#define BTN_ENC PC3 // BED_THE +//#define BTN_ENC PC3 // BED_THERMISTOR_2 // // Extension pins // -//#define EXT0_PIN PB0 //E2_HEAT -//#define EXT1_PIN PB1 //E3_HEAT -//#define EXT2_PIN PB2 //not used (tied to ground -//#define EXT3_PIN PD8 //X_STOP -//#define EXT4_PIN PD9 //Y_STOP -//#define EXT5_PIN PD10 //Z_STOP -//#define EXT6_PIN PD11 -//#define EXT7_PIN PD12 //E1_PW -//#define EXT8_PIN PB10 //Y_PWM +//#define EXT0_PIN PB0 // E2_HEAT +//#define EXT1_PIN PB1 // E3_HEAT +//#define EXT2_PIN PB2 // not used (tied to ground) +//#define EXT3_PIN PD8 // X_STOP +//#define EXT4_PIN PD9 // Y_STOP +//#define EXT5_PIN PD10 // Z_STOP +//#define EXT6_PIN PD11 // U_STOP +//#define EXT7_PIN PD12 // E1_PWM +//#define EXT8_PIN PB10 // Y_PWM // WIFI // PD3 CTS @@ -241,113 +241,85 @@ #define SD_MOSI_PIN PD2 #endif - //#define SD_CARD_DETECT_PIN PA15 // SD_CARD_DETECT + //#define SD_DETECT_PIN PA15 #endif #ifndef SDSS - #define SDSS PA4 // SPI_CS + #define SDSS PA4 // SPI1_CS #endif // OTG -// 30 // PA11 OTG_DM -// 31 // PA12 OTG_DP +// PA11 OTG_DM +// PA12 OTG_DP // USER_PINS -// 34 // PD7 USER3 -// 35 // PB9 USER1 -// 36 // PE0 USER2 -// 37 // PB4 USER4 +// PD7 USER3 +// PB9 USER1 +// PE0 USER2 +// PB4 USER4 // USERKET -// 38 // PE7 USER_BUTTON +// PE7 USER_BUTTON -// 0 // PA9 TX -// 1 // PA10 RX +// PA9 TX +// PA10 RX // IR/PROBE -// 32 // PD1 IR_OUT -// 33 // PC1 IR_ON +// PD1 IR_OUT +// PC1 IR_ON /** * Logical pin vs. port/pin cross reference * - * PA0 54 // E1_THERMISTOR PA9 0 // TX - * PA1 55 // E2_THERMISTOR PA10 1 // RX - * PA2 56 // E3_THERMISTOR PD3 2 // CTS - * PA3 53 // BED_THERMISTOR_3 PD4 3 // RTS - * PA4 16 // SPI_CS PD5 4 // TX - * PA5 17 // SPI_SCK PD6 5 // RX - * PA6 18 // SPI_MISO PB5 6 // WIFI_WAKEUP - * PA7 19 // SPI_MOSI PE11 7 // WIFI_RESET - * PA8 43 // V_STOP PE12 8 // WIFI_BOOT - * PA9 0 // TX PE1 9 // STATUS_LED - * PA10 1 // RX PB12 10 // SPI_CS - * PA11 30 // OTG_DM PB15 11 // SPI_MOSI - * PA12 31 // OTG_DP PB14 12 // SPI_MISO - * PA13 20 // JTAG_TMS/SWDIO PB13 13 // SPI_SCK - * PA14 21 // JTAG_TCK/SWCLK PB7 14 // SDA - * PA15 25 // SD_CARD_DETECT PB6 15 // SCL - * PB0 49 // E2_HEAT_PWM PA4 16 // SPI_CS - * PB1 50 // E3_HEAT_PWM PA5 17 // SPI_SCK - * PB3 22 // JTAG_TDO/SWO PA6 18 // SPI_MISO - * PB4 37 // USER4 PA7 19 // SPI_MOSI - * PB5 6 // WIFI_WAKEUP PA13 20 // JTAG_TMS/SWDIO - * PB6 15 // SCL PA14 21 // JTAG_TCK/SWCLK - * PB7 14 // SDA PB3 22 // JTAG_TDO/SWO - * PB8 77 // E3_PWM PC8 23 // SDIO_D0 - * PB9 35 // USER1 PC9 24 // SDIO_D1 - * PB10 64 // Y_PWM PA15 25 // SD_CARD_DETECT - * PB12 10 // SPI_CS PC10 26 // SDIO_D2 - * PB13 13 // SPI_SCK PC11 27 // SDIO_D3 - * PB14 12 // SPI_MISO PC12 28 // SDIO_CK - * PB15 11 // SPI_MOSI PD2 29 // SDIO_CMD - * PC0 68 // Z_DIR PA11 30 // OTG_DM - * PC1 33 // IR_ON PA12 31 // OTG_DP - * PC2 51 // BED_THERMISTOR_1 PD1 32 // IR_OUT - * PC3 52 // BED_THERMISTOR_2 PC1 33 // IR_ON - * PC4 57 // E1_FAN PD7 34 // USER3 - * PC5 58 // E2_FAN PB9 35 // USER1 - * PC6 67 // Z_PWM PE0 36 // USER2 - * PC7 48 // E1_HEAT_PWM PB4 37 // USER4 - * PC8 23 // SDIO_D0 PE7 38 // USER_BUTTON - * PC9 24 // SDIO_D1 PD8 39 // X_STOP - * PC10 26 // SDIO_D2 PD9 40 // Y_STOP - * PC11 27 // SDIO_D3 PD10 41 // Z_STOP - * PC12 28 // SDIO_CK PD11 42 // U_STOP - * PC13 70 // E1_DIR PA8 43 // V_STOP - * PC14 69 // E1_RESET PD0 44 // W_STOP - * PC15 66 // Z_RESET PD13 45 // BED_HEAT_2 - * PD0 44 // W_STOP PD14 46 // BED_HEAT_1 - * PD1 32 // IR_OUT PD15 47 // BED_HEAT_3 - * PD2 29 // SDIO_CMD PC7 48 // E1_HEAT_PWM - * PD3 2 // CTS PB0 49 // E2_HEAT_PWM - * PD4 3 // RTS PB1 50 // E3_HEAT_PWM - * PD5 4 // TX PC2 51 // BED_THERMISTOR_1 - * PD6 5 // RX PC3 52 // BED_THERMISTOR_2 - * PD7 34 // USER3 PA3 53 // BED_THERMISTOR_3 - * PD8 39 // X_STOP PA0 54 // E1_THERMISTOR - * PD9 40 // Y_STOP PA1 55 // E2_THERMISTOR - * PD10 41 // Z_STOP PA2 56 // E3_THERMISTOR - * PD11 42 // U_STOP PC4 57 // E1_FAN - * PD12 71 // E1_PWM PC5 58 // E2_FAN - * PD13 45 // BED_HEAT_2 PE8 59 // E3_FAN - * PD14 46 // BED_HEAT_1 PE13 60 // X_RESET - * PD15 47 // BED_HEAT_3 PE14 61 // X_PWM - * PE0 36 // USER2 PE15 62 // X_DIR - * PE1 9 // STATUS_LED PE10 63 // Y_RESET - * PE2 76 // E3_DIR PB10 64 // Y_PWM - * PE3 75 // E3_RESET PE9 65 // Y_DIR - * PE4 72 // E2_RESET PC15 66 // Z_RESET - * PE5 73 // E2_PWM PC6 67 // Z_PWM - * PE6 74 // E2_DIR PC0 68 // Z_DIR - * PE7 38 // USER_BUTTON PC14 69 // E1_RESET - * PE8 59 // E3_FAN PC13 70 // E1_DIR - * PE9 65 // Y_DIR PD12 71 // E1_PWM - * PE10 63 // Y_RESET PE4 72 // E2_RESET - * PE11 7 // WIFI_RESET PE5 73 // E2_PWM - * PE12 8 // WIFI_BOOT PE6 74 // E2_DIR - * PE13 60 // X_RESET PE3 75 // E3_RESET - * PE14 61 // X_PWM PE2 76 // E3_DIR - * PE15 62 // X_DIR PB8 77 // E3_PWM + * PA0 E1_THERMISTOR PD0 W_STOP + * PA1 E2_THERMISTOR PD1 IR_OUT + * PA2 E3_THERMISTOR PD2 SDIO_CMD + * PA3 BED_THERMISTOR_3 PD3 CTS + * PA4 SPI1_CS PD4 RTS + * PA5 SPI1_SCK PD5 TX + * PA6 SPI1_MISO PD6 RX + * PA7 SPI1_MOSI PD7 USER3 + * PA8 V_STOP PD8 X_STOP + * PA9 TX PD9 Y_STOP + * PA10 RX PD10 Z_STOP + * PA11 OTG_DM PD11 U_STOP + * PA12 OTG_DP PD12 E1_PWM + * PA13 JTAG_TMS/SWDIO PD13 BED_HEAT_2 + * PA14 JTAG_TCK/SWCLK PD14 BED_HEAT_1 + * PA15 SD_CARD_DETECT PD15 BED_HEAT_3 + * + * PB0 E2_HEAT_PWM PE0 USER2 + * PB1 E3_HEAT_PWM PE1 STATUS_LED + * PB2 --- PE2 E3_DIR + * PB3 JTAG_TDO/SWO PE3 E3_RESET + * PB4 USER4 PE4 E2_RESET + * PB5 WIFI_WAKEUP PE5 E2_PWM + * PB6 SCL PE6 E2_DIR + * PB7 SDA PE7 USER_BUTTON + * PB8 E3_PWM PE8 E3_FAN + * PB9 USER1 PE9 Y_DIR + * PB10 Y_PWM PE10 Y_RESET + * PB11 --- PE11 WIFI_RESET + * PB12 SPI2_CS PE12 WIFI_BOOT + * PB13 SPI2_SCK PE13 X_RESET + * PB14 SPI2_MISO PE14 X_PWM + * PB15 SPI2_MOSI PE15 X_DIR + * + * PC0 Z_DIR + * PC1 IR_ON + * PC2 BED_THERMISTOR_1 + * PC3 BED_THERMISTOR_2 + * PC4 E1_FAN + * PC5 E2_FAN + * PC6 Z_PWM + * PC7 E1_HEAT_PWM + * PC8 SDIO_D0 + * PC9 SDIO_D1 + * PC10 SDIO_D2 + * PC11 SDIO_D3 + * PC12 SDIO_CK + * PC13 E1_DIR + * PC14 E1_RESET + * PC15 Z_RESET */ From 3f6147fe85e9f3d1ea255b218a53dbd71040fec3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Dec 2021 14:28:59 -0600 Subject: [PATCH 201/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20mffp=20usage?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/git/mffp | 4 ++-- buildroot/share/git/mfnew | 4 +--- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/buildroot/share/git/mffp b/buildroot/share/git/mffp index 0680b3dba5627..ab4dd4c0b7714 100755 --- a/buildroot/share/git/mffp +++ b/buildroot/share/git/mffp @@ -6,7 +6,7 @@ # By default: `git push upstream HEAD:bugfix-2.0.x` # -usage() { echo "usage: `basename $0` [1|2] [ref]" 1>&2 } +usage() { echo "usage: `basename $0` [1|2] [ref]" 1>&2 ; } [[ $# < 3 && $1 != "-h" && $1 != "--help" ]] || { usage ; exit 1; } @@ -17,7 +17,7 @@ elif [[ $# == 1 ]]; then MFINFO=$(mfinfo) || exit 1 REF=${1:-HEAD} else - usage + usage ; exit 1 fi IFS=' ' read -a INFO <<< "$MFINFO" diff --git a/buildroot/share/git/mfnew b/buildroot/share/git/mfnew index 6d067a7f08e66..48703e67a14d2 100755 --- a/buildroot/share/git/mfnew +++ b/buildroot/share/git/mfnew @@ -5,9 +5,7 @@ # Create a new branch from the default target with the given name # -usage() { - echo "usage: `basename $0` [1|2] [name]" 1>&2 -} +usage() { echo "usage: `basename $0` [1|2] [name]" 1>&2 ; } [[ $# < 3 && $1 != "-h" && $1 != "--help" ]] || { usage; exit 1; } From d557db842598639f4ab49447e216557515b3ba9e Mon Sep 17 00:00:00 2001 From: Ave6683 <53094187+Ave6683@users.noreply.github.com> Date: Mon, 27 Dec 2021 22:28:27 +0100 Subject: [PATCH 202/273] =?UTF-8?q?=E2=9C=A8=20MagLev=20V4=20probe=20by=20?= =?UTF-8?q?MDD=20(#23192)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 11 +++++++++++ Marlin/src/MarlinCore.cpp | 4 ++++ Marlin/src/core/utility.cpp | 3 ++- Marlin/src/inc/Conditionals_LCD.h | 2 +- Marlin/src/inc/SanityCheck.h | 23 ++++++++++++++++++----- Marlin/src/module/probe.cpp | 15 +++++++++++++++ 6 files changed, 51 insertions(+), 7 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index f0fc4dd7d608f..236c6a8a54612 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1089,6 +1089,17 @@ */ //#define BLTOUCH +/** + * MagLev V4 probe by MDD + * + * This probe is deployed and activated by powering a built-in electromagnet. + */ +//#define MAGLEV4 +#if ENABLED(MAGLEV4) + //#define MAGLEV_TRIGGER_PIN 11 // Set to the connected digital output + #define MAGLEV_TRIGGER_DELAY 15 // Changing this risks overheating the coil +#endif + /** * Touch-MI Probe by hotends.fr * diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5132d07e8711f..16cd43443c1c9 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1502,6 +1502,10 @@ void setup() { SETUP_RUN(bltouch.init(/*set_voltage=*/true)); #endif + #if ENABLED(MAGLEV4) + OUT_WRITE(MAGLEV_TRIGGER_PIN, LOW); + #endif + #if ENABLED(I2C_POSITION_ENCODERS) SETUP_RUN(I2CPEM.init()); #endif diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index cc3b1ace2fdbf..19e76267447d3 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -74,7 +74,8 @@ void safe_delay(millis_t ms) { TERN_(Z_PROBE_SLED, "Z_PROBE_SLED") TERN_(Z_PROBE_ALLEN_KEY, "Z_PROBE_ALLEN_KEY") TERN_(SOLENOID_PROBE, "SOLENOID_PROBE") - TERN(PROBE_SELECTED, "", "NONE") + TERN_(MAGLEV4, "MAGLEV4") + IF_DISABLED(PROBE_SELECTED, "NONE") ); #if HAS_BED_PROBE diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 9e050101aa366..803a182654986 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -822,7 +822,7 @@ /** * Set a flag for any type of bed probe, including the paper-test */ -#if ANY(HAS_Z_SERVO_PROBE, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, SOLENOID_PROBE, SENSORLESS_PROBING, RACK_AND_PINION_PROBE) +#if ANY(HAS_Z_SERVO_PROBE, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, SOLENOID_PROBE, SENSORLESS_PROBING, RACK_AND_PINION_PROBE, MAGLEV4) #define HAS_BED_PROBE 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ab1a6adec5601..50191dd201e97 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1509,8 +1509,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS */ #if 1 < 0 \ + (DISABLED(BLTOUCH) && HAS_Z_SERVO_PROBE) \ - + COUNT_ENABLED(PROBE_MANUALLY, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, RACK_AND_PINION_PROBE, SENSORLESS_PROBING) - #error "Please enable only one probe option: PROBE_MANUALLY, SENSORLESS_PROBING, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo." + + COUNT_ENABLED(PROBE_MANUALLY, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, RACK_AND_PINION_PROBE, SENSORLESS_PROBING, MAGLEV4) + #error "Please enable only one probe option: PROBE_MANUALLY, SENSORLESS_PROBING, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, MAGLEV4, or Z Servo." #endif #if HAS_BED_PROBE @@ -1612,6 +1612,19 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif + /** + * MagLev V4 probe requirements + */ + #if ENABLED(MAGLEV4) + #if !PIN_EXISTS(MAGLEV_TRIGGER) + #error "MAGLEV4 requires MAGLEV_TRIGGER_PIN to be defined." + #elif DISABLED(Z_SAFE_HOMING) + #error "MAGLEV4 requires Z_SAFE_HOMING." + #elif MAGLEV_TRIGGER_DELAY != 15 + #error "MAGLEV_TRIGGER_DELAY should not be changed. Comment out this line to continue." + #endif + #endif + /** * Require pin options and pins to be defined */ @@ -1699,11 +1712,11 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * Require some kind of probe for bed leveling and probe testing */ #if HAS_ABL_NOT_UBL && !PROBE_SELECTED - #error "Auto Bed Leveling requires one of these: PROBE_MANUALLY, SENSORLESS_PROBING, BLTOUCH, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or a Z Servo." + #error "Auto Bed Leveling requires either PROBE_MANUALLY, SENSORLESS_PROBING, or a real probe." #endif #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) - #error "Z_MIN_PROBE_REPEATABILITY_TEST requires a probe: FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo." + #error "Z_MIN_PROBE_REPEATABILITY_TEST requires a real probe." #endif #endif @@ -3443,7 +3456,7 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #if ENABLED(MECHANICAL_GANTRY_CALIBRATION) #if NONE(HAS_MOTOR_CURRENT_DAC, HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_DAC, HAS_TRINAMIC_CONFIG, HAS_MOTOR_CURRENT_PWM) - #error "It is highly recommended to have adjustable current drivers to prevent damage. Disable this line to continue anyway." + #error "Adjustable current drivers are highly recommended to prevent damage. Comment out this line to continue anyway." #elif !defined(GANTRY_CALIBRATION_CURRENT) #error "MECHANICAL_GANTRY_CALIBRATION Requires GANTRY_CALIBRATION_CURRENT to be set." #elif !defined(GANTRY_CALIBRATION_EXTRA_HEIGHT) diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 540b4e1ae6a46..d1f3eee207252 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -121,6 +121,17 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() #endif } +#elif ENABLED(MAGLEV4) + + // Write trigger pin to release the probe + inline void maglev_deploy() { + WRITE(MAGLEV_TRIGGER_PIN, HIGH); + delay(MAGLEV_TRIGGER_DELAY); + WRITE(MAGLEV_TRIGGER_PIN, LOW); + } + + inline void maglev_idle() { do_blocking_move_to_z(10); } + #elif ENABLED(TOUCH_MI_PROBE) // Move to the magnet to unlock the probe @@ -311,6 +322,10 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { WRITE(SOL1_PIN, deploy); #endif + #elif ENABLED(MAGLEV4) + + deploy ? maglev_deploy() : maglev_idle(); + #elif ENABLED(Z_PROBE_SLED) dock_sled(!deploy); From c160a57397bbd31c44c404f7c56a269f8fd802d6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Dec 2021 17:40:53 -0600 Subject: [PATCH 203/273] =?UTF-8?q?=F0=9F=93=8C=20Define=20MKS=20Monster8?= =?UTF-8?q?=20pins=20for=20MKS=5FMINI=5F12864?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #23324 --- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index 2f77c0f9d6f93..161884c322fb8 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -339,14 +339,18 @@ // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) #if ENABLED(MKS_MINI_12864) - //#define LCD_BACKLIGHT_PIN -1 - //#define LCD_RESET_PIN -1 - #define DOGLCD_A0 PD11 - #define DOGLCD_CS EXP1_04_PIN - //#define DOGLCD_SCK EXP2_09_PIN - //#define DOGLCD_MOSI EXP2_05_PIN + + #define ENABLE_SPI1 + #define FORCE_SOFT_SPI + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_05_PIN + #define DOGLCD_SCK EXP2_09_PIN + #define DOGLCD_MOSI EXP2_05_PIN + //#define LCD_BACKLIGHT_PIN -1 + //#define LCD_RESET_PIN -1 #elif ENABLED(FYSETC_MINI_12864_2_1) + #define DOGLCD_CS EXP1_08_PIN #define DOGLCD_A0 EXP1_07_PIN #define LCD_PINS_DC DOGLCD_A0 From c5b74319e7459485ac77263ac2c4597ed6fe6cfd Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 28 Dec 2021 01:05:31 +0000 Subject: [PATCH 204/273] [cron] Bump distribution date (2021-12-28) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 0310f0974928c..ca2fb62834c6c 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 "2021-12-27" +//#define STRING_DISTRIBUTION_DATE "2021-12-28" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 97ccbdbaa547f..c2963ee8327cb 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 "2021-12-27" + #define STRING_DISTRIBUTION_DATE "2021-12-28" #endif /** From 761b1b93c62e9b70dd97c9579450804219d8f25b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 27 Dec 2021 20:52:43 -0600 Subject: [PATCH 205/273] =?UTF-8?q?=F0=9F=93=9D=20Consistent=20pin=20heade?= =?UTF-8?q?r=20orientation?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/esp32/pins_MKS_TINYBEE.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 6 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 36 +++++----- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 40 +++++------ Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 17 ++--- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 4 +- .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 20 +++--- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 4 +- Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h | 30 ++++---- Marlin/src/pins/ramps/pins_MKS_GEN_13.h | 2 +- Marlin/src/pins/ramps/pins_RAMPS.h | 16 ++--- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 48 ++++++------- .../stm32f1/pins_BTT_SKR_MINI_E3_common.h | 62 ++++++++--------- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h | 4 +- Marlin/src/pins/stm32f1/pins_FLY_MINI.h | 4 +- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 2 +- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 20 +++--- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 52 +++++++------- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 16 ++--- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 24 +++---- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 32 ++++----- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 26 +++---- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 2 +- .../pins/stm32f4/pins_FYSETC_CHEETAH_V20.h | 34 +++++----- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 2 +- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h | 41 +++++------ .../src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h | 36 +++++----- Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h | 4 +- .../pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h | 68 +++++++++---------- 30 files changed, 329 insertions(+), 327 deletions(-) diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h index bfa38adadf73d..5cae63d31add6 100644 --- a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h +++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h @@ -127,7 +127,7 @@ * ------ ------ * (BEEPER) 149 |10 9 | 13 (BTN_ENC) (SPI MISO) 19 |10 9 | 18 (SPI SCK) * (LCD_EN) 21 | 8 7 | 4 (LCD_RS) (BTN_EN1) 14 | 8 7 | 5 (SPI CS) - * (LCD_D4) 0 | 6 5 16 (LCD_D5) (BTN_EN2) 12 | 6 5 23 (SPI MOSI) + * (LCD_D4) 0 6 5 | 16 (LCD_D5) (BTN_EN2) 12 6 5 | 23 (SPI MOSI) * (LCD_D6) 15 | 4 3 | 17 (LCD_D7) (SPI_DET) 34 | 4 3 | RESET * GND | 2 1 | 5V GND | 2 1 | 3.3V * ------ ------ diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index 48b178dab5fe5..f0f57c63eedc7 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -60,9 +60,9 @@ /** ------ ------ * 1.30 |10 9 | 2.11 0.17 |10 9 | 0.15 * 0.18 | 8 7 | 0.16 3.26 | 8 7 | 1.23 - * 0.15 6 5 | NC 3.25 6 5 | 0.18 - * NC | 4 3 | NC 1.31 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | NC + * 0.15 6 5 | -- 3.25 6 5 | 0.18 + * -- | 4 3 | -- 1.31 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | -- * ------ ------ * EXP1 EXP2 */ 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 97d78c0d2434d..586fb14e8eb74 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -195,7 +195,7 @@ * (LCD_EN) 1.18 | 8 7 | 1.19 (LCD_RS) (BTN_EN1) 3.26 | 8 7 | 0.16 (SD_SS) * (LCD_D4) 1.20 6 5 | 1.21 (LCD_D5) (BTN_EN2) 3.25 6 5 | 0.18 (MOSI) * (LCD_D6) 1.22 | 4 3 | 1.23 (LCD_D7) (SD_DETECT) 1.31 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | NC + * GND | 2 1 | 5V GND | 2 1 | -- * ------ ------ * EXP1 EXP2 */ @@ -237,11 +237,11 @@ * * BEFORE AFTER * ------ ------ - * GND 1 | 1 2 | 2 5V 5V 1 | 1 2 | 2 GND - * CS 3 | 3 4 | 4 BTN_EN2 CS 3 | 3 4 | 4 BTN_EN2 - * SID 5 | 5 6 6 BTN_EN1 SID 5 | 5 6 6 BTN_EN1 - * open 7 | 7 8 | 8 BTN_ENC CLK 7 | 7 8 | 8 BTN_ENC - * CLK 9 | 9 10 | 10 Beeper open 9 | 9 10 | 10 Beeper + * (CLK) |10 9 | (BEEPER) (BEEPER) |10 9 | -- + * -- | 8 7 | (BTN_ENC) (BTN_ENC) | 8 7 | (CLK) + * (SID) 6 5 | (BTN_EN1) (BTN_EN1) 6 5 | (SID) + * (CS) | 4 3 | (BTN_EN2) (BTN_EN2) | 4 3 | (CS) + * GND | 2 1 | 5V GND | 2 1 | 5V * ------ ------ * LCD LCD */ @@ -270,11 +270,11 @@ * * BEFORE AFTER * ______ ______ - * GND | 1 2 | 5V 5V | 1 2 | GND - * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 - * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 - * SCK | 7 8 | BTN_ENC SCK | 7 8 | BTN_ENC - * MOSI | 9 10 | open | 9 10 | MOSI + * |10 9 | (MOSI) (MOSI) |10 9 | -- + * (BTN_ENC) | 8 7 | (SCK) (BTN_ENC) | 8 7 | (SCK) + * (BTN_EN1) 6 5 | (SID) (BTN_EN1) 6 5 | (SID) + * (BTN_EN2) | 4 3 | (CS) (BTN_EN2) | 4 3 | (CS) + * 5V | 2 1 | GND GND | 2 1 | 5V * ------ ------ * LCD LCD */ @@ -424,13 +424,13 @@ /** * Creality Ender-2 display pinout - * ----- - * 5V | 1 2 | GND - * (MOSI) P1_23 | 3 4 | P1_22 (LCD_CS) - * (LCD_A0) P1_21 | 5 6 P1_20 (BTN_EN2) - * (RESET) P1_19 | 7 8 | P1_18 (BTN_EN1) - * (BTN_ENC) P0_28 | 9 10| P1_30 (SCK) - * ----- + * ------ + * (SCK) P1_30 |10 9 | P0_28 (BTN_ENC) + * (BTN_EN1) P1_18 | 8 7 | P1_19 (RESET) + * (BTN_EN2) P1_20 6 5 | P1_21 (LCD_A0) + * (LCD_CS) P1_22 | 4 3 | P1_23 (MOSI) + * GND | 2 1 | 5V + * ------ * EXP1 */ 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 b9dc845c5b777..03a0360b6e875 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -250,7 +250,7 @@ * 1.18 | 8 7 | 1.19 3.26 | 8 7 | 0.16 * 1.20 6 5 | 1.21 3.25 6 5 | 0.18 * 1.22 | 4 3 | 1.23 1.31 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | NC + * GND | 2 1 | 5V GND | 2 1 | -- * ------ ------ * EXP1 EXP2 */ @@ -298,11 +298,11 @@ * * BEFORE AFTER * ------ ------ - * GND | 1 2 | 5V 5V | 1 2 | GND - * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 - * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 - * open | 7 8 | BTN_ENC open | 7 8 | BTN_ENC - * CLK | 9 10| BEEPER CLK | 9 10| BEEPER + * (BEEPER) | 10 9 | (CLK) (BEEPER) | 10 9 | (CLK) + * (BTN_ENC) | 8 7 | -- (BTN_ENC) | 8 7 | -- + * (BTN_EN1) 6 5 | (SID) (BTN_EN1) 6 5 | (SID) + * (BTN_EN2) | 4 3 | (CS) (BTN_EN2) | 4 3 | (CS) + * 5V | 2 1 | GND GND | 2 1 | 5V * ------ ------ * LCD LCD */ @@ -330,15 +330,15 @@ * * The ANET_FULL_GRAPHICS_LCD connector plug: * - * BEFORE AFTER - * ------ ------ - * GND | 1 2 | 5V 5V | 1 2 | GND - * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 - * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 - * open | 7 8 | BTN_ENC CLK | 7 8 | BTN_ENC - * CLK | 9 10 | BEEPER open | 9 10 | BEEPER - * ------ ------ - * LCD LCD + * BEFORE AFTER + * ------ ------ + * (BEEPER) |10 9 | (CLK) (BEEPER) |10 9 | -- + * (BTN_ENC) | 8 7 | -- (BTN_ENC) | 8 7 | (CLK) + * (BTN_EN1) 6 5 | (SID) (BTN_EN1) 6 5 | (SID) + * (BTN_EN2) | 4 3 | (CS) (BTN_EN2) | 4 3 | (CS) + * 5V | 2 1 | GND GND | 2 1 | 5V + * ------ ------ + * LCD LCD */ #define LCD_PINS_RS EXP1_03_PIN @@ -366,11 +366,11 @@ /** Creality Ender-2 display pinout * ------ - * 5V | 1 2 | GND - * (MOSI) 1.23 | 3 4 | 1.22 (LCD_RS) - * (LCD_A0) 1.21 | 5 6 1.20 (BTN_EN2) - * RESET 1.19 | 7 8 | 1.18 (BTN_EN1) - * (BTN_ENC) 0.28 | 9 10 | 1.30 (SCK) + * (SCK) 1.30 |10 9 | 0.28 (BTN_ENC) + * (BTN_EN1) 1.18 | 8 7 | 1.19 (RESET) + * (BTN_EN2) 1.20 6 5 | 1.21 (LCD_A0) + * (LCD_RS) 1.22 | 4 3 | 1.23 (MOSI) + * GND | 2 1 | 5V * ------ * EXP1 */ diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index 52f34ed0f0d59..37d0cb7fb1e04 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -150,14 +150,15 @@ #endif #if ENABLED(BTT_MOTOR_EXPANSION) - /** ------ ------ - * NC | 1 2 | GND NC | 1 2 | GND - * NC | 3 4 | M1EN M2EN | 3 4 | M3EN - * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG - * M2DIR | 7 8 | M2STP M2RX | 7 8 | M2DIAG - * M3DIR | 9 10 | M3STP M3RX | 9 10 | M3DIAG - * ------ ------ - * EXP2 EXP1 + /** + * ------ ------ + * (M3STP) |10 9 | (M3DIR) (M3DIAG) |10 9 | (M3RX) + * (M2STP) | 8 7 | (M2DIR) (M2DIAG) | 8 7 | (M2RX) + * (M1DIR) 6 5 | (M1STP) (M1DIAG) 6 5 | (M1RX) + * (M1EN) | 4 3 | -- (M3EN) | 4 3 | (M2EN) + * GND | 2 1 | -- GND | 2 1 | -- + * ------ ------ + * EXP2 EXP1 * * NB In EXP_MOT_USE_EXP2_ONLY mode EXP1 is not used and M2EN and M3EN need to be jumpered to M1EN */ diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 15afe7e238375..95bbe17b9b38f 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -233,9 +233,9 @@ /** ------ ------ * (BEEPER) 1.31 |10 9 | 1.30 (BTN_ENC) (MISO) 0.8 |10 9 | 0.7 (SD_SCK) * (LCD_EN) 0.18 | 8 7 | 0.16 (LCD_RS) (BTN_EN1) 3.25 | 8 7 | 0.28 (SD_CS2) - * (LCD_D4) 0.15 | 6 5 0.17 (LCD_D5) (BTN_EN2) 3.26 | 6 5 0.9 (SD_MOSI) + * (LCD_D4) 0.15 6 5 | 0.17 (LCD_D5) (BTN_EN2) 3.26 6 5 | 0.9 (SD_MOSI) * (LCD_D6) 1.0 | 4 3 | 1.22 (LCD_D7) (SD_DETECT) 0.27 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | NC + * GND | 2 1 | 5V GND | 2 1 | -- * ------ ------ * EXP1 EXP2 */ 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 bdc49fc236480..0916138361974 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -186,11 +186,11 @@ /** * ------ - * 5V | 1 2 | GND - * (LCD_EN) P0_18 | 3 4 | P0_17 (LCD_RS) - * (LCD_D4) P0_15 | 5 6 P0_20 (BTN_EN2) - * RESET | 7 8 | P0_19 (BTN_EN1) - * (BTN_ENC) P0_16 | 9 10 | P2_08 (BEEPER) + * (BEEPER) P2_08 |10 9 | P0_16 (BTN_ENC) + * (BTN_EN1) P0_19 | 8 7 | RESET + * (BTN_EN2) P0_20 6 5 | P0_15 (LCD_D4) + * (LCD_RS) P0_17 | 4 3 | P0_18 (LCD_EN) + * GND | 2 1 | 5V * ------ * EXP */ @@ -209,11 +209,11 @@ /** * Ender 3 V2 display SKR E3 Turbo (EXP1) Ender 3 V2 display --> SKR E3 Turbo * ------ ------ RX 8 --> 5 P0_15 - * 5V | 1 2 | GND 5V | 1 2 | GND TX 7 --> 9 P0_16 - * (BTN_E1) A | 3 4 | B (BTN_E2) (LCD_EN) P0_18 | 3 4 | P0_17 (LCD_RS) BEEPER 5 --> 10 P2_08 - * BEEPER | 5 6 ENT (BTN_ENC) (LCD_D4) P0_15 | 5 6 P0_20 (BTN_EN2) - * (SKR_RX1) TX | 7 8 | RX (SKR_TX1) Reset | 7 8 | P0_19 (BTN_EN1) - * NC | 9 10 | NC (BTN_ENC) P0_16 | 9 10 | P2_08 (BEEPER) + * -- |10 9 | -- (BEEPER) P2_08 |10 9 | P0_16 (BTN_ENC) TX 7 --> 9 P0_16 + * (SKR_TX1) RX | 8 7 | TX (SKR_RX1) (BTN_EN1) P0_19 | 8 7 | RESET BEEPER 5 --> 10 P2_08 + * (BTN_ENC) ENT 6 5 | BEEPER (BTN_EN2) P0_20 6 5 | P0_15 (LCD_D4) + * (BTN_E2) B | 4 3 | A (BTN_E1) (LCD_RS) P0_17 | 4 3 | P0_18 (LCD_EN) + * GND | 2 1 | 5V GND | 2 1 | 5V * ------ ------ */ 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 8107f11937cda..7edfb9196fa2f 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -260,9 +260,9 @@ /** ------ ------ * (BEEPER) 1.31 |10 9 | 1.30 (BTN_ENC) (MISO) 0.8 |10 9 | 0.7 (SD_SCK) * (LCD_EN) 0.18 | 8 7 | 0.16 (LCD_RS) (BTN_EN1) 3.25 | 8 7 | 0.28 (SD_CS2) - * (LCD_D4) 0.15 | 6 5 | 0.17 (LCD_D5) (BTN_EN2) 3.26 | 6 5 | 0.9 (SD_MOSI) + * (LCD_D4) 0.15 6 5 | 0.17 (LCD_D5) (BTN_EN2) 3.26 6 5 | 0.9 (SD_MOSI) * (LCD_D6) 1.0 | 4 3 | 1.22 (LCD_D7) (SD_DETECT) 0.27 | 4 3 | RST - * GND | 2 1 | 5V GND | 2 1 | NC + * GND | 2 1 | 5V GND | 2 1 | -- * ------ ------ * EXP1 EXP2 */ diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index dc7dcd6db6092..81c7dc9403dbb 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -157,11 +157,11 @@ /** * ------ - * 5V | 1 2 | GND - * P0_18 | 3 4 | P0_16 - * P0_15 | 5 6 P3_25 - * P2_11 | 7 8 | P3_26 - * P1_30 | 9 10 | P1_31 + * P1_31 |10 9 | P1_30 + * P3_26 | 8 7 | P2_11 + * P3_25 6 5 | P0_15 + * P0_16 | 4 3 | P0_18 + * GND | 2 1 | 5V * ------ * EXP1 * @@ -182,11 +182,11 @@ #if ENABLED(CR10_STOCKDISPLAY) /** ------ - * 5V | 1 2 | GND - * LCD_EN | 3 4 | LCD_RS - * LCD_D4 | 5 6 EN2 - * KILL | 7 8 | EN1 - * ENC | 9 10 | BEEPER + * BEEPER |10 9 | ENC + * EN1 | 8 7 | KILL + * EN2 6 5 | LCD_D4 + * LCD_RS | 4 3 | LCD_EN + * GND | 2 1 | 5V * ------ */ #define BEEPER_PIN EXP1_10_PIN @@ -197,11 +197,11 @@ #elif ENABLED(MKS_MINI_12864) /** ------ - * 5V | 1 2 | GND - * SPI-MOSI | 3 4 | SPI-CS - * A0 | 5 6 EN2 - * -- | 7 8 | EN1 - * ENC | 9 10 | SPI-SCK + * SCK |10 9 | ENC + * EN1 | 8 7 | -- + * EN2 6 5 | A0 + * CS | 4 3 | MOSI + * GND | 2 1 | 5V * ------ */ #define DOGLCD_CS EXP1_04_PIN diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h index 4742ac9b0d250..5f373f99d74bb 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h @@ -89,7 +89,7 @@ * BLUE_LED | 8 7 | RED_LED ENCBTN | 8 7 | SDCS * KILL 6 5 | BEEPER 6 5 | MOSI * A0 | 4 3 | LCD_CS SDCD | 4 3 | - * GND | 2 1 | 5V GND | 2 1 | NC + * GND | 2 1 | 5V GND | 2 1 | -- * ------ ------ * EXP1 EXP2 */ diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 4697ff61b2c49..121fb1b045bf5 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -461,7 +461,7 @@ * D17 | 8 7 | D16 D31 | 8 7 | D53 * D23 6 5 D25 D33 6 5 D51 (MOSI) * D27 | 4 3 | D29 D49 | 4 3 | D41 - * GND | 2 1 | 5V GND | 2 1 | NC + * GND | 2 1 | 5V GND | 2 1 | -- * ------ ------ * EXP1 EXP2 */ @@ -803,13 +803,13 @@ * FYSETC TFT-81050 display pinout * * Board Display - * ----- ----- - * (SCK) D52 | 1 2 | D50 (MISO) MISO | 1 2 | SCK - * (SD_CS) D53 | 3 4 | D33 (BNT_EN2) (BNT_EN2) MOD_RESET | 3 4 | SD_CS - * (MOSI) D51 | 5 6 D31 (BNT_EN1) (BNT_EN1) LCD_CS | 5 6 MOSI - * RESET | 7 8 | D49 (SD_DET) SD_DET | 7 8 | RESET - * NC | 9 10| GND GND | 9 10| 5V - * ----- ----- + * ------ ------ + * GND |10 9 | -- 5V |10 9 | GND + * (SD_DET) 49 | 8 7 | RESET RESET | 8 7 | (SD_DET) + * (BTN_EN1) 31 6 5 | 51 (MOSI) (MOSI) 6 5 | (LCD_CS) + * (BTN_EN2) 33 | 4 3 | 53 (SD_CS) (SD_CS) | 4 3 | (MOD_RESET) + * (MISO) 50 | 2 1 | 52 (SCK) (SCK) | 2 1 | (MISO) + * ------ ------ * EXP2 EXP1 * * Needs custom cable: 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 dae43d3c13ed7..704501de108bc 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -156,14 +156,14 @@ #define USB_CONNECT_INVERTING false /** - * ----- - * 5V | 1 2 | GND - * (LCD_EN) PB7 | 3 4 | PB8 (LCD_RS) - * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) - * RESET | 7 8 | PA9 (BTN_EN1) - * (BTN_ENC) PB6 | 9 10| PA15 (BEEPER) - * ----- - * EXP1 + * ------ + * (BEEPER) PA15 |10 9 | PB6 (BTN_ENC) + * (BTN_EN1) PA9 | 8 7 | RESET + * (BTN_EN2) PA10 6 5 | PB9 (LCD_D4) + * (LCD_RS) PB8 | 4 3 | PB7 (LCD_EN) + * GND | 2 1 | 5V + * ------ + * EXP1 */ #if HAS_WIRED_LCD @@ -195,13 +195,13 @@ #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) /** Creality Ender-2 display pinout - * ----- - * 5V | 1 2 | GND - * (MOSI) PB7 | 3 4 | PB8 (LCD_RS) - * (LCD_A0) PB9 | 5 6 PA10 (BTN_EN2) - * RESET | 7 8 | PA9 (BTN_EN1) - * (BTN_ENC) PB6 | 9 10| PA15 (SCK) - * ----- + * ------ + * (SCK) PA15 |10 9 | PB6 (BTN_ENC) + * (BTN_EN1) PA9 | 8 7 | RESET + * (BTN_EN2) PA10 6 5 | PB9 (LCD_A0) + * (LCD_RS) PB8 | 4 3 | PB7 (MOSI) + * GND | 2 1 | 5V + * ------ * EXP1 */ @@ -228,15 +228,15 @@ /** FYSETC TFT TFT81050 display pinout * - * Board Display - * ----- ----- - * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) - * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) - * (FREE) PB9 | 5 6 PA10 (SD_CS) (PB8) LCD_CS | 5 6 MOSI (SPI1-MOSI) - * RESET | 7 8 | PA9 (MOD_RESET) (PA15) SD_DET | 7 8 | RESET - * (BEEPER) PB6 | 9 10| PA15 (SD_DET) GND | 9 10| 5V - * ----- ----- - * EXP1 EXP1 + * Board Display + * ------ ------ + * (SD_DET) PA15 |10 9 | PB6 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PA9 | 8 7 | RESET (RESET) | 8 7 | (SD_DET) + * (SD_CS) PA10 6 5 | PB9 (MOSI) 6 5 | (LCD_CS) + * (LCD_CS) PB8 | 4 3 | PB7 (SD_CS) | 4 3 | (MOD_RESET) + * GND | 2 1 | 5V (SCK) | 2 1 | (MISO) + * ------ ------ + * EXP1 EXP1 * * Needs 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 8c8043be8b2ad..bbf38e414fde8 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 @@ -120,11 +120,11 @@ /** * SKR Mini E3 V1.0, V1.2 SKR Mini E3 V2.0 * ------ ------ - * 5V | 1 2 | GND 5V | 1 2 | GND - * (LCD_EN) PB7 | 3 4 | PB8 (LCD_RS) (LCD_EN) PB15 | 3 4 | PB8 (LCD_RS) - * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) - * RESET | 7 8 | PA9 (BTN_EN1) RESET | 7 8 | PA9 (BTN_EN1) - * (BTN_ENC) PB6 | 9 10 | PB5 (BEEPER) (BTN_ENC) PA15 | 9 10 | PB5 (BEEPER) + * (BEEPER) PB5 |10 9 | PB6 (BTN_ENC) (BEEPER) PB5 |10 9 | PA15 (BTN_ENC) + * (BTN_EN1) PA9 | 8 7 | RESET (BTN_EN1) PA9 | 8 7 | RESET + * (BTN_EN2) PA10 6 5 | PB9 (LCD_D4) (BTN_EN2) PA10 6 5 | PB9 (LCD_D4) + * (LCD_RS) PB8 | 4 3 | PB7 (LCD_EN) (LCD_RS) PB8 | 4 3 | PB15 (LCD_EN) + * GND | 2 1 | 5V GND | 2 1 | 5V * ------ ------ * EXP1 EXP1 */ @@ -138,14 +138,14 @@ #if EITHER(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) /** - * ------ ------ ------ - * VCC | 1 2 | GND VCC | 1 2 | GND GND | 2 1 | VCC - * A | 3 4 | B A | 3 4 | B B | 4 3 | A - * | 5 6 TX BEEP | 5 6 ENT ENT | 6 5 | BEEP - * | 7 8 | RX TX | 7 8 | RX RX | 8 7 | TX - * BEEP | 9 10 | ENT | 9 10 | | 10 9 | - * ------ ------ ------ - * EXP1 DWIN DWIN (plug) + * ------ ------ ------ + * (ENT) |10 9 | (BEEP) |10 9 | |10 9 | + * (RX) | 8 7 | (RX) | 8 7 | (TX) RX | 8 7 | TX + * (TX) 6 5 | (ENT) 6 5 | (BEEP) ENT | 6 5 | BEEP + * (B) | 4 3 | (A) (B) | 4 3 | (A) B | 4 3 | A + * GND | 2 1 | (VCC) GND | 2 1 | VCC GND | 2 1 | VCC + * ------ ------ ------ + * EXP1 DWIN DWIN (plug) * * All pins are labeled as printed on DWIN PCB. Connect TX-TX, A-A and so on. */ @@ -206,15 +206,15 @@ /** * TFTGLCD_PANEL_SPI display pinout * - * Board Display - * ------ ------ - * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) - * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) LCD_CS | 3 4 | SD_CS (PA10) - * (FREE) PB9 | 5 6 | PA10 (SD_CS) (FREE) | 5 6 | MOSI (SPI1-MOSI) - * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | (FREE) - * (BEEPER) PB6 | 9 10 | PB5 (SD_DET) GND | 9 10 | 5V - * ------ ------ - * EXP1 EXP1 + * Board Display + * ------ ------ + * (SD_DET) PB5 |10 9 | PB6 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PA9 | 8 7 | RESET -- | 8 7 | (SD_DET) + * (SD_CS) PA10 6 5 | PB9 (MOSI) | 6 5 | -- + * (LCD_CS) PB8 | 4 3 | PB7 (SD_CS) | 4 3 | (LCD_CS) + * GND | 2 1 | 5V (SCK) | 2 1 | (MISO) + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * @@ -249,15 +249,15 @@ /** * FYSETC TFT TFT81050 display pinout * - * Board Display - * ------ ------ - * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) - * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) - * (FREE) PB9 | 5 6 | PA10 (SD_CS) (PB8) LCD_CS | 5 6 | MOSI (SPI1-MOSI) - * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | RESET - * (BEEPER) PB6 | 9 10 | PB5 (SD_DET) GND | 9 10 | 5V - * ------ ------ - * EXP1 EXP1 + * Board Display + * ------ ------ + * (SD_DET) PB5 |10 9 | PB6 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PA9 | 8 7 | RESET (RESET) | 8 7 | (SD_DET) + * (SD_CS) PA10 6 5 | PB9 (MOSI) | 6 5 | (LCD_CS) + * (LCD_CS) PB8 | 4 3 | PB7 (SD_CS) | 4 3 | (MOD_RESET) + * GND | 2 1 | 5V (SCK) | 2 1 | (MISO) + * ------ ------ + * EXP1 EXP1 * * Needs 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 a6cc5ffa60fbb..a92de805f75bc 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 @@ -98,7 +98,7 @@ * (LCD_EN) PB6 | 8 7 | PC12 (LCD_RS) (BTN_EN1) PD2 | 8 7 | PA15 (SD_SS) * (LCD_D4) PC13 6 5 | PB7 (LCD_D5) (BTN_EN2) PB8 6 5 | PB5 (MOSI) * (LCD_D6) PC15 | 4 3 | PC14 (LCD_D7) (SD_DETECT) PB9 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | NC + * GND | 2 1 | 5V GND | 2 1 | -- * ------ ------ * EXP1 EXP2 */ diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index ae54805a94c6f..5251c8547b05e 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -167,7 +167,7 @@ * PB10 | 8 7 | PE8 * PB14 6 5 | PB13 * PB12 | 4 3 | PB15 - * GND | 2 1 | 5V + * GND | 2 1 | 5V * ------ * EXP1 */ @@ -191,7 +191,7 @@ * PB10 | 8 7 | ? * PA6 6 5 | PA5 * PA4 | 4 3 | PA7 - * GND | 2 1 | 5V + * GND | 2 1 | 5V * ------ * EXP1 */ diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index e4c741eae7f92..bfddf051f692c 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -123,9 +123,9 @@ /** ------ ------ * (BEEPER) PC14 |10 9 | PC13 (BTN_ENC) (MISO) PB14 |10 9 | PB13 (SD_SCK) * (LCD_EN) PB9 | 8 7 | PB8 (LCD_RS) (BTN_EN1) PB3 | 8 7 | PB12 (SD_CS2) - * (LCD_D4) PB7 | 6 5 PB6 (LCD_D5) (BTN_EN2) PD2 | 6 5 PB15 (SD_MOSI) + * (LCD_D4) PB7 6 5 | PB6 (LCD_D5) (BTN_EN2) PD2 6 5 | PB15 (SD_MOSI) * (LCD_D6) PB5 | 4 3 | PB4 (LCD_D7) (SD_DETECT) PB11 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | NC + * GND | 2 1 | 5V GND | 2 1 | -- * ------ ------ * EXP1 EXP2 */ 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 e02d1db7863d5..b0303861c9192 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -145,7 +145,7 @@ * (LCD_EN) PA4 | 8 7 | PA5 (LCD_RS) (BTN_EN1) PB11 | 8 7 | PA15 (SD_SS) (BTN_EN1) PB11 | 8 7 | RESET * (LCD_D4) PA6 6 5 | PA7 (LCD_D5) (BTN_EN2) PB0 6 5 | PB15 (SD_MOSI) (BTN_EN2) PB0 6 5 | PA6 (LCD_D4) * (LCD_D6) PC4 | 4 3 | PC5 (LCD_D7) (SD_DETECT) PC10 | 4 3 | RESET (LCD_RS) PA5 | 4 3 | PA4 (LCD_EN) - * GND | 2 1 | 5V GND | 2 1 | NC GND | 2 1 | 5V + * GND | 2 1 | 5V GND | 2 1 | -- GND | 2 1 | 5V * ------ ------ ------ * EXP1 EXP2 "Ender-3 EXP1" */ 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 653ebd82a1dd3..99de2e43e7a33 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -197,16 +197,16 @@ #endif /** - * -----------------------------------BTT002 V1.0---------------------------------------- - * ------ ------ | - * PA3 | 1 2 | GND 5V | 1 2 | GND | - * NRESET | 3 4 | PC4 (SD_DET) (LCD_D7) PE13 | 3 4 | PE12 (LCD_D6) | - * (MOSI) PA7 | 5 6 | PB0 (BTN_EN2) (LCD_D5) PE11 | 5 6 | PE10 (LCD_D4) | - * (SD_SS) PA4 | 7 8 | PC5 (BTN_EN1) (LCD_RS) PE8 | 7 8 | PE9 (LCD_EN) | - * (SCK) PA5 | 9 10 | PA6 (MISO) (BTN_ENC) PB1 | 9 10 | PE7 (BEEPER) | - * ------ ------ | - * EXP2 EXP1 | - * -------------------------------------------------------------------------------------- + * ---------------------------------BTT002 V1.0--------------------------------- + * ------ ------ | + * (BEEPER) PE7 |10 9 | PB1 (BTN_ENC) (MISO) PA6 |10 9 | PA5 (SCK) | + * (LCD_EN) PE9 | 8 7 | PE8 (LCD_RS) (BTN_EN1) PC5 | 8 7 | PA4 (SD_SS) | + * (LCD_D4) PE10 6 5 | PE11 (LCD_D5) (BTN_EN2) PB0 6 5 | PA7 (MOSI) | + * (LCD_D6) PE12 | 4 3 | PE13 (LCD_D7) (SD_DET) PC4 | 4 3 | RESET | + * GND | 2 1 | 5V GND | 2 1 | PA3 | + * ------ ------ | + * EXP1 EXP2 | + * ------------------------------------------------------------------------------ */ #define EXP1_03_PIN PE13 #define EXP1_04_PIN PE12 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index e63b534effa5f..740164a197999 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -184,14 +184,14 @@ #endif /** - * BTT E3 RRF - * ----- - * 5V | 1 2 | GND - * (LCD_EN) PE11 | 3 4 | PB1 (LCD_RS) - * (LCD_D4) PE10 | 5 6 PB2 (BTN_EN2) - * RESET | 7 8 | PE7 (BTN_EN1) - * (BTN_ENC) PE9 | 9 10| PE8 (BEEPER) - * ----- + * BTT E3 RRF + * ------ + * (BEEPER) PE8 |10 9 | PE9 (BTN_ENC) + * (BTN_EN1) PE7 | 8 7 | RESET + * (BTN_EN2) PB2 6 5 | PE10 (LCD_D4) + * (LCD_RS) PB1 | 4 3 | PE11 (LCD_EN) + * GND | 2 1 | 5V + * ------ * EXP1 */ @@ -244,15 +244,15 @@ /** * TFTGLCD_PANEL_SPI display pinout * - * Board Display - * ----- ----- - * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) - * (FREE) PE11 | 3 4 | PB1 (LCD_CS) (PE7) LCD_CS | 3 4 | SD_CS (PB2) - * (FREE) PE10 | 5 6 | PB2 (SD_CS) (FREE) | 5 6 | MOSI (SPI1-MOSI) - * RESET | 7 8 | PE7 (MOD_RESET) (PE8) SD_DET | 7 8 | (FREE) - * (BEEPER) PE9 | 9 10| PE8 (SD_DET) GND | 9 10| 5V - * ----- ----- - * EXP1 EXP1 + * Board Display + * ------ ------ + * (SD_DET) PE8 |10 9 | PE9 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PE7 | 8 7 | RESET -- | 8 7 | (SD_DET) + * (SD_CS) PB2 6 5 | PE10 (MOSI) 6 5 | -- + * (LCD_CS) PB1 | 4 3 | PE11 (SD_CS) | 4 3 | (LCD_CS) + * GND | 2 1 | 5V (SCK) | 2 1 | (MISO) + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * @@ -293,15 +293,15 @@ /** FYSETC TFT TFT81050 display pinout * - * Board Display - * ----- ----- - * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) - * (FREE) PE11 | 3 4 | PB1 (LCD_CS) (PE7) MOD_RESET | 3 4 | SD_CS (PB2) - * (FREE) PE10 | 5 6 | PB2 (SD_CS) (PB1) LCD_CS | 5 6 | MOSI (SPI1-MOSI) - * RESET | 7 8 | PE7 (MOD_RESET) (PE8) SD_DET | 7 8 | RESET - * (BEEPER) PE9 | 9 10| PE8 (SD_DET) GND | 9 10| 5V - * ----- ----- - * EXP1 EXP1 + * Board Display + * ------ ------ + * (SD_DET) PE8 |10 9 | PE9 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PE7 | 8 7 | RESET RESET | 8 7 | (SD_DET) + * (SD_CS) PB2 6 5 | PE10 (MOSI) | 6 5 | (LCD_CS) + * (LCD_CS) PB1 | 4 3 | PE11 (SD_CS) | 4 3 | (MOD_RESET) + * GND | 2 1 | 5V (SCK) | 2 1 | (MISO) + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * 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 dfa9d8a7b9ddb..7db6c4922e881 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -365,14 +365,14 @@ #endif /** - * ------ ------ - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | PB10 (SD_DETECT) (LCD_D7) PG5 | 3 4 | PG6 (LCD_D6) - * (MOSI) PB15 | 5 6 | PH10 (BTN_EN2) (LCD_D5) PG7 | 5 6 | PG8 (LCD_D4) - * (SD_SS) PB12 | 7 8 | PD10 (BTN_EN1) (LCD_RS) PA8 | 7 8 | PC10 (LCD_EN) - * (SCK) PB13 | 9 10 | PB14 (MISO) (BTN_ENC) PA15 | 9 10 | PC11 (BEEPER) - * ------ ------ - * EXP2 EXP1 + * ------ ------ + * (BEEPER) PC11 |10 9 | PA15 (BTN_ENC) (MISO) PB14 |10 9 | PB13 (SCK) + * (LCD_EN) PC10 | 8 7 | PA8 (LCD_RS) (BTN_EN1) PD10 | 8 7 | PB12 (SD_SS) + * (LCD_D4) PG8 6 5 | PG7 (LCD_D5) (BTN_EN2) PH10 6 5 | PB15 (MOSI) + * (LCD_D6) PG6 | 4 3 | PG5 (LCD_D7) (SD_DETECT) PB10 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | -- + * ------ ------ + * EXP1 EXP2 */ #define EXP1_03_PIN PG5 #define EXP1_04_PIN PG6 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 9db0459be9549..04a7d9e0b4b2b 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -330,7 +330,7 @@ * (LCD_EN) PE9 | 8 7 | PE10 (LCD_RS) (BTN_EN1) PB2 | 8 7 | PA4 (SD_SS) * (LCD_D4) PE12 6 5 | PE13 (LCD_D5) (BTN_EN2) PB1 6 5 | PA7 (MOSI) * (LCD_D6) PE14 | 4 3 | PE15 (LCD_D7) (SD_DETECT) PC15 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | NC + * GND | 2 1 | 5V GND | 2 1 | -- * ------ ------ * EXP1 EXP2 */ @@ -379,14 +379,14 @@ #if ENABLED(BTT_MOTOR_EXPANSION) /** - * ------ ------ - * NC | 1 2 | GND NC | 1 2 | GND - * NC | 3 4 | M1EN M2EN | 3 4 | M3EN - * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG - * M2DIR | 7 8 | M2STP M2RX | 7 8 | M2DIAG - * M3DIR | 9 10 | M3STP M3RX | 9 10 | M3DIAG - * ------ ------ - * EXP2 EXP1 + * ------ ------ + * M3DIAG |10 9 | M3RX M3STP |10 9 | M3DIR + * M2DIAG | 8 7 | M2RX M2STP | 8 7 | M2DIR + * M1DIAG 6 5 | M1RX M1DIR 6 5 | M1STP + * M3EN | 4 3 | M2EN M1EN | 4 3 | -- + * GND | 2 1 | -- GND | 2 1 | -- + * ------ ------ + * EXP1 EXP2 */ // M1 on Driver Expansion Module @@ -534,9 +534,9 @@ * (ESP-CS) PB12 | 10 | | 7 | PB15 (ESP-MOSI) * 3.3V | 11 | | 6 | PB14 (ESP-MISO) * (ESP-IO0) PD7 | 12 | | 5 | PB13 (ESP-CLK) - * (ESP-IO4) PD10 | 13 | | 4 | NC - * NC | 14 | | 3 | PE15 (ESP-EN) - * (ESP-RX) PD8 | 15 | | 2 | NC + * (ESP-IO4) PD10 | 13 | | 4 | -- + * -- | 14 | | 3 | PE15 (ESP-EN) + * (ESP-RX) PD8 | 15 | | 2 | -- * (ESP-TX) PD9 | 16 | | 1 | PE14 (ESP-RST) * ------- * WIFI 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 1a1ac4ec2171a..5e424d4105fbd 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -317,7 +317,7 @@ * (LCD_EN) PD11 | 8 7 | PD10 (LCD_RS) (BTN_EN1) PG10 | 8 7 | PB12 (SD_SS) * (LCD_D4) PG2 6 5 | PG3 (LCD_D5) (BTN_EN2) PF11 6 5 | PB15 (MOSI) * (LCD_D6) PG6 | 4 3 | PG7 (LCD_D7) (SD_DETECT) PF12 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | NC + * GND | 2 1 | 5V GND | 2 1 | -- * ------ ------ * EXP1 EXP2 */ @@ -367,8 +367,8 @@ #if ENABLED(BTT_MOTOR_EXPANSION) /** ----- ----- - * NC | . . | GND NC | . . | GND - * NC | . . | M1EN M2EN | . . | M3EN + * -- | . . | GND -- | . . | GND + * -- | . . | M1EN M2EN | . . | M3EN * M1STP | . . M1DIR M1RX | . . M1DIAG * M2DIR | . . | M2STP M2RX | . . | M2DIAG * M3DIR | . . | M3STP M3RX | . . | M3DIAG @@ -466,13 +466,13 @@ * * The WYH_L12864 connector plug: * - * BEFORE AFTER - * ______ ______ - * GND | 1 2 | 5V 5V | 1 2 | GND - * CS | 3 4 | BTN_EN2 CS | 3 4 | BTN_EN2 - * SID | 5 6 BTN_EN1 SID | 5 6 BTN_EN1 - * SCK | 7 8 | BTN_ENC SCK | 7 8 | BTN_ENC - * MOSI | 9 10 | MOSI | 9 10 | + * BEFORE AFTER + * ------ ------ + * -- |10 9 | MOSI -- |10 9 | MOSI + * BTN_ENC | 8 7 | SCK BTN_ENC | 8 7 | SCK + * BTN_EN1 | 6 5 SID BTN_EN1 | 6 5 SID + * BTN_EN2 | 4 3 | CS BTN_EN2 | 4 3 | CS + * 5V | 2 1 | GND GND | 2 1 | 5V * ------ ------ * LCD LCD */ @@ -550,12 +550,12 @@ // /** - * ----- - * TX | 1 2 | GND Enable PG1 // Must be high for module to run - * Enable | 3 4 | GPIO2 Reset PG0 // active low, probably OK to leave floating - * Reset | 5 6 | GPIO0 GPIO2 PF15 // must be high (ESP3D software configures this with a pullup so OK to leave as floating) - * 3.3V | 7 8 | RX GPIO0 PF14 // Leave as unused (ESP3D software configures this with a pullup so OK to leave as floating) - * ----- + * ------ + * RX | 8 7 | 3.3V GPIO0 PF14 ... Leave as unused (ESP3D software configures this with a pullup so OK to leave as floating) + * GPIO0 | 6 5 | Reset GPIO2 PF15 ... must be high (ESP3D software configures this with a pullup so OK to leave as floating) + * GPIO2 | 4 3 | Enable Reset PG0 ... active low, probably OK to leave floating + * GND | 2 1 | TX Enable PG1 ... Must be high for module to run + * ------ * W1 */ #define ESP_WIFI_MODULE_COM 6 // Must also set either SERIAL_PORT or SERIAL_PORT_2 to this diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 6d23bc8b208eb..079d6dcccc1b9 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 @@ -333,14 +333,14 @@ #endif /** - * ------ ------ - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | PC4 (SD_DETECT) (LCD_D7) PE13 | 3 4 | PE12 (LCD_D6) - * (MOSI) PA7 | 5 6 PB2 (BTN_EN2) (LCD_D5) PE11 | 5 6 PE10 (LCD_D4) - * (SD_SS) PA4 | 7 8 | PE7 (BTN_EN1) (LCD_RS) PE9 | 7 8 | PB1 (LCD_EN) - * (SCK) PA5 | 9 10 | PA6 (MISO) (BTN_ENC) PB0 | 9 10 | PC5 (BEEPER) - * ------ ------ - * EXP2 EXP1 + * ------ ------ + * (BEEPER) PC5 |10 9 | PB0 (BTN_ENC) (MISO) PA6 |10 9 | PA5 (SCK) + * (LCD_EN) PB1 | 8 7 | PE9 (LCD_RS) (BTN_EN1) PE7 | 8 7 | PA4 (SD_SS) + * (LCD_D4) PE10 | 6 5 PE11 (LCD_D5) (BTN_EN2) PB2 | 6 5 PA7 (MOSI) + * (LCD_D6) PE12 | 4 3 | PE13 (LCD_D7) (SD_DETECT) PC4 | 4 3 | RESET + * GND | 2 1 | 5V GND | 2 1 | -- + * ------ ------ + * EXP1 EXP2 */ #define EXP1_03_PIN PE13 #define EXP1_04_PIN PE12 @@ -379,8 +379,8 @@ #if ENABLED(BTT_MOTOR_EXPANSION) /** ----- ----- - * NC | . . | GND NC | . . | GND - * NC | . . | M1EN M2EN | . . | M3EN + * -- | . . | GND -- | . . | GND + * -- | . . | M1EN M2EN | . . | M3EN * M1STP | . . M1DIR M1RX | . . M1DIAG * M2DIR | . . | M2STP M2RX | . . | M2DIAG * M3DIR | . . | M3STP M3RX | . . | M3DIAG @@ -562,9 +562,9 @@ * (ESP-CS) PB12 | 10 | | 7 | PB15 (ESP-MOSI) * 3.3V | 11 | | 6 | PB14 (ESP-MISO) * (ESP-IO0) PB10 | 12 | | 5 | PB13 (ESP-CLK) - * (ESP-IO4) PB11 | 13 | | 4 | NC - * NC | 14 | | 3 | 3.3V (ESP-EN) - * (ESP-RX) PD8 | 15 | | 2 | NC + * (ESP-IO4) PB11 | 13 | | 4 | -- + * -- | 14 | | 3 | 3.3V (ESP-EN) + * (ESP-RX) PD8 | 15 | | 2 | -- * (ESP-TX) PD9 | 16 | | 1 | PC14 (ESP-RST) * ------- * WIFI diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index af316cf4b1d05..514fad4b89242 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -181,7 +181,7 @@ * PE14 | 8 7 | PE12 PC5 | 8 7 | PF11 * PE10 6 5 | PE9 PC4 6 5 | PB15 * PE8 | 4 3 | PE7 PB2 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | NC + * GND | 2 1 | 5V GND | 2 1 | -- * ------ ------ * EXP1 EXP2 */ diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h index 054da62754651..29aff20ffd4fe 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h @@ -139,26 +139,26 @@ #endif /** - * ----- ----- - * 5V | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | PC3 (SD_DETECT) (LCD_D7) PB7 | 3 4 | PB6 (LCD_D6) - * (SD_MOSI) PA7 5 6 | PC11 (BTN_EN2) (LCD_D5) PB14 5 6 | PB13 (LCD_D4) - * (SD_SS) PA4 | 7 8 | PC10 (BTN_EN1) (LCD_RS) PB12 | 7 8 | PB15 (LCD_EN) - * (SD_SCK) PA5 | 9 10| PA6 (SD_MISO) (BTN_ENC) PC12 | 9 10| PC9 (BEEPER) - * ----- ----- - * EXP2 EXP1 + * ------ ------ + * (SD_MISO) PA6 |10 9 | PA5 (SD_SCK) (BEEPER) PC9 |10 9 | PC12 (BTN_ENC) + * (BTN_EN1) PC10 | 8 7 | PA4 (SD_SS) (LCD_EN) PB15 | 8 7 | PB12 (LCD_RS) + * (BTN_EN2) PC11 6 5 | PA7 (SD_MOSI) (LCD_D4) PB13 6 5 | PB14 (LCD_D5) + * (SD_DETECT) PC3 | 4 3 | RESET (LCD_D6) PB6 | 4 3 | PB7 (LCD_D7) + * GND | 2 1 | 5V GND | 2 1 | 5V + * ------ ------ + * EXP2 EXP1 */ /** -* ----- -* (BEEPER) PC9 | 1 2 | PC12 (BTN_ENC) -* (BTN_EN1) PC10 | 3 4 | PB14 (LCD_D5/MISO) -* (BTN_EN2) PC11 5 6 | PB13 (LCD_D4/SCK) -* (LCD_RS) PB12 | 7 8 | PB15 (LCD_EN/MOSI) -* GND | 9 10| 5V -* ----- -* EXP3 -*/ + * ------ + * 5V |10 9 | GND + * (LCD_EN/MOSI) PB15 | 8 7 | PB12 (LCD_RS) + * (LCD_D4/SCK) PB13 6 5 | PC11 (BTN_EN2) + * (LCD_D5/MISO) PB14 | 4 3 | PC10 (BTN_EN1) + * (BTN_ENC) PC12 | 2 1 | PC9 (BEEPER) + * ------ + * EXP3 + */ #define EXP1_03_PIN PB7 #define EXP1_04_PIN PB6 diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 85071034c2a8f..0e0266f1a4ca5 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -203,7 +203,7 @@ * PC11 | 8 7 | PD2 PC6 | 8 7 | PA4 * PC10 6 5 | PC12 PC7 6 5 | PA7 * PD0 | 4 3 | PD1 PB10 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | 5V + * GND | 2 1 | 5V GND | 2 1 | 5V * ------ ------ * EXP1 EXP2 */ diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h index 161884c322fb8..0e960a17e2c04 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h @@ -239,7 +239,7 @@ * (LCD_EN) PE11 | 8 7 | PD10 (LCD_RS) (BTN_EN1) PE9 | 8 7 | PA4 (SPI1 CS) * (LCD_D4) PD9 6 5 | PD8 (LCD_D5) (BTN_EN2) PE8 6 5 | PA7 (SPI1 MOSI) * (LCD_D6) PE15 | 4 3 | PE7 (LCD_D7) (SPI1_RS) PB11 | 4 3 | RESET - * GND | 2 1 | 5V GND | 2 1 | 3.3V + * GND | 2 1 | 5V GND | 2 1 | 3.3V * ------ ------ * EXP1 EXP2 */ @@ -261,25 +261,26 @@ #define EXP2_09_PIN PA5 #define EXP2_10_PIN PA6 -#ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD -#endif - -#if SD_CONNECTION_IS(ONBOARD) - #define ENABLE_SPI3 - #define SD_SS_PIN -1 - #define SDSS PC9 - #define SD_SCK_PIN PC10 - #define SD_MISO_PIN PC11 - #define SD_MOSI_PIN PC12 - #define SD_DETECT_PIN PC4 // SD_DETECT_PIN doesn't work with NO_SD_HOST_DRIVE disabled -#elif SD_CONNECTION_IS(LCD) - #define ENABLE_SPI1 - #define SDSS EXP2_07_PIN - #define SD_SCK_PIN EXP2_09_PIN - #define SD_MISO_PIN EXP2_10_PIN - #define SD_MOSI_PIN EXP2_05_PIN - #define SD_DETECT_PIN EXP2_04_PIN +#if ENABLED(SDSUPPORT) + #ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD + #endif + #if SD_CONNECTION_IS(ONBOARD) + #define ENABLE_SPI3 + #define SD_SS_PIN -1 + #define SDSS PC9 + #define SD_SCK_PIN PC10 + #define SD_MISO_PIN PC11 + #define SD_MOSI_PIN PC12 + #define SD_DETECT_PIN PC4 // SD_DETECT_PIN doesn't work with NO_SD_HOST_DRIVE disabled + #elif SD_CONNECTION_IS(LCD) + #define ENABLE_SPI1 + #define SDSS EXP2_07_PIN + #define SD_SCK_PIN EXP2_09_PIN + #define SD_MISO_PIN EXP2_10_PIN + #define SD_MOSI_PIN EXP2_05_PIN + #define SD_DETECT_PIN EXP2_04_PIN + #endif #endif #if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI) diff --git a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h index 6368142c3427f..bd4798209e6ab 100644 --- a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h +++ b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h @@ -184,12 +184,12 @@ // /** - * ______ - * 5V | 1 2 | GND - * PB15 | 3 4 | PB12 - * PB13 | 5 6 PC5 - * ---- | 7 8 | PC4 - * PB0 | 9 10 | PA14 + * ------ + * PA14 |10 9 | PB0 + * PC4 | 8 7 | -- + * PC5 | 6 5 PB13 + * PB12 | 4 3 | PB15 + * GND | 2 1 | 5V * ------ * EXP1 * @@ -209,12 +209,12 @@ #define EXP1_10_PIN PA14 #if ENABLED(CR10_STOCKDISPLAY) - /** ______ - * 5V | 1 2 | GND - * LCD_EN | 3 4 | LCD_RS - * LCD_D4 | 5 6 EN2 - * RESET | 7 8 | EN1 - * ENC | 9 10 | BEEPER + /** ------ + * BEEPER |10 9 | ENC + * EN1 | 8 7 | RESET + * EN2 | 6 5 LCD_D4 + * LCD_RS | 4 3 | LCD_EN + * GND | 2 1 | 5V * ------ */ #ifdef DISABLE_JTAGSWD @@ -230,12 +230,12 @@ #define BOARD_ST7920_DELAY_3 750 #elif ENABLED(MKS_MINI_12864) - /** ______ - * 5V | 1 2 | GND - * SPI-MOSI | 3 4 | SPI-CS - * A0 | 5 6 EN2 - * -- | 7 8 | EN1 - * ENC | 9 10 | SPI-SCK + /** ------ + * SCK |10 9 | ENC + * EN1 | 8 7 | -- + * EN2 | 6 5 A0 + * CS | 4 3 | MOSI + * GND | 2 1 | 5V * ------ */ #define DOGLCD_CS EXP1_04_PIN diff --git a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h index 75c7217163b8a..48f986e2ca70e 100644 --- a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h +++ b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h @@ -69,7 +69,7 @@ * (X_DIR) PB15 | · · | PB9 (X_CS) * (LCD_D4) PB13 | · · | AVDD * _CN8_ PB12 | · · | GND - * NC | · · | PC8 (HEATER_0) PA15 | · · | PA5 (SCLK) + * -- | · · | PC8 (HEATER_0) PA15 | · · | PA5 (SCLK) * IOREF | · · | PC9 (BEEPER) PC7 | · · | PA6 (MISO) * RESET | · · | PC10 (SERVO1_PIN) PB5 | · · | PA7 (MOSI) * +3.3V | · · | PC11 (HEATER_BED) PB3 | · · | PD14 (SD_DETECT) @@ -86,7 +86,7 @@ * PF3 | · · | PD4 PF4 | · · | PF15 * PF5 | · · | PD3 (E_STEP) PB6 | · · | PG14 (E_EN) * PF10 | · · | GND (E_DIR) PB2 | · · | PG9 (E_CS) - * NC | · · | PE2 GND | · · | PE8 + * -- | · · | PE2 GND | · · | PE8 * PA7 | · · | PE4 PD13 | · · | PE7 * PF2 | · · | PE5 PD12 | · · | GND * (Y_STEP) PF1 | · · | PE6 (Y_EN) (Z_STEP) PD11 | · · | PE10 (Z_EN) 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 cec1a838fc93d..7cbf9f9d58d19 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 @@ -144,28 +144,28 @@ /** * SKR Mini E3 V3.0 - * ------ - * 5V | 1 2 | GND - * (LCD_EN) PD6 | 3 4 | PB8 (LCD_RS) - * (LCD_D4) PB9 | 5 6 PA10 (BTN_EN2) - * RESET | 7 8 | PA9 (BTN_EN1) - * (BTN_ENC) PA15 | 9 10 | PB5 (BEEPER) - * ------ - * EXP1 + * ------ + * (BEEPER) PB5 |10 9 | PA15 (BTN_ENC) + * (BTN_EN1) PA9 | 8 7 | RESET + * (BTN_EN2) PA10 6 5 | PB9 (LCD_D4) + * (LCD_RS) PB8 | 4 3 | PD6 (LCD_EN) + * GND | 2 1 | 5V + * ------ + * EXP1 */ #define EXP1_09_PIN PA15 #define EXP1_03_PIN PD6 #if EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) /** - * ------ ------ ------ - * VCC | 1 2 | GND VCC | 1 2 | GND GND | 2 1 | VCC - * A | 3 4 | B A | 3 4 | B B | 4 3 | A - * | 5 6 TX BEEP | 5 6 ENT ENT | 6 5 | BEEP - * | 7 8 | RX TX | 7 8 | RX RX | 8 7 | TX - * BEEP | 9 10 | ENT | 9 10 | | 10 9 | - * ------ ------ ------ - * EXP1 DWIN DWIN (plug) + * ------ ------ ------ + * (ENT) |10 9 | (BEEP) |10 9 | |10 9 | + * (RX) | 8 7 | (RX) | 8 7 | (TX) RX | 8 7 | TX + * (TX) 6 5 | (ENT) 6 5 | (BEEP) ENT | 6 5 | BEEP + * (B) | 4 3 | (A) (B) | 4 3 | (A) B | 4 3 | A + * GND | 2 1 | (VCC) GND | 2 1 | VCC GND | 2 1 | VCC + * ------ ------ ------ + * EXP1 DWIN DWIN (plug) * * All pins are labeled as printed on DWIN PCB. Connect TX-TX, A-A and so on. */ @@ -226,15 +226,15 @@ /** * TFTGLCD_PANEL_SPI display pinout * - * Board Display - * ------ ------ - * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) - * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) LCD_CS | 3 4 | SD_CS (PA10) - * (FREE) PB9 | 5 6 | PA10 (SD_CS) (FREE) | 5 6 | MOSI (SPI1-MOSI) - * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | (FREE) - * (BEEPER) PB6 | 9 10 | PB5 (SD_DET) GND | 9 10 | 5V - * ------ ------ - * EXP1 EXP1 + * Board Display + * ------ ------ + * (BEEPER) PB6 |10 9 | PB5 (SD_DET) 5V |10 9 | GND + * RESET | 8 7 | PA9 (MOD_RESET) -- | 8 7 | (SD_DET) + * PB9 6 5 | PA10 (SD_CS) (MOSI) | 6 5 | -- + * PB7 | 4 3 | PB8 (LCD_CS) (SD_CS) | 4 3 | (LCD_CS) + * GND | 2 1 | 5V (SCK) | 2 1 | (MISO) + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * @@ -269,15 +269,15 @@ /** * FYSETC TFT TFT81050 display pinout * - * Board Display - * ------ ------ - * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) - * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) - * (FREE) PB9 | 5 6 | PA10 (SD_CS) (PB8) LCD_CS | 5 6 | MOSI (SPI1-MOSI) - * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | RESET - * (BEEPER) PB6 | 9 10 | PB5 (SD_DET) GND | 9 10 | 5V - * ------ ------ - * EXP1 EXP1 + * Board Display + * ------ ------ + * (SD_DET) PB5 |10 9 | PB6 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PA9 | 8 7 | RESET (RESET) | 8 7 | (SD_DET) + * (SD_CS) PA10 6 5 | PB9 (FREE) (MOSI) | 6 5 | (LCD_CS) + * (LCD_CS) PB8 | 4 3 | PB7 (FREE) (SD_CS) | 4 3 | (MOD_RESET) + * 5V | 2 1 | GND (SCK) | 2 1 | (MISO) + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * From d58daaa42c8e238b3e1eba4041ca5bcfa497c61f Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Tue, 28 Dec 2021 00:23:50 -0500 Subject: [PATCH 206/273] =?UTF-8?q?=F0=9F=9A=B8=20DWIN=20Enhanced=20improv?= =?UTF-8?q?e,=20fix,=20and=20extend=20(#23240)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Offset icon change to show mesh leveling status - Reset extruder position when enter to Move menu - New live end-stop diagnostic page - Editable firmware retracts settings for Tune and filament settings menu - Print Statistics page accessible from the Advanced Settings menu - Reset printer draws the boot image - Adds individual axes homing menu - Adds probe deploy/stow to Probe Settings menu - Updates lock screen - Rebuilds main buttons to support text caption in other languages - Increases probe offset limits to 60 mm - Fix M303 PID variable update - Fix Resume/Pause button update - Fix redraw of print done - Fix very large file name bug - Fix bug in bed manual leveling --- Marlin/src/gcode/lcd/M0_M1.cpp | 1 + Marlin/src/gcode/temp/M303.cpp | 11 +- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 698 ++++++++++-------- Marlin/src/lcd/e3v2/enhanced/dwin.h | 91 +-- Marlin/src/lcd/e3v2/enhanced/dwin_defines.h | 92 +++ Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp | 2 +- Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h | 2 +- Marlin/src/lcd/e3v2/enhanced/dwin_popup.cpp | 55 ++ Marlin/src/lcd/e3v2/enhanced/dwin_popup.h | 62 ++ Marlin/src/lcd/e3v2/enhanced/dwinui.cpp | 3 +- Marlin/src/lcd/e3v2/enhanced/dwinui.h | 51 +- Marlin/src/lcd/e3v2/enhanced/endstop_diag.cpp | 109 +++ Marlin/src/lcd/e3v2/enhanced/endstop_diag.h | 37 + Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp | 7 +- Marlin/src/lcd/e3v2/enhanced/lockscreen.h | 7 +- Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp | 22 +- Marlin/src/lcd/e3v2/enhanced/meshviewer.h | 22 +- Marlin/src/lcd/e3v2/enhanced/printstats.cpp | 76 ++ Marlin/src/lcd/e3v2/enhanced/printstats.h | 37 + Marlin/src/lcd/language/language_an.h | 2 +- Marlin/src/lcd/language/language_ca.h | 2 +- Marlin/src/lcd/language/language_cz.h | 10 +- Marlin/src/lcd/language/language_da.h | 2 +- Marlin/src/lcd/language/language_de.h | 2 +- Marlin/src/lcd/language/language_en.h | 12 +- Marlin/src/lcd/language/language_es.h | 2 +- Marlin/src/lcd/language/language_eu.h | 2 +- Marlin/src/lcd/language/language_fr.h | 2 +- Marlin/src/lcd/language/language_gl.h | 2 +- Marlin/src/lcd/language/language_hr.h | 2 +- Marlin/src/lcd/language/language_hu.h | 2 +- Marlin/src/lcd/language/language_it.h | 2 +- Marlin/src/lcd/language/language_nl.h | 2 +- Marlin/src/lcd/language/language_pl.h | 2 +- Marlin/src/lcd/language/language_pt_br.h | 2 +- Marlin/src/lcd/language/language_ro.h | 2 +- Marlin/src/lcd/language/language_ru.h | 74 +- Marlin/src/lcd/language/language_sk.h | 2 +- Marlin/src/lcd/language/language_sv.h | 2 +- Marlin/src/lcd/language/language_tr.h | 2 +- Marlin/src/lcd/language/language_uk.h | 74 +- Marlin/src/lcd/language/language_vi.h | 2 +- Marlin/src/lcd/language/language_zh_CN.h | 2 +- Marlin/src/lcd/language/language_zh_TW.h | 2 +- 44 files changed, 1071 insertions(+), 526 deletions(-) create mode 100644 Marlin/src/lcd/e3v2/enhanced/dwin_defines.h create mode 100644 Marlin/src/lcd/e3v2/enhanced/dwin_popup.cpp create mode 100644 Marlin/src/lcd/e3v2/enhanced/dwin_popup.h create mode 100644 Marlin/src/lcd/e3v2/enhanced/endstop_diag.cpp create mode 100644 Marlin/src/lcd/e3v2/enhanced/endstop_diag.h create mode 100644 Marlin/src/lcd/e3v2/enhanced/printstats.cpp create mode 100644 Marlin/src/lcd/e3v2/enhanced/printstats.h diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 6e3b84c020f06..6a93861407f1f 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -36,6 +36,7 @@ #elif ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" #elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #include "../../lcd/e3v2/enhanced/dwin_popup.h" #include "../../lcd/e3v2/enhanced/dwin.h" #endif diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index f823aefbed976..a43575933b9da 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -77,10 +77,17 @@ void GcodeSuite::M303() { return; } - const celsius_t temp = parser.celsiusval('S', default_temp); - const int c = parser.intval('C', 5); + const bool seenC = parser.seenval('C'); + const int c = seenC ? parser.value_int() : 5; + const bool seenS = parser.seenval('S'); + const celsius_t temp = seenS ? parser.value_celsius() : default_temp; const bool u = parser.boolval('U'); + #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + if (seenC) HMI_data.PidCycles = c; + if (seenS) { if (hid == H_BED) HMI_data.BedPidT = temp; else HMI_data.HotendPidT = temp; } + #endif + #if DISABLED(BUSY_WHILE_HEATING) KEEPALIVE_STATE(NOT_BUSY); #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index d1a9ba7077fda..64a85b4b2311d 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -23,8 +23,8 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.7.1 - * Date: 2021/11/09 + * Version: 3.9.1 + * Date: 2021/11/21 */ #include "../../../inc/MarlinConfigPre.h" @@ -32,6 +32,7 @@ #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) #include "dwin.h" +#include "dwin_popup.h" #include "../../fontutils.h" #include "../../marlinui.h" @@ -78,10 +79,18 @@ #include "../../../feature/powerloss.h" #endif +#if HAS_ESDIAG + #include "endstop_diag.h" +#endif + #if HAS_MESH #include "meshviewer.h" #endif +#if ENABLED(PRINTCOUNTER) + #include "printstats.h" +#endif + #include #include #include @@ -236,9 +245,12 @@ MenuClass *MaxJerkMenu = nullptr; MenuClass *StepsMenu = nullptr; MenuClass *HotendPIDMenu = nullptr; MenuClass *BedPIDMenu = nullptr; -#if EITHER(HAS_BED_PROBE, BABYSTEPPING) +#if HAS_BED_PROBE MenuClass *ZOffsetWizMenu = nullptr; #endif +#if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) + MenuClass *HomingMenu = nullptr; +#endif // Updatable menuitems pointers MenuItemClass *HotendTargetItem = nullptr; @@ -270,13 +282,23 @@ void HMI_ToggleLanguage() { #endif } +//----------------------------------------------------------------------------- +// Main Buttons +//----------------------------------------------------------------------------- + typedef struct { uint16_t x, y[2], w, h; } text_info_t; -void ICON_Button(const bool here, const int iconid, const frame_rect_t &ico, const text_info_t (&txt)[2]) { - const bool cn = HMI_IsChinese(); - DWIN_ICON_Show(true, false, false, ICON, iconid + here, ico.x, ico.y); - if (here) DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, ico.x, ico.y, ico.x + ico.w - 1, ico.y + ico.h - 1); - DWIN_Frame_AreaCopy(1, txt[cn].x, txt[cn].y[here], txt[cn].x + txt[cn].w - 1, txt[cn].y[here] + txt[cn].h - 1, ico.x + (ico.w - txt[cn].w) / 2, (ico.y + ico.h - 28) - txt[cn].h/2); +void ICON_Button(const bool selected, const int iconid, const frame_rect_t &ico, const text_info_t (&txt), FSTR_P caption) { + DWIN_ICON_Show(true, false, false, ICON, iconid + selected, ico.x, ico.y); + if (selected) DWINUI::Draw_Box(0, HMI_data.Highlight_Color, ico); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, txt.x, txt.y[selected], txt.x + txt.w - 1, txt.y[selected] + txt.h - 1, ico.x + (ico.w - txt.w) / 2, (ico.y + ico.h - 28) - txt.h/2); + } + else { + const uint16_t x = ico.x + (ico.w - strlen_P(caption)*DWINUI::fontWidth()) / 2, + y = (ico.y + ico.h - 28) - DWINUI::fontHeight() / 2; + DWINUI::Draw_String(x, y, caption); + } } // @@ -284,11 +306,8 @@ void ICON_Button(const bool here, const int iconid, const frame_rect_t &ico, con // void ICON_Print() { constexpr frame_rect_t ico = { 17, 110, 110, 100 }; - constexpr text_info_t txt[2] = { - { 1, { 417, 449 }, 30, 14 }, - { 1, { 405, 447 }, 27, 15 } - }; - ICON_Button(select_page.now == PAGE_PRINT, ICON_Print_0, ico, txt); + constexpr text_info_t txt = { 1, { 405, 447 }, 27, 15 }; + ICON_Button(select_page.now == PAGE_PRINT, ICON_Print_0, ico, txt, GET_TEXT_F(MSG_BUTTON_PRINT)); } // @@ -296,11 +315,8 @@ void ICON_Print() { // void ICON_Prepare() { constexpr frame_rect_t ico = { 145, 110, 110, 100 }; - constexpr text_info_t txt[2] = { - { 33, { 417, 449 }, 51, 14 }, - { 31, { 405, 447 }, 27, 15 } - }; - ICON_Button(select_page.now == PAGE_PREPARE, ICON_Prepare_0, ico, txt); + constexpr text_info_t txt = { 31, { 405, 447 }, 27, 15 }; + ICON_Button(select_page.now == PAGE_PREPARE, ICON_Prepare_0, ico, txt, GET_TEXT_F(MSG_PREPARE)); } // @@ -308,11 +324,8 @@ void ICON_Prepare() { // void ICON_Control() { constexpr frame_rect_t ico = { 17, 226, 110, 100 }; - constexpr text_info_t txt[2] = { - { 85, { 417, 449 }, 46, 14 }, - { 61, { 405, 447 }, 27, 15 } - }; - ICON_Button(select_page.now == PAGE_CONTROL, ICON_Control_0, ico, txt); + constexpr text_info_t txt = { 61, { 405, 447 }, 27, 15 }; + ICON_Button(select_page.now == PAGE_CONTROL, ICON_Control_0, ico, txt, GET_TEXT_F(MSG_CONTROL)); } // @@ -320,11 +333,8 @@ void ICON_Control() { // void ICON_StartInfo() { constexpr frame_rect_t ico = { 145, 226, 110, 100 }; - constexpr text_info_t txt[2] = { - { 133, { 417, 449 }, 23, 14 }, - { 91, { 405, 447 }, 27, 15 } - }; - ICON_Button(select_page.now == PAGE_INFO_LEVELING, ICON_Info_0, ico, txt); + constexpr text_info_t txt = { 91, { 405, 447 }, 27, 15 }; + ICON_Button(select_page.now == PAGE_INFO_LEVELING, ICON_Info_0, ico, txt, GET_TEXT_F(MSG_BUTTON_INFO)); } // @@ -332,11 +342,8 @@ void ICON_StartInfo() { // void ICON_Leveling() { constexpr frame_rect_t ico = { 145, 226, 110, 100 }; - constexpr text_info_t txt[2] = { - { 88, { 433, 464 }, 36, 14 }, - { 211, { 405, 447 }, 27, 15 } - }; - ICON_Button(select_page.now == PAGE_INFO_LEVELING, ICON_Leveling_0, ico, txt); + constexpr text_info_t txt = { 211, { 405, 447 }, 27, 15 }; + ICON_Button(select_page.now == PAGE_INFO_LEVELING, ICON_Leveling_0, ico, txt, GET_TEXT_F(MSG_BUTTON_LEVEL)); } // @@ -344,11 +351,8 @@ void ICON_Leveling() { // void ICON_Tune() { constexpr frame_rect_t ico = { 8, 232, 80, 100 }; - constexpr text_info_t txt[2] = { - { 0, { 433, 464 }, 32, 14 }, - { 121, { 405, 447 }, 27, 15 } - }; - ICON_Button(select_print.now == PRINT_SETUP, ICON_Setup_0, ico, txt); + constexpr text_info_t txt = { 121, { 405, 447 }, 27, 15 }; + ICON_Button(select_print.now == PRINT_SETUP, ICON_Setup_0, ico, txt, GET_TEXT_F(MSG_TUNE)); } // @@ -356,11 +360,8 @@ void ICON_Tune() { // void ICON_Pause() { constexpr frame_rect_t ico = { 96, 232, 80, 100 }; - constexpr text_info_t txt[2] = { - { 157, { 417, 449 }, 39, 14 }, - { 181, { 405, 447 }, 27, 15 } - }; - ICON_Button(select_print.now == PRINT_PAUSE_RESUME, ICON_Pause_0, ico, txt); + constexpr text_info_t txt = { 181, { 405, 447 }, 27, 15 }; + ICON_Button(select_print.now == PRINT_PAUSE_RESUME, ICON_Pause_0, ico, txt, GET_TEXT_F(MSG_BUTTON_PAUSE)); } // @@ -368,11 +369,8 @@ void ICON_Pause() { // void ICON_Resume() { constexpr frame_rect_t ico = { 96, 232, 80, 100 }; - constexpr text_info_t txt[2] = { - { 33, { 433, 464 }, 53, 14 }, - { 1, { 405, 447 }, 27, 15 } - }; - ICON_Button(select_print.now == PRINT_PAUSE_RESUME, ICON_Continue_0, ico, txt); + constexpr text_info_t txt = { 1, { 405, 447 }, 27, 15 }; + ICON_Button(select_print.now == PRINT_PAUSE_RESUME, ICON_Continue_0, ico, txt, GET_TEXT_F(MSG_BUTTON_RESUME)); } // @@ -380,13 +378,14 @@ void ICON_Resume() { // void ICON_Stop() { constexpr frame_rect_t ico = { 184, 232, 80, 100 }; - constexpr text_info_t txt[2] = { - { 196, { 417, 449 }, 29, 14 }, - { 151, { 405, 447 }, 27, 12 } - }; - ICON_Button(select_print.now == PRINT_STOP, ICON_Stop_0, ico, txt); + constexpr text_info_t txt = { 151, { 405, 447 }, 27, 12 }; + ICON_Button(select_print.now == PRINT_STOP, ICON_Stop_0, ico, txt, GET_TEXT_F(MSG_BUTTON_STOP)); } +//----------------------------------------------------------------------------- +// Drawing routines +//----------------------------------------------------------------------------- + void Draw_Menu_Cursor(const int8_t line) { DWIN_Draw_Rectangle(1, HMI_data.Cursor_color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); } @@ -422,10 +421,10 @@ void Erase_Menu_Text(const uint8_t line) { } void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false) { + if (icon) DWINUI::Draw_Icon(icon, ICOX, MBASE(line) - 3); if (label) DWINUI::Draw_String(LBLX, MBASE(line) - 1, (char*)label); - if (icon) DWINUI::Draw_Icon(icon, 26, MBASE(line) - 3); - if (more) DWINUI::Draw_Icon(ICON_More, 226, MBASE(line) - 3); - DWIN_Draw_Line(HMI_data.SplitLine_Color, 16, MBASE(line) + 33, 256, MBASE(line) + 33); + if (more) DWINUI::Draw_Icon(ICON_More, VALX + 16, MBASE(line) - 3); + DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MYPOS(line + 1), 240); } void Draw_Chkb_Line(const uint8_t line, const bool checked) { @@ -469,50 +468,21 @@ inline bool Apply_Encoder(const EncoderState &encoder_diffState, T &valref) { return encoder_diffState == ENCODER_DIFF_ENTER; } -// -// Draw Popup Windows -// - -inline void Draw_Popup_Bkgd_60() { - DWIN_Draw_Rectangle(1, HMI_data.PopupBg_color, 14, 60, 258, 330); - DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, 14, 60, 258, 330); -} - -inline void Draw_Popup_Bkgd_105() { - DWIN_Draw_Rectangle(1, HMI_data.PopupBg_color, 14, 105, 258, 374); - DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, 14, 105, 258, 374); -} - -void Clear_Popup_Area() { - DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); -} - -void DWIN_Draw_Popup1(const uint8_t icon) { +//PopUps +void Popup_window_PauseOrStop() { + if (HMI_IsChinese()) { DWINUI::ClearMenuArea(); - Draw_Popup_Bkgd_60(); - if (icon) DWINUI::Draw_Icon(icon, 101, 105); -} -void DWIN_Draw_Popup2(FSTR_P const fmsg2, uint8_t button) { - if (fmsg2) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 240, fmsg2); - if (button) DWINUI::Draw_Icon(button, 86, 280); -} - -void DWIN_Draw_Popup(const uint8_t icon, const char * const cmsg1, FSTR_P const fmsg2, uint8_t button) { - DWIN_Draw_Popup1(icon); - if (cmsg1) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 210, cmsg1); - DWIN_Draw_Popup2(fmsg2, button); -} - -void DWIN_Draw_Popup(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fmsg2, uint8_t button) { - DWIN_Draw_Popup1(icon); - if (fmsg1) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 210, fmsg1); - DWIN_Draw_Popup2(fmsg2, button); -} - -void DWIN_Popup_Continue(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fmsg2) { - HMI_SaveProcessID(WaitResponse); - DWIN_Draw_Popup(icon, fmsg1, fmsg2, ICON_Continue_E); // Button Continue + Draw_Popup_Bkgd(); + if (select_print.now == PRINT_PAUSE_RESUME) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); + else if (select_print.now == PRINT_STOP) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); + DWIN_Frame_AreaCopy(1, 220, 304, 264, 319, 130, 150); + DWINUI::Draw_Icon(ICON_Confirm_C, 26, 280); + DWINUI::Draw_Icon(ICON_Cancel_C, 146, 280); + Draw_Select_Highlight(true); DWIN_UpdateLCD(); + } + else + DWIN_Popup_ConfirmCancel(ICON_BLTouch, select_print.now == PRINT_PAUSE_RESUME ? GET_TEXT_F(MSG_PAUSE_PRINT) : GET_TEXT_F(MSG_STOP_PRINT)); } #if HAS_HOTEND @@ -521,7 +491,7 @@ void DWIN_Popup_Continue(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fm if (HMI_IsChinese()) { HMI_SaveProcessID(WaitResponse); DWINUI::ClearMenuArea(); - Draw_Popup_Bkgd_60(); + Draw_Popup_Bkgd(); DWINUI::Draw_Icon(ICON_TempTooLow, 102, 105); DWIN_Frame_AreaCopy(1, 103, 371, 136, 386, 69, 240); DWIN_Frame_AreaCopy(1, 170, 371, 270, 386, 102, 240); @@ -534,79 +504,25 @@ void DWIN_Popup_Continue(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fm #endif -void Popup_Window_Resume() { - Clear_Popup_Area(); - Draw_Popup_Bkgd_105(); - if (HMI_IsChinese()) { - DWIN_Frame_AreaCopy(1, 160, 338, 235, 354, 98, 135); - DWIN_Frame_AreaCopy(1, 103, 321, 271, 335, 52, 192); - DWINUI::Draw_Icon(ICON_Cancel_C, 26, 307); - DWINUI::Draw_Icon(ICON_Continue_C, 146, 307); - } - else { - DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 115, F("Continue Print")); - DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 192, F("It looks like the last")); - DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 212, F("file was interrupted.")); - DWINUI::Draw_Icon(ICON_Cancel_E, 26, 307); - DWINUI::Draw_Icon(ICON_Continue_E, 146, 307); - } -} - -void Draw_Select_Highlight(const bool sel) { - HMI_flag.select_flag = sel; - const uint16_t c1 = sel ? HMI_data.Highlight_Color : HMI_data.PopupBg_color, - c2 = sel ? HMI_data.PopupBg_color : HMI_data.Highlight_Color; - DWIN_Draw_Rectangle(0, c1, 25, 279, 126, 318); - DWIN_Draw_Rectangle(0, c1, 24, 278, 127, 319); - DWIN_Draw_Rectangle(0, c2, 145, 279, 246, 318); - DWIN_Draw_Rectangle(0, c2, 144, 278, 247, 319); -} - -void Popup_window_PauseOrStop() { - if (HMI_IsChinese()) { - DWINUI::ClearMenuArea(); - Draw_Popup_Bkgd_60(); - if (select_print.now == PRINT_PAUSE_RESUME) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); - else if (select_print.now == PRINT_STOP) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); - DWIN_Frame_AreaCopy(1, 220, 304, 264, 319, 130, 150); - DWINUI::Draw_Icon(ICON_Confirm_C, 26, 280); - DWINUI::Draw_Icon(ICON_Cancel_C, 146, 280); - } - else { - DWIN_Draw_Popup(ICON_BLTouch, F("Please confirm"), select_print.now == PRINT_PAUSE_RESUME ? GET_TEXT_F(MSG_PAUSE_PRINT) : GET_TEXT_F(MSG_STOP_PRINT)); - DWINUI::Draw_Icon(ICON_Confirm_E, 26, 280); - DWINUI::Draw_Icon(ICON_Cancel_E, 146, 280); - } - Draw_Select_Highlight(true); - DWIN_UpdateLCD(); -} - #if HAS_HOTEND || HAS_HEATED_BED void DWIN_Popup_Temperature(const bool toohigh) { - Clear_Popup_Area(); - Draw_Popup_Bkgd_105(); + DWINUI::ClearMenuArea(); + Draw_Popup_Bkgd(); + if (HMI_IsChinese()) { if (toohigh) { DWINUI::Draw_Icon(ICON_TempTooHigh, 102, 165); - if (HMI_IsChinese()) { DWIN_Frame_AreaCopy(1, 103, 371, 237, 386, 52, 285); DWIN_Frame_AreaCopy(1, 151, 389, 185, 402, 187, 285); DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); } else { - DWINUI::Draw_String(HMI_data.PopupTxt_Color, 36, 300, F("Nozzle or Bed temperature")); - DWINUI::Draw_String(HMI_data.PopupTxt_Color, 92, 300, F("is too high")); - } - } - else { - DWINUI::Draw_Icon(ICON_TempTooLow, 102, 165); - if (HMI_IsChinese()) { + DWINUI::Draw_Icon(ICON_TempTooLow, 102, 165); DWIN_Frame_AreaCopy(1, 103, 371, 270, 386, 52, 285); DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); } - else { - DWINUI::Draw_String(HMI_data.PopupTxt_Color, 36, 300, F("Nozzle or Bed temperature")); - DWINUI::Draw_String(HMI_data.PopupTxt_Color, 92, 300, F("is too low")); - } + } + else { + DWIN_Draw_Popup(toohigh ? ICON_TempTooHigh : ICON_TempTooLow, F("Nozzle or Bed temperature"), toohigh ? F("is too high") : F("is too low")); } } #endif @@ -642,7 +558,7 @@ void DWIN_CheckStatusMessage() { }; void DWIN_DrawStatusMessage() { - const uint8_t max_status_chars = DWIN_WIDTH / DWINUI::fontWidth(DWINUI::font); + const uint8_t max_status_chars = DWIN_WIDTH / DWINUI::fontWidth(); #if ENABLED(STATUS_MESSAGE_SCROLLING) @@ -693,12 +609,10 @@ void DWIN_DrawStatusMessage() { void Draw_Print_Labels() { if (HMI_IsChinese()) { - Title.FrameCopy(30, 1, 42, 14); // "Printing" DWIN_Frame_AreaCopy(1, 0, 72, 63, 86, 41, 173); // Printing Time DWIN_Frame_AreaCopy(1, 65, 72, 128, 86, 176, 173); // Remain } else { - Title.ShowCaption(GET_TEXT(MSG_PRINTING)); DWINUI::Draw_String( 46, 173, F("Print Time")); DWINUI::Draw_String(181, 173, F("Remain")); } @@ -732,27 +646,30 @@ void ICON_ResumeOrPause() { } void Draw_PrintProcess() { + if (HMI_IsChinese()) + Title.FrameCopy(30, 1, 42, 14); // "Printing" + else + Title.ShowCaption(GET_TEXT_F(MSG_PRINTING)); DWINUI::ClearMenuArea(); - Draw_Print_Labels(); - - ICON_Tune(); - ICON_ResumeOrPause(); - ICON_Stop(); - DWIN_Print_Header(sdprint ? card.longest_filename() : nullptr); - + Draw_Print_Labels(); DWINUI::Draw_Icon(ICON_PrintTime, 15, 173); DWINUI::Draw_Icon(ICON_RemainTime, 150, 171); - Draw_Print_ProgressBar(); Draw_Print_ProgressElapsed(); Draw_Print_ProgressRemain(); - + ICON_Tune(); + ICON_ResumeOrPause(); + ICON_Stop(); DWIN_UpdateLCD(); } void Goto_PrintProcess() { - if (checkkey == PrintProcess) return; + if (checkkey == PrintProcess) { + ICON_ResumeOrPause(); + DWIN_UpdateLCD(); + return; + } checkkey = PrintProcess; Draw_PrintProcess(); } @@ -762,30 +679,27 @@ void Draw_PrintDone() { _percent_done = 100; _remain_time = 0; + Title.ShowCaption(GET_TEXT_F(MSG_PRINT_DONE)); DWINUI::ClearMenuArea(); DWIN_Print_Header(nullptr); + Draw_Print_ProgressBar(); Draw_Print_Labels(); DWINUI::Draw_Icon(ICON_PrintTime, 15, 173); DWINUI::Draw_Icon(ICON_RemainTime, 150, 171); - Draw_Print_ProgressBar(); Draw_Print_ProgressElapsed(); Draw_Print_ProgressRemain(); - // show print done confirm - DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, 240, DWIN_WIDTH - 1, STATUS_Y - 1); - DWINUI::Draw_Icon(HMI_IsChinese() ? ICON_Confirm_C : ICON_Confirm_E, 86, 283); + DWINUI::Draw_Icon(HMI_IsChinese() ? ICON_Confirm_C : ICON_Confirm_E, 86, 273); + DWIN_UpdateLCD(); } void Draw_Main_Menu() { DWINUI::ClearMenuArea(); - if (HMI_IsChinese()) Title.FrameCopy(2, 2, 26, 13); // "Home" etc else Title.ShowCaption(MACHINE_NAME); - DWINUI::Draw_Icon(ICON_LOGO, 71, 52); // CREALITY logo - ICON_Print(); ICON_Prepare(); ICON_Control(); @@ -917,6 +831,18 @@ void update_variable() { DWINUI::Draw_Signed_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 210, 417, _offset); } + #if HAS_MESH + static bool _leveling_active = false; + if (_leveling_active != planner.leveling_active) { + _leveling_active = planner.leveling_active; + DWIN_Draw_Box(1, HMI_data.Background_Color, 186, 416, 20, 20); + if (_leveling_active) + DWINUI::Draw_Icon(ICON_SetZOffset, 186, 416); + else + DWINUI::Draw_Icon(ICON_Zoffset, 187, 416); + } + #endif + _draw_xyz_position(false); } @@ -933,14 +859,15 @@ void update_variable() { #endif void make_name_without_ext(char *dst, char *src, size_t maxlen=MENU_CHAR_LIMIT) { - char * const name = card.longest_filename(); - size_t pos = strlen(name); // index of ending nul + size_t pos = strlen(src); // index of ending nul // For files, remove the extension // which may be .gcode, .gco, or .g if (!card.flag.filenameIsDir) while (pos && src[pos] != '.') pos--; // find last '.' (stop at 0) + if (!pos) pos = strlen(src); // pos = 0 ('.' not found) restore pos + size_t len = pos; // nul or '.' if (len > maxlen) { // Keep the name short pos = len = maxlen; // move nul down @@ -1083,11 +1010,11 @@ void HMI_SDCardUpdate() { if (DWIN_lcd_sd_status != card.isMounted()) { DWIN_lcd_sd_status = card.isMounted(); //SERIAL_ECHOLNPGM("HMI_SDCardUpdate: ", DWIN_lcd_sd_status); - if (DWIN_lcd_sd_status) { + if (DWIN_lcd_sd_status) { // Media inserted if (checkkey == SelectFile) Redraw_SD_List(); } - else { + else { // Media removed // clean file icon if (checkkey == SelectFile) { Redraw_SD_List(); @@ -1140,7 +1067,7 @@ void Draw_Status_Area(const bool with_update) { #endif #if HAS_ZOFFSET_ITEM - DWINUI::Draw_Icon(ICON_Zoffset, 187, 416); + DWINUI::Draw_Icon(planner.leveling_active ? ICON_SetZOffset : ICON_Zoffset, 187, 416); #endif DWINUI::Draw_Signed_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 210, 417, BABY_Z_VAR); @@ -1188,7 +1115,7 @@ void Draw_Info_Menu() { DWINUI::Draw_CenteredString(268, F(CORP_WEBSITE)); LOOP_L_N(i, 3) { - DWINUI::Draw_Icon(ICON_PrintSize + i, 26, 99 + i * 73); + DWINUI::Draw_Icon(ICON_PrintSize + i, ICOX, 99 + i * 73); DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MBASE(2) + i * 73, 240); } @@ -1244,7 +1171,7 @@ void HMI_MainMenu() { queue.inject(F("G28Z\nG29")); // Force to get the current Z home position #else last_checkkey = MainMenu; - Goto_InfoMenu(); + Goto_Info_Menu(); #endif break; } @@ -1477,7 +1404,7 @@ void HMI_PauseOrStop() { #ifdef ACTION_ON_CANCEL hostui.cancel(); #endif - DWIN_Draw_Popup(ICON_BLTouch, F("Stopping...") , F("Please wait until done.")); + DWIN_Draw_Popup(ICON_BLTouch, F("Stopping..."), F("Please wait until done.")); } else Goto_PrintProcess(); // cancel stop @@ -1507,6 +1434,12 @@ void Draw_Main_Area() { case PrintProcess: Draw_PrintProcess(); break; case PrintDone: Draw_PrintDone(); break; case Info: Draw_Info_Menu(); break; + #if HAS_ESDIAG + case ESDiagProcess: Draw_EndStopDiag(); break; + #endif + #if ENABLED(PRINTCOUNTER) + case PrintStatsProcess: Draw_PrintStats(); break; + #endif case PauseOrStop: Popup_window_PauseOrStop(); break; #if ENABLED(ADVANCED_PAUSE_FEATURE) case FilamentPurge: Draw_Popup_FilamentPurge(); break; @@ -1524,6 +1457,7 @@ void Draw_Main_Area() { void HMI_ReturnScreen() { checkkey = last_checkkey; + wait_for_user = false; Draw_Main_Area(); return; } @@ -1532,7 +1466,6 @@ void HMI_Popup() { EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_ENTER) { - wait_for_user = false; HMI_ReturnScreen(); } } @@ -1563,6 +1496,15 @@ void EachMomentUpdate() { if (ELAPSED(ms, next_var_update_ms)) { next_var_update_ms = ms + DWIN_VAR_UPDATE_INTERVAL; update_variable(); + switch (checkkey) { + #if HAS_ESDIAG + case ESDiagProcess: + ESDiag.Update(); + break; + #endif + default: + break; + } } if (ELAPSED(ms, next_status_update_ms)) { @@ -1643,61 +1585,70 @@ void EachMomentUpdate() { #if ENABLED(POWER_LOSS_RECOVERY) else if (DWIN_lcd_sd_status && recovery.dwin_flag) { // resume print before power off - static bool recovery_flag = false; - - recovery.dwin_flag = false; - recovery_flag = true; - - auto update_selection = [&](const bool sel) { - HMI_flag.select_flag = sel; - const uint16_t c1 = sel ? HMI_data.PopupBg_color : HMI_data.Highlight_Color; - DWIN_Draw_Rectangle(0, c1, 25, 306, 126, 345); - DWIN_Draw_Rectangle(0, c1, 24, 305, 127, 346); - const uint16_t c2 = sel ? HMI_data.Highlight_Color : HMI_data.PopupBg_color; - DWIN_Draw_Rectangle(0, c2, 145, 306, 246, 345); - DWIN_Draw_Rectangle(0, c2, 144, 305, 247, 346); - }; - - Popup_Window_Resume(); - update_selection(true); - - // TODO: Get the name of the current file from someplace - // - //(void)recovery.interrupted_file_exists(); - SdFile *dir = nullptr; - const char * const filename = card.diveToFile(true, dir, recovery.info.sd_filename); - card.selectFileByName(filename); - DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 252, card.longest_filename()); - DWIN_UpdateLCD(); - - while (recovery_flag) { - EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_ENTER) { - recovery_flag = false; - if (HMI_flag.select_flag) break; - TERN_(POWER_LOSS_RECOVERY, queue.inject(F("M1000C"))); - return HMI_StartFrame(true); - } - else - update_selection(encoder_diffState == ENCODER_DIFF_CW); - - DWIN_UpdateLCD(); - } - watchdog_refresh(); - } - - select_print.set(PRINT_SETUP); - queue.inject(F("M1000")); - sdprint = true; - Goto_PrintProcess(); - Draw_Status_Area(true); + Goto_PowerLossRecovery(); } #endif // POWER_LOSS_RECOVERY DWIN_UpdateLCD(); } +#if ENABLED(POWER_LOSS_RECOVERY) + void Popup_PowerLossRecovery() { + DWINUI::ClearMenuArea(); + Draw_Popup_Bkgd(); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 160, 338, 235, 354, 98, 115); + DWIN_Frame_AreaCopy(1, 103, 321, 271, 335, 52, 167); + DWINUI::Draw_Icon(ICON_Cancel_C, 26, 280); + DWINUI::Draw_Icon(ICON_Continue_C, 146, 280); + } + else { + DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 70, GET_TEXT_F(MSG_OUTAGE_RECOVERY)); + DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 147, F("It looks like the last")); + DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 167, F("file was interrupted.")); + DWINUI::Draw_Icon(ICON_Cancel_E, 26, 280); + DWINUI::Draw_Icon(ICON_Continue_E, 146, 280); + } + SdFile *dir = nullptr; + const char * const filename = card.diveToFile(true, dir, recovery.info.sd_filename); + card.selectFileByName(filename); + DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 207, card.longest_filename()); + Draw_Select_Highlight(HMI_flag.select_flag); + DWIN_UpdateLCD(); + } + + void Goto_PowerLossRecovery() { + recovery.dwin_flag = false; + LCD_MESSAGE_F("Recovery from power loss"); + HMI_flag.select_flag = false; + Popup_PowerLossRecovery(); + last_checkkey = MainMenu; + checkkey = PwrlossRec; + } + + void HMI_PowerlossRecovery() { + EncoderState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (HMI_flag.select_flag) { + queue.inject(F("M1000C")); + select_page.reset(); + Goto_Main_Menu(); + } + else { + select_print.set(PRINT_SETUP); + queue.inject(F("M1000")); + sdprint = true; + Goto_PrintProcess(); + } + } + else + Draw_Select_Highlight(encoder_diffState != ENCODER_DIFF_CW); + DWIN_UpdateLCD(); + } +#endif // POWER_LOSS_RECOVERY + + void DWIN_HandleScreen() { switch (checkkey) { case MainMenu: HMI_MainMenu(); break; @@ -1720,18 +1671,31 @@ void DWIN_HandleScreen() { #endif case NothingToDo: break; case Locked: HMI_LockScreen(); break; + #if HAS_ESDIAG + case ESDiagProcess: HMI_Popup(); break; + #endif + #if ENABLED(PRINTCOUNTER) + case PrintStatsProcess: HMI_Popup(); break; + #endif default: break; } } +bool IDisPopUp() { // If ID is popup... + return (checkkey == NothingToDo) || + (checkkey == WaitResponse) || + (checkkey == Info) || + (checkkey == Homing) || + (checkkey == Leveling) || + TERN_(HAS_ESDIAG, (checkkey == ESDiagProcess) ||) + TERN_(PRINTCOUNTER, (checkkey == PrintStatsProcess) ||) + (checkkey == PauseOrStop) || + (checkkey == FilamentPurge); +} + void HMI_SaveProcessID(const uint8_t id) { if (checkkey != id) { - if ((checkkey != NothingToDo) && - (checkkey != WaitResponse) && - (checkkey != Homing) && - (checkkey != Leveling) && - (checkkey != PauseOrStop) && - (checkkey != FilamentPurge)) last_checkkey = checkkey; // if not a popup + if (!IDisPopUp()) last_checkkey = checkkey; // if previous is not a popup checkkey = id; } } @@ -1811,7 +1775,7 @@ void DWIN_PidTuning(pidresult_t result) { void DWIN_Print_Header(const char *text = nullptr) { static char headertxt[31] = ""; // Print header text - if (text != nullptr) { + if (text) { const int8_t size = _MIN((unsigned) 30, strlen_P(text)); LOOP_L_N(i, size) headertxt[i] = text[i]; headertxt[size] = '\0'; @@ -1929,8 +1893,8 @@ void MarlinUI::kill_screen(FSTR_P const lcd_error, FSTR_P const lcd_component) { void DWIN_RebootScreen() { DWIN_Frame_Clear(Color_Bg_Black); - DWINUI::Draw_Icon(ICON_LOGO, 71, 150); // CREALITY logo - DWINUI::Draw_CenteredString(Color_White, 200, F("Please wait until reboot.")); + DWIN_JPG_ShowAndCache(0); + DWINUI::Draw_CenteredString(Color_White, 220, F("Please wait until reboot. ")); DWIN_UpdateLCD(); delay(500); } @@ -2012,29 +1976,47 @@ void DWIN_Redraw_screen() { MeshViewer.Draw(); } } -#endif +#endif // HAS_MESH + +void DWIN_LockScreen() { + if (checkkey != Locked) { + lockScreen.rprocess = checkkey; + checkkey = Locked; + lockScreen.init(); + } +} + +void DWIN_UnLockScreen() { + if (checkkey == Locked) { + checkkey = lockScreen.rprocess; + Draw_Main_Area(); + } +} void HMI_LockScreen() { EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; lockScreen.onEncoder(encoder_diffState); - if (lockScreen.isUnlocked()) { - if (CurrentMenu == AdvancedSettings) - Draw_AdvancedSettings_Menu(); - else - Draw_Tune_Menu(); - } + if (lockScreen.isUnlocked()) DWIN_UnLockScreen(); } -void DWIN_LockScreen(const bool flag) { - HMI_flag.lock_flag = flag; - checkkey = Locked; - lockScreen.init(); -} +#if HAS_ESDIAG + void Draw_EndStopDiag() { + HMI_SaveProcessID(ESDiagProcess); + ESDiag.Draw(); + } +#endif -// -// NEW MENU SUBSYSTEM ========================================================= -// +#if ENABLED(PRINTCOUNTER) + void Draw_PrintStats() { + HMI_SaveProcessID(PrintStatsProcess); + PrintStats.Draw(); + } +#endif + +//============================================================================= +// NEW MENU SUBSYSTEM +//============================================================================= // On click functions @@ -2152,15 +2134,31 @@ void RebootPrinter() { HAL_reboot(); } -void Goto_InfoMenu(){ - checkkey = Info; +void Goto_Info_Menu(){ + HMI_SaveProcessID(Info); Draw_Info_Menu(); } +void Goto_Move_Menu() { + #if HAS_HOTEND + gcode.process_subcommands_now(F("G92E0")); // reset extruder position + planner.synchronize(); + #endif + Draw_Move_Menu(); +} + void DisableMotors() { queue.inject(F("M84")); } +void AutoLev() { queue.inject(F("G28Z\nG29")); } // Force to get the current Z home position + void AutoHome() { queue.inject_P(G28_STR); } +void HomeX() { queue.inject(F("G28X")); } + +void HomeY() { queue.inject(F("G28Y")); } + +void HomeZ() { queue.inject(F("G28Z")); } + void SetHome() { // Apply workspace offset, making the current position 0,0,0 queue.inject(F("G92 X0 Y0 Z0")); @@ -2285,8 +2283,6 @@ void SetPID(celsius_t t, heater_id_t h) { } #endif -void Goto_LockScreen() { DWIN_LockScreen(true); } - #if HAS_HOME_OFFSET void ApplyHomeOffset() { set_home_offset(HMI_value.axis, HMI_value.Value / MINUNITMULT); } void SetHomeOffsetX() { HMI_value.axis = X_AXIS; SetPFloatOnClick(-50, 50, UNITFDIGITS, ApplyHomeOffset); } @@ -2295,13 +2291,15 @@ void Goto_LockScreen() { DWIN_LockScreen(true); } #endif #if HAS_BED_PROBE - void SetProbeOffsetX() { SetPFloatOnClick(-50, 50, UNITFDIGITS); } - void SetProbeOffsetY() { SetPFloatOnClick(-50, 50, UNITFDIGITS); } + void SetProbeOffsetX() { SetPFloatOnClick(-60, 60, UNITFDIGITS); } + void SetProbeOffsetY() { SetPFloatOnClick(-60, 60, UNITFDIGITS); } void SetProbeOffsetZ() { SetPFloatOnClick(-10, 10, 2); } void ProbeTest() { LCD_MESSAGE(MSG_M48_TEST); queue.inject(F("G28O\nM48 P10")); } + void ProbeStow() { probe.stow(); } + void ProbeDeploy() { probe.deploy(); } #endif #if HAS_FILAMENT_SENSOR @@ -2409,6 +2407,8 @@ void SetFlow() { SetPIntOnClick(MIN_PRINT_FLOW, MAX_PRINT_FLOW, ApplyFlow); } void LevBed(uint8_t point) { char cmd[100] = ""; #if HAS_ONESTEP_LEVELING + static bool inLev = false; + if (inLev) return; char str_1[6] = "", str_2[6] = "", str_3[6] = ""; #define fmt "X:%s, Y:%s, Z:%s" float xpos = 0, ypos = 0, zval = 0; @@ -2444,8 +2444,10 @@ void LevBed(uint8_t point) { #if HAS_ONESTEP_LEVELING planner.synchronize(); + probe.stow(); gcode.process_subcommands_now(F("M420S0\nG28O")); planner.synchronize(); + inLev = true; zval = probe.probe_at_point(xpos, ypos, PROBE_PT_STOW); sprintf_P(cmd, PSTR(fmt), dtostrf(xpos, 1, 1, str_1), @@ -2453,6 +2455,7 @@ void LevBed(uint8_t point) { dtostrf(zval, 1, 2, str_3) ); ui.set_status(cmd); + inLev = false; #else planner.synchronize(); sprintf_P(cmd, PSTR(fmt), xpos, ypos); @@ -2572,6 +2575,13 @@ void SetStepsZ() { HMI_value.axis = Z_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP } #endif +#if ENABLED(FWRETRACT) + void SetRetractLength() { SetPFloatOnClick( 0, 10, UNITFDIGITS); }; + void SetRetractSpeed() { SetPFloatOnClick( 1, 90, UNITFDIGITS); }; + void SetZRaise() { SetPFloatOnClick( 0, 2, 2); }; + void SetRecoverSpeed() { SetPFloatOnClick( 1, 90, UNITFDIGITS); }; +#endif + // Menuitem Drawing functions ================================================= void onDrawMenuItem(MenuItemClass* menuitem, int8_t line) { @@ -2745,7 +2755,9 @@ void onDrawLanguage(MenuItemClass* menuitem, int8_t line) { void onDrawPwrLossR(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, recovery.enabled); } #endif -void onDrawEnableSound(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, ui.buzzer_enabled); } +#if ENABLED(SOUND_MENU_ITEM) + void onDrawEnableSound(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, ui.buzzer_enabled); } +#endif void onDrawSelColorItem(MenuItemClass* menuitem, int8_t line) { const uint16_t color = *(uint16_t*)static_cast(menuitem)->value; @@ -3025,9 +3037,12 @@ void onDrawStepsZ(MenuItemClass* menuitem, int8_t line) { void HMI_Menu() { EncoderState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (CurrentMenu != nullptr) CurrentMenu->onClick(); - } else if (CurrentMenu != nullptr) CurrentMenu->onScroll(encoder_diffState == ENCODER_DIFF_CW); + if (CurrentMenu) { + if (encoder_diffState == ENCODER_DIFF_ENTER) + CurrentMenu->onClick(); + else + CurrentMenu->onScroll(encoder_diffState == ENCODER_DIFF_CW); + } } // Get an integer value using the encoder without draw anything @@ -3079,8 +3094,8 @@ void HMI_SetInt() { int8_t val = HMI_GetInt(HMI_value.MinValue, HMI_value.MaxValue); switch (val) { case 0: return; break; - case 1: if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); break; - case 2: if (HMI_value.Apply != nullptr) HMI_value.Apply(); break; + case 1: if (HMI_value.LiveUpdate) HMI_value.LiveUpdate(); break; + case 2: if (HMI_value.Apply) HMI_value.Apply(); break; } } @@ -3089,8 +3104,8 @@ void HMI_SetIntNoDraw() { int8_t val = HMI_GetIntNoDraw(HMI_value.MinValue, HMI_value.MaxValue); switch (val) { case 0: return; break; - case 1: if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); break; - case 2: if (HMI_value.Apply != nullptr) HMI_value.Apply(); break; + case 1: if (HMI_value.LiveUpdate) HMI_value.LiveUpdate(); break; + case 2: if (HMI_value.Apply) HMI_value.Apply(); break; } } @@ -3099,8 +3114,8 @@ void HMI_SetPInt() { int8_t val = HMI_GetInt(HMI_value.MinValue, HMI_value.MaxValue); switch (val) { case 0: return; - case 1: if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); break; - case 2: *HMI_value.P_Int = HMI_value.Value; if (HMI_value.Apply != nullptr) HMI_value.Apply(); break; + case 1: if (HMI_value.LiveUpdate) HMI_value.LiveUpdate(); break; + case 2: *HMI_value.P_Int = HMI_value.Value; if (HMI_value.Apply) HMI_value.Apply(); break; } } @@ -3133,8 +3148,8 @@ void HMI_SetFloat() { const int8_t val = HMI_GetFloat(HMI_value.dp, HMI_value.MinValue, HMI_value.MaxValue); switch (val) { case 0: return; - case 1: if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); break; - case 2: if (HMI_value.Apply != nullptr) HMI_value.Apply(); break; + case 1: if (HMI_value.LiveUpdate) HMI_value.LiveUpdate(); break; + case 2: if (HMI_value.Apply) HMI_value.Apply(); break; } } @@ -3143,8 +3158,8 @@ void HMI_SetPFloat() { const int8_t val = HMI_GetFloat(HMI_value.dp, HMI_value.MinValue, HMI_value.MaxValue); switch (val) { case 0: return; - case 1: if (HMI_value.LiveUpdate != nullptr) HMI_value.LiveUpdate(); break; - case 2: *HMI_value.P_Float = HMI_value.Value / POW(10, HMI_value.dp); if (HMI_value.Apply != nullptr) HMI_value.Apply(); break; + case 1: if (HMI_value.LiveUpdate) HMI_value.LiveUpdate(); break; + case 2: *HMI_value.P_Float = HMI_value.Value / POW(10, HMI_value.dp); if (HMI_value.Apply) HMI_value.Apply(); break; } } @@ -3159,7 +3174,7 @@ void SetMenuTitle(frame_rect_t cn, const __FlashStringHelper* fstr) { void Draw_Prepare_Menu() { checkkey = Menu; - if (PrepareMenu == nullptr) PrepareMenu = new MenuClass(); + if (!PrepareMenu) PrepareMenu = new MenuClass(); if (CurrentMenu != PrepareMenu) { CurrentMenu = PrepareMenu; SetMenuTitle({133, 1, 28, 13}, GET_TEXT_F(MSG_PREPARE)); @@ -3168,16 +3183,22 @@ void Draw_Prepare_Menu() { #if ENABLED(ADVANCED_PAUSE_FEATURE) ADDMENUITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENT_MAN), onDrawSubMenu, Draw_FilamentMan_Menu); #endif - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_MOVE_AXIS), onDrawMoveSubMenu, Draw_Move_Menu); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_MOVE_AXIS), onDrawMoveSubMenu, Goto_Move_Menu); ADDMENUITEM(ICON_LevBed, GET_TEXT_F(MSG_BED_LEVELING), onDrawSubMenu, Draw_LevBedCorners_Menu); ADDMENUITEM(ICON_CloseMotor, GET_TEXT_F(MSG_DISABLE_STEPPERS), onDrawDisableMotors, DisableMotors); - ADDMENUITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawAutoHome, AutoHome); + #if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) + ADDMENUITEM(ICON_Homing, GET_TEXT_F(MSG_HOMING), onDrawSubMenu, Draw_Homing_Menu); + #else + ADDMENUITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawAutoHome, AutoHome); + #endif #if ENABLED(MESH_BED_LEVELING) ADDMENUITEM(ICON_ManualMesh, GET_TEXT_F(MSG_MANUAL_MESH), onDrawSubMenu, Draw_ManualMesh_Menu); #endif #if HAS_ZOFFSET_ITEM - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + #if HAS_BED_PROBE ADDMENUITEM(ICON_SetZOffset, GET_TEXT_F(MSG_PROBE_WIZARD), onDrawSubMenu, Draw_ZOffsetWiz_Menu); + #elif ENABLED(BABYSTEPPING) + ADDMENUITEM_P(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); #else ADDMENUITEM(ICON_SetHome, GET_TEXT_F(MSG_SET_HOME_OFFSETS), onDrawHomeOffset, SetHome); #endif @@ -3200,7 +3221,7 @@ void Draw_Prepare_Menu() { void Draw_LevBedCorners_Menu() { DWINUI::ClearMenuArea(); checkkey = Menu; - if (LevBedMenu == nullptr) LevBedMenu = new MenuClass(); + if (!LevBedMenu) LevBedMenu = new MenuClass(); if (CurrentMenu != LevBedMenu) { CurrentMenu = LevBedMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_BED_TRAMMING)); // TODO: Chinese, English "Bed Tramming" JPG @@ -3217,7 +3238,7 @@ void Draw_LevBedCorners_Menu() { void Draw_Control_Menu() { checkkey = Menu; - if (ControlMenu == nullptr) ControlMenu = new MenuClass(); + if (!ControlMenu) ControlMenu = new MenuClass(); if (CurrentMenu != ControlMenu) { CurrentMenu = ControlMenu; SetMenuTitle({103, 1, 28, 14}, GET_TEXT_F(MSG_CONTROL)); @@ -3232,18 +3253,18 @@ void Draw_Control_Menu() { #endif ADDMENUITEM(ICON_Reboot, GET_TEXT_F(MSG_RESET_PRINTER), onDrawMenuItem, RebootPrinter); ADDMENUITEM(ICON_AdvSet, GET_TEXT_F(MSG_ADVANCED_SETTINGS), onDrawSubMenu, Draw_AdvancedSettings_Menu); - ADDMENUITEM(ICON_Info, GET_TEXT_F(MSG_INFO_SCREEN), onDrawInfoSubMenu, Goto_InfoMenu); + ADDMENUITEM(ICON_Info, GET_TEXT_F(MSG_INFO_SCREEN), onDrawInfoSubMenu, Goto_Info_Menu); } CurrentMenu->draw(); } void Draw_AdvancedSettings_Menu() { checkkey = Menu; - if (AdvancedSettings == nullptr) AdvancedSettings = new MenuClass(); + if (!AdvancedSettings) AdvancedSettings = new MenuClass(); if (CurrentMenu != AdvancedSettings) { CurrentMenu = AdvancedSettings; SetMenuTitle({0}, GET_TEXT_F(MSG_ADVANCED_SETTINGS)); // TODO: Chinese, English "Advanced Settings" JPG - DWINUI::MenuItemsPrepare(12); + DWINUI::MenuItemsPrepare(15); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); #if HAS_HOME_OFFSET ADDMENUITEM(ICON_HomeOffset, GET_TEXT_F(MSG_SET_HOME_OFFSETS), onDrawSubMenu, Draw_HomeOffset_Menu); @@ -3273,14 +3294,21 @@ void Draw_AdvancedSettings_Menu() { #if HAS_MESH ADDMENUITEM(ICON_MeshViewer, GET_TEXT_F(MSG_MESH_VIEW), onDrawSubMenu, DWIN_MeshViewer); #endif - ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, Goto_LockScreen); + #if HAS_ESDIAG + ADDMENUITEM(ICON_ESDiag, F("End-stops diag."), onDrawSubMenu, Draw_EndStopDiag); + #endif + #if ENABLED(PRINTCOUNTER) + ADDMENUITEM(ICON_PrintStats, GET_TEXT_F(MSG_INFO_STATS_MENU), onDrawSubMenu, Draw_PrintStats); + ADDMENUITEM(ICON_PrintStatsReset, GET_TEXT_F(MSG_INFO_PRINT_COUNT_RESET), onDrawSubMenu, PrintStats.Reset); + #endif + ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, DWIN_LockScreen); } CurrentMenu->draw(); } void Draw_Move_Menu() { checkkey = Menu; - if (MoveMenu == nullptr) MoveMenu = new MenuClass(); + if (!MoveMenu) MoveMenu = new MenuClass(); if (CurrentMenu != MoveMenu) { CurrentMenu = MoveMenu; SetMenuTitle({192, 1, 42, 14}, GET_TEXT_F(MSG_MOVE_AXIS)); @@ -3294,13 +3322,13 @@ void Draw_Move_Menu() { #endif } CurrentMenu->draw(); - if (!all_axes_trusted()) LCD_MESSAGE_F("WARNING: position is unknown"); + if (!all_axes_trusted()) LCD_MESSAGE_F("WARNING: current position is unknown, home axes"); } #if HAS_HOME_OFFSET void Draw_HomeOffset_Menu() { checkkey = Menu; - if (HomeOffMenu == nullptr) HomeOffMenu = new MenuClass(); + if (!HomeOffMenu) HomeOffMenu = new MenuClass(); if (CurrentMenu != HomeOffMenu) { CurrentMenu = HomeOffMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); // TODO: Chinese, English "Set Home Offsets" JPG @@ -3317,16 +3345,18 @@ void Draw_Move_Menu() { #if HAS_BED_PROBE void Draw_ProbeSet_Menu() { checkkey = Menu; - if (ProbeSetMenu == nullptr) ProbeSetMenu = new MenuClass(); + if (!ProbeSetMenu) ProbeSetMenu = new MenuClass(); if (CurrentMenu != ProbeSetMenu) { CurrentMenu = ProbeSetMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_ZPROBE_SETTINGS)); // TODO: Chinese, English "Probe Settings" JPG - DWINUI::MenuItemsPrepare(5); + DWINUI::MenuItemsPrepare(7); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); ADDMENUITEM_P(ICON_ProbeOffsetX, GET_TEXT_F(MSG_ZPROBE_XOFFSET), onDrawPFloatMenu, SetProbeOffsetX, &probe.offset.x); ADDMENUITEM_P(ICON_ProbeOffsetY, GET_TEXT_F(MSG_ZPROBE_YOFFSET), onDrawPFloatMenu, SetProbeOffsetY, &probe.offset.y); ADDMENUITEM_P(ICON_ProbeOffsetZ, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetProbeOffsetZ, &probe.offset.z); ADDMENUITEM(ICON_ProbeTest, GET_TEXT_F(MSG_M48_TEST), onDrawMenuItem, ProbeTest); + ADDMENUITEM(ICON_ProbeStow, GET_TEXT_F(MSG_MANUAL_STOW), onDrawMenuItem, ProbeStow); + ADDMENUITEM(ICON_ProbeDeploy, GET_TEXT_F(MSG_MANUAL_DEPLOY), onDrawMenuItem, ProbeDeploy); } CurrentMenu->draw(); } @@ -3335,11 +3365,11 @@ void Draw_Move_Menu() { #if HAS_FILAMENT_SENSOR void Draw_FilSet_Menu() { checkkey = Menu; - if (FilSetMenu == nullptr) FilSetMenu = new MenuClass(); + if (!FilSetMenu) FilSetMenu = new MenuClass(); if (CurrentMenu != FilSetMenu) { CurrentMenu = FilSetMenu; CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_FILAMENT_SET)); - DWINUI::MenuItemsPrepare(6); + DWINUI::MenuItemsPrepare(10); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); #if HAS_FILAMENT_SENSOR ADDMENUITEM(ICON_Runout, GET_TEXT_F(MSG_RUNOUT_ENABLE), onDrawRunoutEnable, SetRunoutEnable); @@ -3354,6 +3384,12 @@ void Draw_Move_Menu() { ADDMENUITEM_P(ICON_FilLoad, GET_TEXT_F(MSG_FILAMENT_LOAD), onDrawPFloatMenu, SetFilLoad, &fc_settings[0].load_length); ADDMENUITEM_P(ICON_FilUnload, GET_TEXT_F(MSG_FILAMENT_UNLOAD), onDrawPFloatMenu, SetFilUnload, &fc_settings[0].unload_length); #endif + #if ENABLED(FWRETRACT) + ADDMENUITEM_P(ICON_FWRetLength, GET_TEXT_F(MSG_CONTROL_RETRACT), onDrawPFloatMenu, SetRetractLength, &fwretract.settings.retract_length); + ADDMENUITEM_P(ICON_FWRetSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_RETRACT_SPEED), onDrawPFloatMenu, SetRetractSpeed, &fwretract.settings.retract_feedrate_mm_s); + ADDMENUITEM_P(ICON_FWRetZRaise, GET_TEXT_F(MSG_CONTROL_RETRACT_ZHOP), onDrawPFloat2Menu, SetZRaise, &fwretract.settings.retract_zraise); + ADDMENUITEM_P(ICON_FWRecSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_UNRETRACT_SPEED), onDrawPFloatMenu, SetRecoverSpeed, &fwretract.settings.retract_recover_feedrate_mm_s); + #endif } CurrentMenu->draw(); } @@ -3361,7 +3397,7 @@ void Draw_Move_Menu() { void Draw_SelectColors_Menu() { checkkey = Menu; - if (SelectColorMenu == nullptr) SelectColorMenu = new MenuClass(); + if (!SelectColorMenu) SelectColorMenu = new MenuClass(); if (CurrentMenu != SelectColorMenu) { CurrentMenu = SelectColorMenu; SetMenuTitle({0}, F("Select Colors")); // TODO: Chinese, English "Select Color" JPG @@ -3392,7 +3428,7 @@ void Draw_SelectColors_Menu() { void Draw_GetColor_Menu() { checkkey = Menu; - if (GetColorMenu == nullptr) GetColorMenu = new MenuClass(); + if (!GetColorMenu) GetColorMenu = new MenuClass(); if (CurrentMenu != GetColorMenu) { CurrentMenu = GetColorMenu; SetMenuTitle({0}, F("Get Color")); // TODO: Chinese, English "Get Color" JPG @@ -3409,11 +3445,11 @@ void Draw_GetColor_Menu() { void Draw_Tune_Menu() { checkkey = Menu; - if (TuneMenu == nullptr) TuneMenu = new MenuClass(); + if (!TuneMenu) TuneMenu = new MenuClass(); if (CurrentMenu != TuneMenu) { CurrentMenu = TuneMenu; SetMenuTitle({73, 2, 28, 12}, GET_TEXT_F(MSG_TUNE)); // TODO: Chinese, English "Tune" JPG - DWINUI::MenuItemsPrepare(10); + DWINUI::MenuItemsPrepare(14); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_PrintProcess); ADDMENUITEM_P(ICON_Speed, GET_TEXT_F(MSG_SPEED), onDrawSpeedItem, SetSpeed, &feedrate_percentage); #if HAS_HOTEND @@ -3428,11 +3464,17 @@ void Draw_Tune_Menu() { #if HAS_ZOFFSET_ITEM && EITHER(HAS_BED_PROBE, BABYSTEPPING) ADDMENUITEM_P(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawZOffset, SetZOffset, &BABY_Z_VAR); #endif + #if ENABLED(FWRETRACT) + ADDMENUITEM_P(ICON_FWRetLength, GET_TEXT_F(MSG_CONTROL_RETRACT), onDrawPFloatMenu, SetRetractLength, &fwretract.settings.retract_length); + ADDMENUITEM_P(ICON_FWRetSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_RETRACT_SPEED), onDrawPFloatMenu, SetRetractSpeed, &fwretract.settings.retract_feedrate_mm_s); + ADDMENUITEM_P(ICON_FWRetZRaise, GET_TEXT_F(MSG_CONTROL_RETRACT_ZHOP), onDrawPFloat2Menu, SetZRaise, &fwretract.settings.retract_zraise); + ADDMENUITEM_P(ICON_FWRecSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_UNRETRACT_SPEED), onDrawPFloatMenu, SetRecoverSpeed, &fwretract.settings.retract_recover_feedrate_mm_s); + #endif ADDMENUITEM_P(ICON_Flow, GET_TEXT_F(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); #if ENABLED(ADVANCED_PAUSE_FEATURE) ADDMENUITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); #endif - ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, Goto_LockScreen); + ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, DWIN_LockScreen); #if HAS_LCD_BRIGHTNESS ADDMENUITEM_P(ICON_Brightness, F("LCD Brightness"), onDrawPInt8Menu, SetBrightness, &ui.brightness); #endif @@ -3442,7 +3484,7 @@ void Draw_Tune_Menu() { void Draw_Motion_Menu() { checkkey = Menu; - if (MotionMenu == nullptr) MotionMenu = new MenuClass(); + if (!MotionMenu) MotionMenu = new MenuClass(); if (CurrentMenu != MotionMenu) { CurrentMenu = MotionMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_MOTION)); // TODO: Chinese, English "Motion" JPG @@ -3462,7 +3504,7 @@ void Draw_Motion_Menu() { #if ENABLED(ADVANCED_PAUSE_FEATURE) void Draw_FilamentMan_Menu() { checkkey = Menu; - if (FilamentMenu == nullptr) FilamentMenu = new MenuClass(); + if (!FilamentMenu) FilamentMenu = new MenuClass(); if (CurrentMenu != FilamentMenu) { CurrentMenu = FilamentMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_FILAMENT_MAN)); // TODO: Chinese, English "Filament Management" JPG @@ -3482,7 +3524,7 @@ void Draw_Motion_Menu() { #if ENABLED(MESH_BED_LEVELING) void Draw_ManualMesh_Menu() { checkkey = Menu; - if (ManualMesh == nullptr) ManualMesh = new MenuClass(); + if (!ManualMesh) ManualMesh = new MenuClass(); if (CurrentMenu != ManualMesh) { CurrentMenu = ManualMesh; SetMenuTitle({0}, GET_TEXT_F(MSG_MANUAL_MESH)); // TODO: Chinese, English "Manual Mesh Leveling" JPG @@ -3525,20 +3567,20 @@ void Draw_Motion_Menu() { void Draw_Preheat1_Menu() { HMI_value.Preheat = 0; - if (PreheatMenu == nullptr) PreheatMenu = new MenuClass(); + if (!PreheatMenu) PreheatMenu = new MenuClass(); Draw_Preheat_Menu({59, 16, 81, 14}, F(PREHEAT_1_LABEL " Preheat Settings")); // TODO: English "PLA Settings" JPG } void Draw_Preheat2_Menu() { HMI_value.Preheat = 1; - if (PreheatMenu == nullptr) PreheatMenu = new MenuClass(); + if (!PreheatMenu) PreheatMenu = new MenuClass(); Draw_Preheat_Menu({142, 16, 82, 14}, F(PREHEAT_2_LABEL " Preheat Settings")); // TODO: English "ABS Settings" JPG } #ifdef PREHEAT_3_LABEL void Draw_Preheat3_Menu() { HMI_value.Preheat = 2; - if (PreheatMenu == nullptr) PreheatMenu = new MenuClass(); + if (!PreheatMenu) PreheatMenu = new MenuClass(); #define PREHEAT_3_TITLE PREHEAT_3_LABEL " Preheat Set." Draw_Preheat_Menu({0}, F(PREHEAT_3_TITLE)); // TODO: Chinese, English "Custom Preheat Settings" JPG } @@ -3548,7 +3590,7 @@ void Draw_Motion_Menu() { void Draw_Temperature_Menu() { checkkey = Menu; - if (TemperatureMenu == nullptr) TemperatureMenu = new MenuClass(); + if (!TemperatureMenu) TemperatureMenu = new MenuClass(); if (CurrentMenu != TemperatureMenu) { CurrentMenu = TemperatureMenu; SetMenuTitle({236, 2, 28, 12}, GET_TEXT_F(MSG_TEMPERATURE)); @@ -3576,7 +3618,7 @@ void Draw_Temperature_Menu() { void Draw_MaxSpeed_Menu() { checkkey = Menu; - if (MaxSpeedMenu == nullptr) MaxSpeedMenu = new MenuClass(); + if (!MaxSpeedMenu) MaxSpeedMenu = new MenuClass(); if (CurrentMenu != MaxSpeedMenu) { CurrentMenu = MaxSpeedMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_MAXSPEED)); @@ -3594,7 +3636,7 @@ void Draw_MaxSpeed_Menu() { void Draw_MaxAccel_Menu() { checkkey = Menu; - if (MaxAccelMenu == nullptr) MaxAccelMenu = new MenuClass(); + if (!MaxAccelMenu) MaxAccelMenu = new MenuClass(); if (CurrentMenu != MaxAccelMenu) { CurrentMenu = MaxAccelMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_ACCELERATION)); @@ -3613,7 +3655,7 @@ void Draw_MaxAccel_Menu() { #if HAS_CLASSIC_JERK void Draw_MaxJerk_Menu() { checkkey = Menu; - if (MaxJerkMenu == nullptr) MaxJerkMenu = new MenuClass(); + if (!MaxJerkMenu) MaxJerkMenu = new MenuClass(); if (CurrentMenu != MaxJerkMenu) { CurrentMenu = MaxJerkMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_JERK)); @@ -3632,7 +3674,7 @@ void Draw_MaxAccel_Menu() { void Draw_Steps_Menu() { checkkey = Menu; - if (StepsMenu == nullptr) StepsMenu = new MenuClass(); + if (!StepsMenu) StepsMenu = new MenuClass(); if (CurrentMenu != StepsMenu) { CurrentMenu = StepsMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_STEPS_PER_MM)); @@ -3651,7 +3693,7 @@ void Draw_Steps_Menu() { #if HAS_HOTEND void Draw_HotendPID_Menu() { checkkey = Menu; - if (HotendPIDMenu == nullptr) HotendPIDMenu = new MenuClass(); + if (!HotendPIDMenu) HotendPIDMenu = new MenuClass(); if (CurrentMenu != HotendPIDMenu) { CurrentMenu = HotendPIDMenu; CurrentMenu->MenuTitle.SetCaption(F("Hotend PID Settings")); @@ -3674,7 +3716,7 @@ void Draw_Steps_Menu() { #if HAS_HEATED_BED void Draw_BedPID_Menu() { checkkey = Menu; - if (BedPIDMenu == nullptr) BedPIDMenu = new MenuClass(); + if (!BedPIDMenu) BedPIDMenu = new MenuClass(); if (CurrentMenu != BedPIDMenu) { CurrentMenu = BedPIDMenu; CurrentMenu->MenuTitle.SetCaption(F("Bed PID Settings")); @@ -3694,10 +3736,10 @@ void Draw_Steps_Menu() { } #endif -#if EITHER(HAS_BED_PROBE, BABYSTEPPING) +#if HAS_BED_PROBE void Draw_ZOffsetWiz_Menu() { checkkey = Menu; - if (ZOffsetWizMenu == nullptr) ZOffsetWizMenu = new MenuClass(); + if (!ZOffsetWizMenu) ZOffsetWizMenu = new MenuClass(); if (CurrentMenu != ZOffsetWizMenu) { CurrentMenu = ZOffsetWizMenu; CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_PROBE_WIZARD)); @@ -3712,4 +3754,22 @@ void Draw_Steps_Menu() { } #endif +#if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) + void Draw_Homing_Menu() { + checkkey = Menu; + if (!HomingMenu) HomingMenu = new MenuClass(); + if (CurrentMenu != HomingMenu) { + CurrentMenu = HomingMenu; + CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_HOMING)); + DWINUI::MenuItemsPrepare(5); + ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_Prepare_Menu); + ADDMENUITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawMenuItem, AutoHome); + ADDMENUITEM(ICON_HomeX, GET_TEXT_F(MSG_AUTO_HOME_X), onDrawMenuItem, HomeX); + ADDMENUITEM(ICON_HomeY, GET_TEXT_F(MSG_AUTO_HOME_Y), onDrawMenuItem, HomeY); + ADDMENUITEM(ICON_HomeZ, GET_TEXT_F(MSG_AUTO_HOME_Z), onDrawMenuItem, HomeZ); + } + CurrentMenu->draw(); + } +#endif + #endif // DWIN_CREALITY_LCD_ENHANCED diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.h b/Marlin/src/lcd/e3v2/enhanced/dwin.h index 05b81c1019923..773c9c7bdfaf7 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.h @@ -24,8 +24,8 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.7.1 - * Date: 2021/11/09 + * Version: 3.9.1 + * Date: 2021/11/21 */ #include "../../../inc/MarlinConfigPre.h" @@ -45,7 +45,7 @@ #define HAS_ZOFFSET_ITEM 1 #endif -static constexpr size_t eeprom_data_size = 64; +#include "dwin_defines.h" enum processID : uint8_t { // Process ID @@ -59,11 +59,16 @@ enum processID : uint8_t { SelectFile, PrintProcess, PrintDone, + PwrlossRec, + Reboot, Info, // Popup Windows Homing, Leveling, + PidProcess, + ESDiagProcess, + PrintStatsProcess, PauseOrStop, FilamentPurge, WaitResponse, @@ -97,39 +102,6 @@ typedef struct { void (*LiveUpdate)() = nullptr; // Auxiliar live update function } HMI_value_t; -typedef struct { - uint16_t Background_Color = Def_Background_Color; - uint16_t Cursor_color = Def_Cursor_color; - uint16_t TitleBg_color = Def_TitleBg_color; - uint16_t TitleTxt_color = Def_TitleTxt_color; - uint16_t Text_Color = Def_Text_Color; - uint16_t Selected_Color = Def_Selected_Color; - uint16_t SplitLine_Color = Def_SplitLine_Color; - uint16_t Highlight_Color = Def_Highlight_Color; - uint16_t StatusBg_Color = Def_StatusBg_Color; - uint16_t StatusTxt_Color = Def_StatusTxt_Color; - uint16_t PopupBg_color = Def_PopupBg_color; - uint16_t PopupTxt_Color = Def_PopupTxt_Color; - uint16_t AlertBg_Color = Def_AlertBg_Color; - uint16_t AlertTxt_Color = Def_AlertTxt_Color; - uint16_t PercentTxt_Color = Def_PercentTxt_Color; - uint16_t Barfill_Color = Def_Barfill_Color; - uint16_t Indicator_Color = Def_Indicator_Color; - uint16_t Coordinate_Color = Def_Coordinate_Color; - #if HAS_PREHEAT - #ifdef PREHEAT_1_TEMP_HOTEND - int16_t HotendPidT = PREHEAT_1_TEMP_HOTEND; - int16_t PidCycles = 10; - #endif - #ifdef PREHEAT_1_TEMP_BED - int16_t BedPidT = PREHEAT_1_TEMP_BED; - #endif - #endif - #if ENABLED(PREVENT_COLD_EXTRUSION) - int16_t ExtMinT = EXTRUDE_MINTEMP; - #endif -} HMI_data_t; - typedef struct { uint8_t language; bool pause_flag:1; // printing is paused @@ -138,15 +110,24 @@ typedef struct { bool select_flag:1; // Popup button selected bool home_flag:1; // homing in course bool heat_flag:1; // 0: heating done 1: during heating - bool lock_flag:1; // 0: lock called from AdvSet 1: lock called from Tune } HMI_flag_t; extern HMI_value_t HMI_value; extern HMI_flag_t HMI_flag; -extern HMI_data_t HMI_data; extern uint8_t checkkey; extern millis_t dwin_heat_time; +// Popups +#if HAS_HOTEND || HAS_HEATED_BED + void DWIN_Popup_Temperature(const bool toohigh); +#endif +#if HAS_HOTEND + void Popup_Window_ETempTooLow(); +#endif +#if ENABLED(POWER_LOSS_RECOVERY) + void Popup_PowerLossRecovery(); +#endif + // SD Card void HMI_SDCardInit(); void HMI_SDCardUpdate(); @@ -154,8 +135,8 @@ void HMI_SDCardUpdate(); // Other void Goto_PrintProcess(); void Goto_Main_Menu(); -void Goto_InfoMenu(); -void Draw_Select_Highlight(const bool sel); +void Goto_Info_Menu(); +void Goto_PowerLossRecovery(); void Draw_Status_Area(const bool with_update); // Status Area void Draw_Main_Area(); // Redraw main area; void DWIN_Redraw_screen(); // Redraw all screen elements @@ -204,11 +185,18 @@ void DWIN_RebootScreen(); #endif // Utility and extensions +void DWIN_LockScreen(); +void DWIN_UnLockScreen(); void HMI_LockScreen(); -void DWIN_LockScreen(const bool flag = true); #if HAS_MESH void DWIN_MeshViewer(); #endif +#if HAS_ESDIAG + void Draw_EndStopDiag(); +#endif +#if ENABLED(PRINTCOUNTER) + void Draw_PrintStats(); +#endif // HMI user control functions void HMI_Menu(); @@ -262,23 +250,6 @@ void Draw_Steps_Menu(); #if EITHER(HAS_BED_PROBE, BABYSTEPPING) void Draw_ZOffsetWiz_Menu(); #endif - -// Popup windows - -void DWIN_Draw_Popup(const uint8_t icon, const char * const cmsg1, FSTR_P const fmsg2, uint8_t button=0); -void DWIN_Draw_Popup(const uint8_t icon, FSTR_P const fmsg1=nullptr, FSTR_P const fmsg2=nullptr, uint8_t button=0); - -template -void DWIN_Popup_Confirm(const uint8_t icon, T amsg1, U amsg2) { - HMI_SaveProcessID(WaitResponse); - DWIN_Draw_Popup(icon, amsg1, amsg2, ICON_Confirm_E); // Button Confirm - DWIN_UpdateLCD(); -} - -#if HAS_HOTEND || HAS_HEATED_BED - void DWIN_Popup_Temperature(const bool toohigh); -#endif -#if HAS_HOTEND - void Popup_Window_ETempTooLow(); +#if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) + void Draw_Homing_Menu(); #endif -void Popup_Window_Resume(); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_defines.h b/Marlin/src/lcd/e3v2/enhanced/dwin_defines.h new file mode 100644 index 0000000000000..b92d3d3b85e9b --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_defines.h @@ -0,0 +1,92 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * DWIN general defines and data structs + * Author: Miguel A. Risco-Castillo + * Version: 3.9.1 + * Date: 2021/11/21 + */ + +#include "../../../core/types.h" +#include "../common/dwin_color.h" + +#define Def_Background_Color RGB( 1, 12, 8) +#define Def_Cursor_color RGB(20, 49, 31) +#define Def_TitleBg_color RGB( 0, 23, 16) +#define Def_TitleTxt_color Color_White +#define Def_Text_Color Color_White +#define Def_Selected_Color Select_Color +#define Def_SplitLine_Color RGB( 0, 23, 16) +#define Def_Highlight_Color Color_White +#define Def_StatusBg_Color RGB( 0, 23, 16) +#define Def_StatusTxt_Color Color_Yellow +#define Def_PopupBg_color Color_Bg_Window +#define Def_PopupTxt_Color Popup_Text_Color +#define Def_AlertBg_Color Color_Bg_Red +#define Def_AlertTxt_Color Color_Yellow +#define Def_PercentTxt_Color Percent_Color +#define Def_Barfill_Color BarFill_Color +#define Def_Indicator_Color Color_White +#define Def_Coordinate_Color Color_White + +#define HAS_ESDIAG 1 +#define DEFAULT_LCD_BRIGHTNESS 127 + +typedef struct { +// Color settings + uint16_t Background_Color = Def_Background_Color; + uint16_t Cursor_color = Def_Cursor_color; + uint16_t TitleBg_color = Def_TitleBg_color; + uint16_t TitleTxt_color = Def_TitleTxt_color; + uint16_t Text_Color = Def_Text_Color; + uint16_t Selected_Color = Def_Selected_Color; + uint16_t SplitLine_Color = Def_SplitLine_Color; + uint16_t Highlight_Color = Def_Highlight_Color; + uint16_t StatusBg_Color = Def_StatusBg_Color; + uint16_t StatusTxt_Color = Def_StatusTxt_Color; + uint16_t PopupBg_color = Def_PopupBg_color; + uint16_t PopupTxt_Color = Def_PopupTxt_Color; + uint16_t AlertBg_Color = Def_AlertBg_Color; + uint16_t AlertTxt_Color = Def_AlertTxt_Color; + uint16_t PercentTxt_Color = Def_PercentTxt_Color; + uint16_t Barfill_Color = Def_Barfill_Color; + uint16_t Indicator_Color = Def_Indicator_Color; + uint16_t Coordinate_Color = Def_Coordinate_Color; +// + #if defined(PREHEAT_1_TEMP_HOTEND) && HAS_HOTEND + int16_t HotendPidT = PREHEAT_1_TEMP_HOTEND; + #endif + #if defined(PREHEAT_1_TEMP_BED) && HAS_HEATED_BED + int16_t BedPidT = PREHEAT_1_TEMP_BED; + #endif + #if ANY(HAS_HOTEND, HAS_HEATED_BED) + int16_t PidCycles = 10; + #endif + #if ENABLED(PREVENT_COLD_EXTRUSION) + int16_t ExtMinT = EXTRUDE_MINTEMP; + #endif +} HMI_data_t; + +static constexpr size_t eeprom_data_size = 64; +extern HMI_data_t HMI_data; diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp index 681b318a15e0b..83cbc207183da 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.cpp @@ -23,7 +23,7 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.7.1 + * Version: 3.8.1 * Date: 2021/11/09 */ diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h index 43cb098b91389..fc1b6d675609f 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_lcd.h @@ -24,7 +24,7 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.7.1 + * Version: 3.8.1 * Date: 2021/11/09 */ diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_popup.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin_popup.cpp new file mode 100644 index 0000000000000..89909e5c27669 --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_popup.cpp @@ -0,0 +1,55 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.8.1 + * Date: 2021/11/06 + */ + +#include "dwin.h" +#include "dwin_popup.h" + +void Draw_Select_Highlight(const bool sel) { + HMI_flag.select_flag = sel; + const uint16_t c1 = sel ? HMI_data.Highlight_Color : HMI_data.PopupBg_color, + c2 = sel ? HMI_data.PopupBg_color : HMI_data.Highlight_Color; + DWIN_Draw_Rectangle(0, c1, 25, 279, 126, 318); + DWIN_Draw_Rectangle(0, c1, 24, 278, 127, 319); + DWIN_Draw_Rectangle(0, c2, 145, 279, 246, 318); + DWIN_Draw_Rectangle(0, c2, 144, 278, 247, 319); +} + +void DWIN_Popup_Continue(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fmsg2) { + HMI_SaveProcessID(WaitResponse); + DWIN_Draw_Popup(icon, fmsg1, fmsg2, ICON_Continue_E); // Button Continue + DWIN_UpdateLCD(); +} + +void DWIN_Popup_ConfirmCancel(const uint8_t icon, FSTR_P const fmsg2) { + DWIN_Draw_Popup(ICON_BLTouch, F("Please confirm"), fmsg2); + DWINUI::Draw_Icon(ICON_Confirm_E, 26, 280); + DWINUI::Draw_Icon(ICON_Cancel_E, 146, 280); + Draw_Select_Highlight(true); + DWIN_UpdateLCD(); +} diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin_popup.h b/Marlin/src/lcd/e3v2/enhanced/dwin_popup.h new file mode 100644 index 0000000000000..65784a8c9f567 --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/dwin_popup.h @@ -0,0 +1,62 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * DWIN UI Enhanced implementation + * Author: Miguel A. Risco-Castillo + * Version: 3.8.1 + * Date: 2021/11/06 + */ + +#include "dwinui.h" +#include "dwin.h" + +// Popup windows + +void Draw_Select_Highlight(const bool sel); + +inline void Draw_Popup_Bkgd() { + DWIN_Draw_Rectangle(1, HMI_data.PopupBg_color, 14, 60, 258, 330); + DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, 14, 60, 258, 330); +} + +template +void DWIN_Draw_Popup(const uint8_t icon, T amsg1=nullptr, U amsg2=nullptr, uint8_t button=0) { + DWINUI::ClearMenuArea(); + Draw_Popup_Bkgd(); + if (icon) DWINUI::Draw_Icon(icon, 101, 105); + if (amsg1) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 210, amsg1); + if (amsg2) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 240, amsg2); + if (button) DWINUI::Draw_Icon(button, 86, 280); +} + +template +void DWIN_Popup_Confirm(const uint8_t icon, T amsg1, U amsg2) { + HMI_SaveProcessID(WaitResponse); + DWIN_Draw_Popup(icon, amsg1, amsg2, ICON_Confirm_E); // Button Confirm + DWIN_UpdateLCD(); +} + +void DWIN_Popup_Continue(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fmsg2); + +void DWIN_Popup_ConfirmCancel(const uint8_t icon, FSTR_P const fmsg2); diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp index 52b7c3b5213f9..501725374006b 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.cpp @@ -23,7 +23,7 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.7.1 + * Version: 3.8.1 * Date: 2021/11/09 */ @@ -34,6 +34,7 @@ #include "../../../inc/MarlinConfig.h" #include "dwin_lcd.h" #include "dwinui.h" +#include "dwin_defines.h" //#define DEBUG_OUT 1 #include "../../../core/debug_out.h" diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.h b/Marlin/src/lcd/e3v2/enhanced/dwinui.h index 9a717da80d7e2..c222b3aeb92a4 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.h @@ -24,8 +24,8 @@ /** * DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.7.1 - * Date: 2021/11/09 + * Version: 3.9.1 + * Date: 2021/11/21 */ #include "dwin_lcd.h" @@ -38,12 +38,20 @@ #define ICON_Cancel ICON_StockConfiguration #define ICON_CustomPreheat ICON_SetEndTemp #define ICON_Error ICON_TempTooHigh +#define ICON_ESDiag ICON_Info #define ICON_ExtrudeMinT ICON_HotendTemp #define ICON_FilLoad ICON_WriteEEPROM #define ICON_FilMan ICON_ResumeEEPROM #define ICON_FilSet ICON_ResumeEEPROM #define ICON_FilUnload ICON_ReadEEPROM #define ICON_Flow ICON_StepE +#define ICON_FWRetLength ICON_StepE +#define ICON_FWRetSpeed ICON_Setspeed +#define ICON_FWRetZRaise ICON_MoveZ +#define ICON_FWRecSpeed ICON_Setspeed +#define ICON_HomeX ICON_MoveX +#define ICON_HomeY ICON_MoveY +#define ICON_HomeZ ICON_MoveZ #define ICON_LevBed ICON_SetEndTemp #define ICON_Lock ICON_Cool #define ICON_ManualMesh ICON_HotendTemp @@ -52,9 +60,14 @@ #define ICON_MeshViewer ICON_HotendTemp #define ICON_MoveZ0 ICON_HotendTemp #define ICON_Park ICON_Motion +#define ICON_PIDbed ICON_SetBedTemp #define ICON_PIDcycles ICON_ResumeEEPROM #define ICON_PIDValue ICON_Contact +#define ICON_PrintStats ICON_PrintTime +#define ICON_PrintStatsReset ICON_RemainTime +#define ICON_ProbeDeploy ICON_SetEndTemp #define ICON_ProbeSet ICON_SetEndTemp +#define ICON_ProbeStow ICON_SetEndTemp #define ICON_ProbeTest ICON_SetEndTemp #define ICON_Pwrlossr ICON_Motion #define ICON_Reboot ICON_ResumeEEPROM @@ -63,25 +76,11 @@ #define ICON_SetCustomPreheat ICON_SetEndTemp #define ICON_Sound ICON_Cool -// Default UI Colors -#define Def_Background_Color Color_Bg_Black -#define Def_Cursor_color Rectangle_Color -#define Def_TitleBg_color Color_Bg_Blue -#define Def_TitleTxt_color Color_White -#define Def_Text_Color Color_White -#define Def_Selected_Color Select_Color -#define Def_SplitLine_Color Line_Color -#define Def_Highlight_Color Color_White -#define Def_StatusBg_Color RGB(0,20,20) -#define Def_StatusTxt_Color Color_Yellow -#define Def_PopupBg_color Color_Bg_Window -#define Def_PopupTxt_Color Popup_Text_Color -#define Def_AlertBg_Color Color_Bg_Red -#define Def_AlertTxt_Color Color_Yellow -#define Def_PercentTxt_Color Percent_Color -#define Def_Barfill_Color BarFill_Color -#define Def_Indicator_Color Color_White -#define Def_Coordinate_Color Color_White +// Extended and default UI Colors +#define Color_Black 0 +#define Color_Green RGB(0,63,0) +#define Color_Aqua RGB(0,63,31) +#define Color_Blue RGB(0,0,31) // UI element defines and constants #define DWIN_FONT_MENU font8x16 @@ -197,9 +196,11 @@ namespace DWINUI { // Get font character width uint8_t fontWidth(uint8_t cfont); + inline uint8_t fontWidth() { return fontWidth(font); }; // Get font character height uint8_t fontHeight(uint8_t cfont); + inline uint8_t fontHeight() { return fontHeight(font); }; // Get screen x coordinates from text column uint16_t ColToX(uint8_t col); @@ -412,6 +413,14 @@ namespace DWINUI { Draw_CenteredString(false, font, textcolor, backcolor, y, title); } + // Draw a box + // mode: 0=frame, 1=fill, 2=XOR fill + // color: Rectangle color + // frame: Box coordinates and size + inline void Draw_Box(uint8_t mode, uint16_t color, frame_rect_t frame) { + DWIN_Draw_Box(mode, color, frame.x, frame.y, frame.w, frame.h); + } + // Draw a circle // Color: circle color // x: abscissa of the center of the circle diff --git a/Marlin/src/lcd/e3v2/enhanced/endstop_diag.cpp b/Marlin/src/lcd/e3v2/enhanced/endstop_diag.cpp new file mode 100644 index 0000000000000..0f982c3a36c5a --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/endstop_diag.cpp @@ -0,0 +1,109 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * DWIN End Stops diagnostic page + * Author: Miguel A. Risco-Castillo + * Version: 1.0 + * Date: 2021/11/06 + */ + +#include "../../../inc/MarlinConfigPre.h" +#include "dwin_defines.h" + +#if BOTH(DWIN_CREALITY_LCD_ENHANCED, HAS_ESDIAG) + +#include "endstop_diag.h" + +#include "../../../core/types.h" +#include "../../marlinui.h" +#include "dwin_lcd.h" +#include "dwinui.h" +#include "dwin_popup.h" +#include "dwin.h" + +#if HAS_FILAMENT_SENSOR + #include "../../../feature/runout.h" +#endif + +#if HAS_BED_PROBE + #include "../../../module/probe.h" +#endif + +ESDiagClass ESDiag; + +void draw_es_label(FSTR_P const flabel=nullptr) { + DWINUI::cursor.x = 40; + if (flabel) DWINUI::Draw_String(F(flabel)); + DWINUI::Draw_String(F(": ")); + DWINUI::MoveBy(0, 25); +} + +void draw_es_state(const bool is_hit) { + const uint8_t LM = 130; + DWINUI::cursor.x = LM; + DWIN_Draw_Rectangle(1, HMI_data.PopupBg_color, LM, DWINUI::cursor.y, LM + 100, DWINUI::cursor.y + 20); + is_hit ? DWINUI::Draw_String(RGB(31,31,16), F(STR_ENDSTOP_HIT)) : DWINUI::Draw_String(RGB(16,63,16), F(STR_ENDSTOP_OPEN)); + DWINUI::MoveBy(0, 25); +} + +void ESDiagClass::Draw() { + Title.ShowCaption(F("End-stops Diagnostic")); + DWINUI::ClearMenuArea(); + Draw_Popup_Bkgd(); + DWINUI::Draw_Icon(ICON_Continue_E, 86, 250); + DWINUI::cursor.y = 80; + #define ES_LABEL(S) draw_es_label(F(STR_##S)) + #if HAS_X_MIN + ES_LABEL(X_MIN); + #endif + #if HAS_Y_MIN + ES_LABEL(Y_MIN); + #endif + #if HAS_Z_MIN + ES_LABEL(Z_MIN); + #endif + #if HAS_FILAMENT_SENSOR + draw_es_label(F(STR_FILAMENT)); + #endif + Update(); +} + +void ESDiagClass::Update() { + DWINUI::cursor.y = 80; + #define ES_REPORT(S) draw_es_state(READ(S##_PIN) != S##_ENDSTOP_INVERTING) + #if HAS_X_MIN + ES_REPORT(X_MIN); + #endif + #if HAS_Y_MIN + ES_REPORT(Y_MIN); + #endif + #if HAS_Z_MIN + ES_REPORT(Z_MIN); + #endif + #if HAS_FILAMENT_SENSOR + draw_es_state(READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE); + #endif + DWIN_UpdateLCD(); +} + +#endif // DWIN_CREALITY_LCD_ENHANCED && HAS_MESH diff --git a/Marlin/src/lcd/e3v2/enhanced/endstop_diag.h b/Marlin/src/lcd/e3v2/enhanced/endstop_diag.h new file mode 100644 index 0000000000000..1864b9572386c --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/endstop_diag.h @@ -0,0 +1,37 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * DWIN End Stops diagnostic page + * Author: Miguel A. Risco-Castillo + * Version: 1.0 + * Date: 2021/11/06 + */ + +class ESDiagClass { +public: + void Draw(); + void Update(); +}; + +extern ESDiagClass ESDiag; diff --git a/Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp b/Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp index ca772184f1482..8dc84dcc46c1d 100644 --- a/Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/lockscreen.cpp @@ -21,10 +21,10 @@ */ /** - * DWIN UI Enhanced implementation + * Lock screen implementation for DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.6.3 - * Date: 2021/09/08 + * Version: 2.1 + * Date: 2021/11/09 */ #include "../../../inc/MarlinConfigPre.h" @@ -41,6 +41,7 @@ LockScreenClass lockScreen; uint8_t LockScreenClass::lock_pos = 0; bool LockScreenClass::unlocked = false; +uint8_t LockScreenClass::rprocess = 0; void LockScreenClass::init() { lock_pos = 0; diff --git a/Marlin/src/lcd/e3v2/enhanced/lockscreen.h b/Marlin/src/lcd/e3v2/enhanced/lockscreen.h index f0c4c1fde8d23..f44ca418f1b62 100644 --- a/Marlin/src/lcd/e3v2/enhanced/lockscreen.h +++ b/Marlin/src/lcd/e3v2/enhanced/lockscreen.h @@ -22,10 +22,10 @@ #pragma once /** - * DWIN UI Enhanced implementation + * Lock screen implementation for DWIN UI Enhanced implementation * Author: Miguel A. Risco-Castillo - * Version: 3.6.3 - * Date: 2021/09/08 + * Version: 2.1 + * Date: 2021/11/09 */ #include "../common/encoder.h" @@ -36,6 +36,7 @@ class LockScreenClass { static bool unlocked; static uint8_t lock_pos; public: + static uint8_t rprocess; static void init(); static void onEncoder(EncoderState encoder_diffState); static void draw(); diff --git a/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp b/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp index 3824d63b2b48d..1ecbbff0aa4c9 100644 --- a/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/meshviewer.cpp @@ -1,12 +1,13 @@ /** - * DWIN Mesh Viewer - * Author: Miguel A. Risco-Castillo - * version: 3.8.1 - * Date: 2021/11/06 + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as - * published by the Free Software Foundation, either version 3 of the License, or + * 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, @@ -14,11 +15,18 @@ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * - * You should have received a copy of the GNU Lesser General Public License + * You should have received a copy of the GNU General Public License * along with this program. If not, see . * */ +/** + * DWIN Mesh Viewer + * Author: Miguel A. Risco-Castillo + * Version: 3.8.1 + * Date: 2021/11/06 + */ + #include "../../../inc/MarlinConfigPre.h" #if BOTH(DWIN_CREALITY_LCD_ENHANCED, HAS_MESH) diff --git a/Marlin/src/lcd/e3v2/enhanced/meshviewer.h b/Marlin/src/lcd/e3v2/enhanced/meshviewer.h index 0ba6ae2d7d158..6e7fe6fd827c1 100644 --- a/Marlin/src/lcd/e3v2/enhanced/meshviewer.h +++ b/Marlin/src/lcd/e3v2/enhanced/meshviewer.h @@ -1,12 +1,13 @@ /** - * DWIN Mesh Viewer - * Author: Miguel A. Risco-Castillo - * Version: 3.8.1 - * Date: 2021/11/06 + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as - * published by the Free Software Foundation, either version 3 of the License, or + * 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, @@ -14,12 +15,19 @@ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * - * You should have received a copy of the GNU Lesser General Public License + * You should have received a copy of the GNU General Public License * along with this program. If not, see . * */ #pragma once +/** + * DWIN Mesh Viewer + * Author: Miguel A. Risco-Castillo + * Version: 3.8.1 + * Date: 2021/11/06 + */ + class MeshViewerClass { public: void Draw(); diff --git a/Marlin/src/lcd/e3v2/enhanced/printstats.cpp b/Marlin/src/lcd/e3v2/enhanced/printstats.cpp new file mode 100644 index 0000000000000..54205363be1f8 --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/printstats.cpp @@ -0,0 +1,76 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * DWIN Print Stats page + * Author: Miguel A. Risco-Castillo + * Version: 1.0 + * Date: 2021/11/21 + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if BOTH(DWIN_CREALITY_LCD_ENHANCED, PRINTCOUNTER) + +#include "printstats.h" + +#include "../../../core/types.h" +#include "../../marlinui.h" +#include "../../../module/printcounter.h" +#include "dwin_lcd.h" +#include "dwinui.h" +#include "dwin_popup.h" +#include "dwin.h" + +PrintStatsClass PrintStats; + +void PrintStatsClass::Draw() { + char buf[50] = ""; + char str[30] = ""; + constexpr int8_t MRG = 30; + + Title.ShowCaption(GET_TEXT_F(MSG_INFO_STATS_MENU)); + DWINUI::ClearMenuArea(); + Draw_Popup_Bkgd(); + DWINUI::Draw_Icon(ICON_Continue_E, 86, 250); + printStatistics ps = print_job_timer.getStats(); + + sprintf_P(buf, PSTR("%s: %i"), GET_TEXT(MSG_INFO_PRINT_COUNT), ps.totalPrints); + DWINUI::Draw_String(MRG, 80, buf); + sprintf_P(buf, PSTR("%s: %i"), GET_TEXT(MSG_INFO_COMPLETED_PRINTS), ps.finishedPrints); + DWINUI::Draw_String(MRG, 100, buf); + duration_t(print_job_timer.getStats().printTime).toDigital(str, true); + sprintf_P(buf, PSTR("%s: %s"), GET_TEXT(MSG_INFO_PRINT_TIME), str); + DWINUI::Draw_String(MRG, 120, buf); + duration_t(print_job_timer.getStats().longestPrint).toDigital(str, true); + sprintf_P(buf, PSTR("%s: %s"), GET_TEXT(MSG_INFO_PRINT_LONGEST), str); + DWINUI::Draw_String(MRG, 140, buf); + sprintf_P(buf, PSTR("%s: %s m"), GET_TEXT(MSG_INFO_PRINT_FILAMENT), dtostrf(ps.filamentUsed / 1000, 1, 2, str)); + DWINUI::Draw_String(MRG, 160, buf); +} + +void PrintStatsClass::Reset() { + print_job_timer.initStats(); + HMI_AudioFeedback(); +} + +#endif // DWIN_CREALITY_LCD_ENHANCED && PRINTCOUNTER diff --git a/Marlin/src/lcd/e3v2/enhanced/printstats.h b/Marlin/src/lcd/e3v2/enhanced/printstats.h new file mode 100644 index 0000000000000..5f62a4c2688cc --- /dev/null +++ b/Marlin/src/lcd/e3v2/enhanced/printstats.h @@ -0,0 +1,37 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * DWIN Print Stats page + * Author: Miguel A. Risco-Castillo + * Version: 1.0 + * Date: 2021/11/21 + */ + +class PrintStatsClass { +public: + void Draw(); + static void Reset(); +}; + +extern PrintStatsClass PrintStats; diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index 8e4ff0e95cfc6..02d4455331d04 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -195,7 +195,7 @@ namespace Language_an { LSTR MSG_INFO_PROTOCOL = _UxGT("Protocolo"); LSTR MSG_CASE_LIGHT = _UxGT("Luz"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Conteo de impresion"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Tiempo total d'imp."); diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index 6fba76a552e1e..d70e6051b5db6 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -183,7 +183,7 @@ namespace Language_ca { LSTR MSG_INFO_PROTOCOL = _UxGT("Protocol"); LSTR MSG_CASE_LIGHT = _UxGT("Llum"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Total impressions"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Acabades"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Temps imprimint"); diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index 596591e0f66e4..20c8686a24870 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -60,7 +60,7 @@ namespace Language_cz { LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostart"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Uvolnit motory"); LSTR MSG_DEBUG_MENU = _UxGT("Nabídka ladění"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test ukaz. průběhu"); #else LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test uk. průběhu"); @@ -421,12 +421,12 @@ namespace Language_cz { LSTR MSG_PLEASE_RESET = _UxGT("Proveďte reset"); LSTR MSG_HEATING = _UxGT("Zahřívání..."); LSTR MSG_COOLING = _UxGT("Chlazení..."); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_BED_HEATING = _UxGT("Zahřívání podložky"); #else LSTR MSG_BED_HEATING = _UxGT("Zahřívání podl."); #endif - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_BED_COOLING = _UxGT("Chlazení podložky"); #else LSTR MSG_BED_COOLING = _UxGT("Chlazení podl."); @@ -465,7 +465,7 @@ namespace Language_cz { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jas světla"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("NESPRÁVNÁ TISKÁRNA"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Počet tisků"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Dokončeno"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Celkový čas"); @@ -535,7 +535,7 @@ namespace Language_cz { LSTR MSG_CYCLE_MIX = _UxGT("Střídat mix"); LSTR MSG_GRADIENT_MIX = _UxGT("Přechod mix"); LSTR MSG_REVERSE_GRADIENT = _UxGT("Opačný přechod"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_ACTIVE_VTOOL = _UxGT("Aktivní V-nástroj"); LSTR MSG_START_VTOOL = _UxGT("Spustit V-nástroj"); LSTR MSG_END_VTOOL = _UxGT("Ukončit V-nástroj"); diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index e032605578685..b3644a754c4d8 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -156,7 +156,7 @@ namespace Language_da { LSTR MSG_INFO_BOARD_MENU = _UxGT("Kort Info"); LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistors"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Ant. Prints"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Færdige"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Total print tid"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 00f759a83afc8..5ac0f1487b201 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -491,7 +491,7 @@ namespace Language_de { LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Falscher Drucker"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Gesamte Drucke"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Komplette Drucke"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Gesamte Druckzeit"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 1d8861b2c700d..c8660cd1c8c52 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -75,6 +75,9 @@ namespace Language_en { LSTR MSG_HOMING = _UxGT("Homing"); LSTR MSG_AUTO_HOME = _UxGT("Auto Home"); LSTR MSG_AUTO_HOME_A = _UxGT("Home @"); + LSTR MSG_AUTO_HOME_X = _UxGT("Home X"); + LSTR MSG_AUTO_HOME_Y = _UxGT("Home Y"); + LSTR MSG_AUTO_HOME_Z = _UxGT("Home Z"); LSTR MSG_FILAMENT_SET = _UxGT("Filament Settings"); LSTR MSG_FILAMENT_MAN = _UxGT("Filament Management"); LSTR MSG_LEVBED_FL = _UxGT("Front Left"); @@ -83,6 +86,7 @@ namespace Language_en { LSTR MSG_LEVBED_BL = _UxGT("Back Left"); LSTR MSG_LEVBED_BR = _UxGT("Back Right"); LSTR MSG_MANUAL_MESH = _UxGT("Manual Mesh"); + LSTR MSG_AUTO_MESH = _UxGT("Auto Build Mesh"); LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Align"); LSTR MSG_ITERATION = _UxGT("G34 Iteration: %i"); LSTR MSG_DECREASING_ACCURACY = _UxGT("Accuracy Decreasing!"); @@ -426,6 +430,11 @@ namespace Language_en { LSTR MSG_BUTTON_BACK = _UxGT("Back"); LSTR MSG_BUTTON_PROCEED = _UxGT("Proceed"); LSTR MSG_BUTTON_SKIP = _UxGT("Skip"); + LSTR MSG_BUTTON_INFO = _UxGT("Info"); + LSTR MSG_BUTTON_LEVEL = _UxGT("Level"); + LSTR MSG_BUTTON_PAUSE = _UxGT("Pause"); + LSTR MSG_BUTTON_RESUME = _UxGT("Resume"); + LSTR MSG_BUTTON_ADVANCED = _UxGT("Advanced"); LSTR MSG_PAUSING = _UxGT("Pausing..."); LSTR MSG_PAUSE_PRINT = _UxGT("Pause Print"); LSTR MSG_RESUME_PRINT = _UxGT("Resume Print"); @@ -577,7 +586,8 @@ namespace Language_en { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Light Brightness"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("INCORRECT PRINTER"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 + LSTR MSG_INFO_PRINT_COUNT_RESET = _UxGT("Reset Print Count"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Print Count"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completed"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Total Print Time"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 9c593215bbd7f..1dbc7faf70006 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -463,7 +463,7 @@ namespace Language_es { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Brillo cabina"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Impresora incorrecta"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Cont. de impresión"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Tiempo total de imp."); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index adc812f6ffee9..ad6a4f3071761 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -280,7 +280,7 @@ namespace Language_eu { LSTR MSG_INFO_PROTOCOL = _UxGT("Protokoloa"); LSTR MSG_CASE_LIGHT = _UxGT("Kabina Argia"); LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Argiaren Distira"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Inprim. Zenbaketa"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Burututa"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Inprim. denbora"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index e9c55ed4018d7..d72578d8d629a 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -504,7 +504,7 @@ namespace Language_fr { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Luminosité"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Imprimante incorrecte"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Nbre impressions"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Terminées"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Tps impr. total"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 1f3acf5f09b0c..3026e761c415e 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -479,7 +479,7 @@ namespace Language_gl { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Brillo Luces"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("IMPRESORA INCORRECTA"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Total Impresións"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Tempo Total Imp."); diff --git a/Marlin/src/lcd/language/language_hr.h b/Marlin/src/lcd/language/language_hr.h index 23be8abbb185f..78db2ad66029f 100644 --- a/Marlin/src/lcd/language/language_hr.h +++ b/Marlin/src/lcd/language/language_hr.h @@ -137,7 +137,7 @@ namespace Language_hr { LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Neispravan pisač"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Broj printova"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Završeni"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Ukupno printanja"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 204091f5d5611..cfe7af58974c6 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -553,7 +553,7 @@ namespace Language_hu { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Fényerösség"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("HELYTELEN NYOMTATÓ"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Nyomtatás számláló"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Befejezett"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Összes nyomtatási idö"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 780f4e9743e49..e0ae0e62a489e 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -562,7 +562,7 @@ namespace Language_it { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Luminosità Luci"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("STAMPANTE ERRATA"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Contat. stampa"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completati"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Tempo totale"); diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index 42df92b880394..e55ed9fea78fb 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -180,7 +180,7 @@ namespace Language_nl { LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Onjuiste printer"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Printed Aantal"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Totaal Voltooid"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Totale Printtijd"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index bf94feea54ec6..7c012f46df5a4 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -430,7 +430,7 @@ namespace Language_pl { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jasność oświetlenia"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Niepoprawna drukarka"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Wydrukowano"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Ukończono"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Czas druku"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index c66f717f9d283..0c44145e00e22 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -400,7 +400,7 @@ namespace Language_pt_br { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Intensidade Brilho"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Impressora Incorreta"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Total de Impressões"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Realizadas"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Tempo de Impressão"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index fee63dc2ad903..29cdc51c80e99 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -486,7 +486,7 @@ namespace Language_ro { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Light Brightness"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("INCORRECT PRINTER"); -#if LCD_WIDTH >= 20 +#if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Total Printuri"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completat"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Timp Imprimare Total"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 495410500a509..774636f1ed10b 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -43,7 +43,7 @@ namespace Language_ru { LSTR MSG_MEDIA_INSERTED = _UxGT("SD карта вставлена"); LSTR MSG_MEDIA_REMOVED = _UxGT("SD карта извлечена"); LSTR MSG_MEDIA_WAITING = _UxGT("Вставьте SD карту"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Сбой инициализации SD"); #else LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Сбой инициализ. SD"); @@ -51,7 +51,7 @@ namespace Language_ru { LSTR MSG_MEDIA_READ_ERROR = _UxGT("Ошибка считывания"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB диск удалён"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("Ошибка USB диска"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переполнение вызова"); #else LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переполн. вызова"); @@ -81,7 +81,7 @@ namespace Language_ru { LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Следующая точка"); LSTR MSG_LEVEL_BED_DONE = _UxGT("Выравнивание готово!"); LSTR MSG_Z_FADE_HEIGHT = _UxGT("Высота спада"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_SET_HOME_OFFSETS = _UxGT("Установ. смещения дома"); LSTR MSG_HOME_OFFSET_X = _UxGT("Смещение дома X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Смещение дома Y"); @@ -101,7 +101,7 @@ namespace Language_ru { LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Смещения применены"); LSTR MSG_SET_ORIGIN = _UxGT("Установить ноль"); LSTR MSG_SELECT_ORIGIN = _UxGT("Выберите ноль"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_LAST_VALUE_SP = _UxGT("Последнее знач. "); #else LSTR MSG_LAST_VALUE_SP = _UxGT("Послед. знач. "); @@ -127,7 +127,7 @@ namespace Language_ru { LSTR MSG_COOLDOWN = _UxGT("Охлаждение"); LSTR MSG_CUTTER_FREQUENCY = _UxGT("Частота"); LSTR MSG_LASER_MENU = _UxGT("Управление лазером"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_SPINDLE_MENU = _UxGT("Управление шпинделем"); LSTR MSG_LASER_TOGGLE = _UxGT("Переключить лазер"); LSTR MSG_SPINDLE_TOGGLE = _UxGT("Переключ.шпиндель"); @@ -161,7 +161,7 @@ namespace Language_ru { LSTR MSG_LEVEL_BED = _UxGT("Выровнять стол"); LSTR MSG_BED_TRAMMING = _UxGT("Выровнять углы"); LSTR MSG_NEXT_CORNER = _UxGT("Следующий угол"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Вверх до срабатыв. зонда"); LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Углы в норме. Вырав.стола"); #else @@ -170,7 +170,7 @@ namespace Language_ru { #endif LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Хорошие точки: "); LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Последняя Z: "); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_MESH_EDITOR = _UxGT("Смещение по Z"); LSTR MSG_EDITING_STOPPED = _UxGT("Правка сетки окончена"); #else @@ -205,7 +205,7 @@ namespace Language_ru { LSTR MSG_UBL_LEVEL_BED = _UxGT("Настройка UBL"); LSTR MSG_LCD_TILTING_MESH = _UxGT("Точка разворота"); LSTR MSG_UBL_MANUAL_MESH = _UxGT("Ручной ввод сетки"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_UBL_BC_INSERT = _UxGT("Разместить шайбу,измерить"); LSTR MSG_UBL_BC_REMOVE = _UxGT("Убрать и замерить стол"); #else @@ -219,7 +219,7 @@ namespace Language_ru { LSTR MSG_UBL_DEACTIVATE_MESH = _UxGT("Деактивировать UBL"); LSTR MSG_UBL_MESH_EDIT = _UxGT("Редактор сеток"); LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Править свою сетку"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Температура стола"); LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Температура стола"); LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Температура сопла"); @@ -237,7 +237,7 @@ namespace Language_ru { LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Точная правка сетки"); LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Построить сетку"); LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Построить сетку $"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Построить холодную сетку"); #else LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Строить холод.сетку"); @@ -245,7 +245,7 @@ namespace Language_ru { LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Правка высоты сетки"); LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Высота"); LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Проверить сетку"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Проверить сетку $"); LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Проверить свою сетку"); #else @@ -261,7 +261,7 @@ namespace Language_ru { LSTR MSG_G26_LEAVING = _UxGT("Выйти из G26"); LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Продолжить сетку"); LSTR MSG_UBL_MESH_LEVELING = _UxGT("Выравнивание сетки"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-х точечное выравнивание"); #else LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-точечное выравн."); @@ -273,7 +273,7 @@ namespace Language_ru { LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Вывести карту сетки"); LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Вывести на хост"); LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Вывести в CSV"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Сохранить сетку снаружи"); LSTR MSG_UBL_INFO_UBL = _UxGT("Вывод информации UBL"); LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполнителя"); @@ -323,7 +323,7 @@ namespace Language_ru { LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Свет по умолчанию"); LSTR MSG_LED_CHANNEL_N = _UxGT("Канал ="); LSTR MSG_LEDS2 = _UxGT("Свет #2"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_NEO2_PRESETS = _UxGT("Свет #2 предустановки"); #else LSTR MSG_NEO2_PRESETS = _UxGT("Свет #2 предустан."); @@ -360,7 +360,7 @@ namespace Language_ru { LSTR MSG_NOZZLE_STANDBY = _UxGT("Сопло ожидает"); LSTR MSG_BED = _UxGT("Стол, ") LCD_STR_DEGREE "C"; LSTR MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_COOLER = _UxGT("Охлаждение лазера"); LSTR MSG_COOLER_TOGGLE = _UxGT("Переключ. охлажд."); LSTR MSG_FLOWMETER_SAFETY = _UxGT("Безопасн. потока"); @@ -408,7 +408,7 @@ namespace Language_ru { LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-рывок"); LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-рывок"); LSTR MSG_VE_JERK = _UxGT("Ve-рывок"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_JUNCTION_DEVIATION = _UxGT("Отклонение узла"); #else LSTR MSG_JUNCTION_DEVIATION = _UxGT("Отклон. узла"); @@ -452,7 +452,7 @@ namespace Language_ru { LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E в мм") SUPERSCRIPT_THREE; LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E огран.,мм") SUPERSCRIPT_THREE; LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E огран. *"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_FILAMENT_DIAM = _UxGT("Диам. филамента"); LSTR MSG_FILAMENT_DIAM_E = _UxGT("Диам. филамента *"); #else @@ -466,7 +466,7 @@ namespace Language_ru { LSTR MSG_CONTRAST = _UxGT("Контраст экрана"); LSTR MSG_STORE_EEPROM = _UxGT("Сохранить настройки"); LSTR MSG_LOAD_EEPROM = _UxGT("Загрузить настройки"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_RESTORE_DEFAULTS = _UxGT("На базовые параметры"); LSTR MSG_INIT_EEPROM = _UxGT("Инициализация EEPROM"); #else @@ -520,7 +520,7 @@ namespace Language_ru { LSTR MSG_NO_MOVE = _UxGT("Нет движения."); LSTR MSG_KILLED = _UxGT("УБИТО. "); LSTR MSG_STOPPED = _UxGT("ОСТАНОВЛЕНО. "); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_CONTROL_RETRACT = _UxGT("Втягивание, мм"); LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Смена втягив., мм"); LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Возврат смены, мм"); @@ -539,7 +539,7 @@ namespace Language_ru { LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Возврат V"); LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Поменять длины"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Поменять дополнительно"); #else LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Поменять дополнит."); @@ -548,7 +548,7 @@ namespace Language_ru { LSTR MSG_TOOL_CHANGE = _UxGT("Смена сопел"); LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Поднятие по Z"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Начальная скор."); LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Скорость втягив."); #else @@ -568,7 +568,7 @@ namespace Language_ru { LSTR MSG_FILAMENTCHANGE = _UxGT("Смена филамента"); LSTR MSG_FILAMENTCHANGE_E = _UxGT("Смена филамента *"); LSTR MSG_FILAMENTLOAD = _UxGT("Загрузить филамент"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_FILAMENTLOAD_E = _UxGT("Загрузить филамент *"); LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Выгрузить филамент *"); #else @@ -606,7 +606,7 @@ namespace Language_ru { LSTR MSG_ZPROBE_XOFFSET = _UxGT("Смещение X"); LSTR MSG_ZPROBE_YOFFSET = _UxGT("Смещение Y"); LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Смещение Z"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двигать сопло к столу"); #else LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двиг. сопло к столу"); @@ -650,7 +650,7 @@ namespace Language_ru { LSTR MSG_DELTA_SETTINGS = _UxGT("Настройки Delta"); LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Авто калибровка"); LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Высота Delta"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондировать Z-смещения"); #else LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондир. Z-смещения"); @@ -660,7 +660,7 @@ namespace Language_ru { LSTR MSG_DELTA_RADIUS = _UxGT("Радиус"); LSTR MSG_INFO_MENU = _UxGT("О принтере"); LSTR MSG_INFO_PRINTER_MENU = _UxGT("Данные принтера"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_3POINT_LEVELING = _UxGT("3-точечное выравнивание"); LSTR MSG_LINEAR_LEVELING = _UxGT("Линейное выравнивание"); LSTR MSG_BILINEAR_LEVELING = _UxGT("Билинейное выравнивание"); @@ -671,7 +671,7 @@ namespace Language_ru { #endif LSTR MSG_UBL_LEVELING = _UxGT("Управление UBL"); LSTR MSG_MESH_LEVELING = _UxGT("Выравнивание сетки"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_MESH_DONE = _UxGT("Зондирование выполнено"); #else LSTR MSG_MESH_DONE = _UxGT("Зондиров. выполнено"); @@ -683,7 +683,7 @@ namespace Language_ru { LSTR MSG_INFO_EXTRUDERS = _UxGT("Экструдеры"); LSTR MSG_INFO_BAUDRATE = _UxGT("Скорость,БОД"); LSTR MSG_INFO_PROTOCOL = _UxGT("Протокол"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Контроль утечки Т: Выкл"); LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Контроль утечки Т: Вкл"); LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Время простоя хотенда"); @@ -696,7 +696,7 @@ namespace Language_ru { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Яркость подсветки"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Неверный принтер"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Счётчик печати"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Общее время печати"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Наидольшее задание"); @@ -730,7 +730,7 @@ namespace Language_ru { LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Выдавить ещё"); LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Возобновить печать"); LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Сопла: "); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_RUNOUT_SENSOR = _UxGT("Датчик оконч. филамента"); #else LSTR MSG_RUNOUT_SENSOR = _UxGT("Датчик оконч.филам."); @@ -741,7 +741,7 @@ namespace Language_ru { LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ВЫБИРЕТЕ ФИЛАМЕНТ"); LSTR MSG_MMU2_MENU = _UxGT("Настройки MMU"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Обновить прошивку MMU!"); #else LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Обнови прошивку MMU"); @@ -756,7 +756,7 @@ namespace Language_ru { LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Извлечь филамент ~"); LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Выгрузить филамент"); LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Загрузка %i..."); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Извлечение филамента..."); #else LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Извлеч.филамента..."); @@ -768,7 +768,7 @@ namespace Language_ru { LSTR MSG_MMU2_RESETTING = _UxGT("Перезапуск MMU..."); LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Удалите и нажмите"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_MIX = _UxGT("Смешивание"); #else LSTR MSG_MIX = _UxGT("Смешив."); @@ -780,7 +780,7 @@ namespace Language_ru { LSTR MSG_CYCLE_MIX = _UxGT("Цикличное смешивание"); LSTR MSG_GRADIENT_MIX = _UxGT("Градиент смешивания"); LSTR MSG_REVERSE_GRADIENT = _UxGT("Сменить градиент"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_TOGGLE_MIX = _UxGT("Переключить смешивание"); LSTR MSG_ACTIVE_VTOOL = _UxGT("Активация В-инструм."); LSTR MSG_START_VTOOL = _UxGT("Начало В-инструмента"); @@ -808,7 +808,7 @@ namespace Language_ru { LSTR MSG_SNAKE = _UxGT("Змейка"); LSTR MSG_MAZE = _UxGT("Лабиринт"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_BAD_PAGE = _UxGT("Плохой индекс страницы"); LSTR MSG_BAD_PAGE_SPEED = _UxGT("Плохая скорость страницы"); #else @@ -824,7 +824,7 @@ namespace Language_ru { LSTR MSG_REMOVE_PASSWORD = _UxGT("Удалить пароль"); LSTR MSG_PASSWORD_SET = _UxGT("Пароль это "); LSTR MSG_START_OVER = _UxGT("Старт через"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Запомни для сохранения!"); #else LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Запомни, сохрани!"); @@ -875,7 +875,7 @@ namespace Language_ru { LSTR MSG_LEVEL_X_AXIS = _UxGT("Уровень оси X"); LSTR MSG_AUTO_CALIBRATE = _UxGT("Авто калибровка"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_HEATER_TIMEOUT = _UxGT("Время нагревателя вышло"); #else LSTR MSG_HEATER_TIMEOUT = _UxGT("Время нагрев. вышло"); @@ -884,7 +884,7 @@ namespace Language_ru { LSTR MSG_REHEATING = _UxGT("Нагрев..."); LSTR MSG_PROBE_WIZARD = _UxGT("Мастер Z-зонда"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Зондиров. контр. точки Z"); LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Движение к точке зондиров."); #else diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 9ab08f2766388..275fea3081708 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -575,7 +575,7 @@ namespace Language_sk { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jas svetla"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Nesprávna tlačiareň"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Počet tlačí"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Dokončené"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Celkový čas"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index 69161d6b553b4..d4c03d0d61d3c 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -523,7 +523,7 @@ namespace Language_sv { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Ljus ljusstyrka"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("INKORREKT SKRIVARE"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Utskriftsantal"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Färdiga"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Total Utskriftstid"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 4c2bbfa0dc009..447ea9d5bf2c5 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -456,7 +456,7 @@ namespace Language_tr { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Aydınlatma Parlaklğı"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Yanlış Yazıcı"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Baskı Sayısı"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Tamamlanan"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Toplam Baskı Süresi"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 23110b5e4db94..798351c67e22b 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -44,7 +44,7 @@ namespace Language_uk { LSTR MSG_MEDIA_INSERTED = _UxGT("SD-картка вставлена"); LSTR MSG_MEDIA_REMOVED = _UxGT("SD-картка видалена"); LSTR MSG_MEDIA_WAITING = _UxGT("Вставте SD-картку"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Збій ініціалізації SD"); #else LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Збій ініціаліз. SD"); @@ -52,7 +52,7 @@ namespace Language_uk { LSTR MSG_MEDIA_READ_ERROR = _UxGT("Помилка зчитування"); LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB диск видалений"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("Помилка USB диску"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переповнення виклику"); LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Програмні кінцевики"); #else @@ -83,7 +83,7 @@ namespace Language_uk { LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Наступна точка"); LSTR MSG_LEVEL_BED_DONE = _UxGT("Завершено!"); LSTR MSG_Z_FADE_HEIGHT = _UxGT("Висота спаду"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_SET_HOME_OFFSETS = _UxGT("Встанов. зміщення дому"); LSTR MSG_HOME_OFFSET_X = _UxGT("Зміщення дому X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Зміщення дому Y"); @@ -103,7 +103,7 @@ namespace Language_uk { LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Зміщення прийняті"); LSTR MSG_SET_ORIGIN = _UxGT("Встановити нуль"); LSTR MSG_SELECT_ORIGIN = _UxGT("Оберіть нуль"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_LAST_VALUE_SP = _UxGT("Останнє значення "); #else LSTR MSG_LAST_VALUE_SP = _UxGT("Останнє знач. "); @@ -131,7 +131,7 @@ namespace Language_uk { LSTR MSG_CUTTER_FREQUENCY = _UxGT("Частота"); LSTR MSG_LASER_MENU = _UxGT("Керування лазером"); LSTR MSG_SPINDLE_MENU = _UxGT("Керування шпінделем"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_LASER_POWER = _UxGT("Потужність лазера"); LSTR MSG_SPINDLE_TOGGLE = _UxGT("Перемкн. шпіндель"); LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Перемкнути вакуум"); @@ -162,7 +162,7 @@ namespace Language_uk { LSTR MSG_BED_LEVELING = _UxGT("Вирівнювання столу"); LSTR MSG_LEVEL_BED = _UxGT("Вирівняти стіл"); LSTR MSG_BED_TRAMMING = _UxGT("Вирівняти кути"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Вгору до спрацюв. зонду"); LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Кути в межах. Вирів.столу"); #else @@ -172,7 +172,7 @@ namespace Language_uk { LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Хороші точки: "); LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Остання Z: "); LSTR MSG_NEXT_CORNER = _UxGT("Наступний кут"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_MESH_EDITOR = _UxGT("Зміщення по Z"); #else LSTR MSG_MESH_EDITOR = _UxGT("Зміщення Z"); @@ -205,7 +205,7 @@ namespace Language_uk { LSTR MSG_UBL_TOOLS = _UxGT("Інструменти UBL"); LSTR MSG_UBL_LEVEL_BED = _UxGT("Налаштування UBL"); LSTR MSG_LCD_TILTING_MESH = _UxGT("Точка нахилу"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_UBL_MANUAL_MESH = _UxGT("Ручне введення сітки"); LSTR MSG_UBL_BC_INSERT = _UxGT("Розмістити шайбу і вимір."); #else @@ -214,7 +214,7 @@ namespace Language_uk { #endif LSTR MSG_UBL_MESH_WIZARD = _UxGT("Майстер сіток UBL"); LSTR MSG_UBL_BC_INSERT2 = _UxGT("Вимірювання"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_UBL_BC_REMOVE = _UxGT("Видалити і виміряти стіл"); #else LSTR MSG_UBL_BC_REMOVE = _UxGT("Видали і вимір. стіл"); @@ -226,7 +226,7 @@ namespace Language_uk { LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" столу,") LCD_STR_DEGREE "C"; LSTR MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" сопла,") LCD_STR_DEGREE "C"; - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Редагувати свою сітку"); LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Точне редагування сітки"); LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Будувати свою сітку"); @@ -256,7 +256,7 @@ namespace Language_uk { LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Продовжити сітку"); LSTR MSG_UBL_MESH_LEVELING = _UxGT("Вирівнювання сітки"); LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-точкове вирівн."); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Вирівнювання растру"); #else LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Вирівнюв. растру"); @@ -269,7 +269,7 @@ namespace Language_uk { LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Вивести в CSV"); LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Зберегти зовні"); LSTR MSG_UBL_INFO_UBL = _UxGT("Інформація по UBL"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповнюв."); #else LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповн."); @@ -279,7 +279,7 @@ namespace Language_uk { LSTR MSG_UBL_FILLIN_MESH = _UxGT("Заповнити сітку"); LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Анулювати все"); LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Анулювати найближчу"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налаштувати все"); LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Точно налашт.найближчу"); #else @@ -308,7 +308,7 @@ namespace Language_uk { LSTR MSG_LED_CONTROL = _UxGT("Керування світлом"); LSTR MSG_LEDS = _UxGT("Підсвітка"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_LED_PRESETS = _UxGT("Передустановки світла"); #else LSTR MSG_LED_PRESETS = _UxGT("Передустан. світла"); @@ -324,7 +324,7 @@ namespace Language_uk { LSTR MSG_SET_LEDS_DEFAULT = _UxGT("За умовчанням"); LSTR MSG_LED_CHANNEL_N = _UxGT("Канал ="); LSTR MSG_LEDS2 = _UxGT("Світло #2"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_NEO2_PRESETS = _UxGT("Передустановка світла #2"); #else LSTR MSG_NEO2_PRESETS = _UxGT("Передуст. світла #2"); @@ -361,7 +361,7 @@ namespace Language_uk { LSTR MSG_NOZZLE_STANDBY = _UxGT("Сопло очікує"); LSTR MSG_BED = _UxGT("Стіл, ") LCD_STR_DEGREE "C"; LSTR MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_COOLER = _UxGT("Охолодження лазеру"); LSTR MSG_COOLER_TOGGLE = _UxGT("Перемк. охолодж."); #else @@ -372,7 +372,7 @@ namespace Language_uk { LSTR MSG_LASER = _UxGT("Лазер"); LSTR MSG_FAN_SPEED = _UxGT("Швидк. вент."); LSTR MSG_FAN_SPEED_N = _UxGT("Швидк. вент. ~"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_STORED_FAN_N = _UxGT("Збереж.швидк.вент. ~"); LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Дод. швидк. вент. ~"); #else @@ -413,7 +413,7 @@ namespace Language_uk { LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-ривок"); LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-ривок"); LSTR MSG_VE_JERK = _UxGT("Ve-ривок"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_JUNCTION_DEVIATION = _UxGT("Відхилення вузла"); #else LSTR MSG_JUNCTION_DEVIATION = _UxGT("Відхил.вузла"); @@ -428,7 +428,7 @@ namespace Language_uk { LSTR MSG_VMAX_E = _UxGT("Швидк.макс ") LCD_STR_E; LSTR MSG_VMAX_EN = _UxGT("Швидк.макс *"); LSTR MSG_VMIN = _UxGT("Швидк. мін"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_VTRAV_MIN = _UxGT("Переміщення мін"); #else LSTR MSG_VTRAV_MIN = _UxGT("Переміщ. мін"); @@ -471,7 +471,7 @@ namespace Language_uk { LSTR MSG_STORE_EEPROM = _UxGT("Зберегти в EEPROM"); LSTR MSG_LOAD_EEPROM = _UxGT("Зчитати з EEPROM"); LSTR MSG_RESTORE_DEFAULTS = _UxGT("На базові параметри"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_INIT_EEPROM = _UxGT("Ініціалізація EEPROM"); #else LSTR MSG_INIT_EEPROM = _UxGT("Ініціаліз. EEPROM"); @@ -525,7 +525,7 @@ namespace Language_uk { LSTR MSG_NO_MOVE = _UxGT("Немає руху."); LSTR MSG_KILLED = _UxGT("ПЕРЕРВАНО. "); LSTR MSG_STOPPED = _UxGT("ЗУПИНЕНО. "); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_CONTROL_RETRACT = _UxGT("Втягування, мм"); LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Зміна втягув.,мм"); LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Повернення, мм"); @@ -547,7 +547,7 @@ namespace Language_uk { LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Очистити довжину"); LSTR MSG_TOOL_CHANGE = _UxGT("Зміна сопла"); LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Підняти по Z"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Початк.швидкість"); LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Швидкість втягув."); #else @@ -556,7 +556,7 @@ namespace Language_uk { #endif LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Паркувати голову"); LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Відновити швидкість"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Оберти вентилятора"); LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Час вентилятора"); #else @@ -621,7 +621,7 @@ namespace Language_uk { LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("ВИТІК ТЕПЛА СТОЛУ"); LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ВИТІК ТЕПЛА КАМЕРИ"); LSTR MSG_THERMAL_RUNAWAY_COOLER = _UxGT("ВИТІК ОХОЛОДЖЕННЯ"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_COOLING_FAILED = _UxGT("ОХОЛОДЖЕННЯ НЕ ВДАЛОСЬ"); #else LSTR MSG_COOLING_FAILED = _UxGT("ОХОЛОДЖ. НЕ ВДАЛОСЬ"); @@ -638,7 +638,7 @@ namespace Language_uk { LSTR MSG_BED_HEATING = _UxGT("Нагрів столу..."); LSTR MSG_PROBE_HEATING = _UxGT("Нагрів зонду..."); LSTR MSG_CHAMBER_HEATING = _UxGT("Нагрів камери..."); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_BED_COOLING = _UxGT("Охолодження столу..."); LSTR MSG_PROBE_COOLING = _UxGT("Охолодження зонду..."); LSTR MSG_CHAMBER_COOLING = _UxGT("Охолодження камери..."); @@ -665,7 +665,7 @@ namespace Language_uk { LSTR MSG_INFO_MENU = _UxGT("Про принтер"); LSTR MSG_INFO_PRINTER_MENU = _UxGT("Дані принтера"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_3POINT_LEVELING = _UxGT("3-точкове вирівнювання"); LSTR MSG_LINEAR_LEVELING = _UxGT("Лінійне вирівнювання"); LSTR MSG_BILINEAR_LEVELING = _UxGT("Білінійне вирівнювання"); @@ -676,7 +676,7 @@ namespace Language_uk { #endif LSTR MSG_UBL_LEVELING = _UxGT("UBL"); LSTR MSG_MESH_LEVELING = _UxGT("Вирівнювання сітки"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_MESH_DONE = _UxGT("Зондування сітки виконано"); #else LSTR MSG_MESH_DONE = _UxGT("Зондування виконано"); @@ -688,7 +688,7 @@ namespace Language_uk { LSTR MSG_INFO_EXTRUDERS = _UxGT("Екструдери"); LSTR MSG_INFO_BAUDRATE = _UxGT("Бод"); LSTR MSG_INFO_PROTOCOL = _UxGT("Протокол"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Контроль витіку ") LCD_STR_THERMOMETER _UxGT(" Вимк"); LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Контроль витіку ") LCD_STR_THERMOMETER _UxGT(" Увімк"); LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Час простою хотенду"); @@ -704,7 +704,7 @@ namespace Language_uk { LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Завершено"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Екструдовано"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Кількість друків"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Весь час друку"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Найдовший час"); @@ -731,7 +731,7 @@ namespace Language_uk { LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("ЗУПИНКА ДРУКУ"); LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("ЗАВАНТАЖИТИ ПРУТОК"); LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("ВИВАНТАЖИТИ ПРУТОК"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ПАРАМЕТРИ ПРОДОВЖЕННЯ:"); #else LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ПАРАМ.ПРОДОВЖЕННЯ:"); @@ -739,7 +739,7 @@ namespace Language_uk { LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Видавити ще"); LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Відновити друк"); LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Сопло: "); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_RUNOUT_SENSOR = _UxGT("Датчик закінчення прутка"); LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Відстань закінч.,мм"); #else @@ -757,7 +757,7 @@ namespace Language_uk { LSTR MSG_MMU2_RESUMING = _UxGT("MMU Продовження..."); LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Завантажити"); LSTR MSG_MMU2_LOAD_ALL = _UxGT("MMU Завантажити все"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завантажити в сопло"); #else LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завант. в сопло"); @@ -774,7 +774,7 @@ namespace Language_uk { LSTR MSG_MMU2_RESETTING = _UxGT("MMU Перезапуск..."); LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Видаліть, натисніть"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_MIX = _UxGT("Змішування"); #else LSTR MSG_MIX = _UxGT("Змішув."); @@ -783,7 +783,7 @@ namespace Language_uk { LSTR MSG_MIXER = _UxGT("Змішувач"); LSTR MSG_GRADIENT = _UxGT("Градієнт"); LSTR MSG_FULL_GRADIENT = _UxGT("Повний градієнт"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_TOGGLE_MIX = _UxGT("Переключити змішування"); #else LSTR MSG_TOGGLE_MIX = _UxGT("Переключ.змішування"); @@ -792,7 +792,7 @@ namespace Language_uk { LSTR MSG_GRADIENT_MIX = _UxGT("Градієнт змішування"); LSTR MSG_REVERSE_GRADIENT = _UxGT("Змінити градієнт"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_ACTIVE_VTOOL = _UxGT("Активація В-інструменту"); LSTR MSG_GRADIENT_ALIAS = _UxGT("Псевдонім В-інструменту"); LSTR MSG_RESET_VTOOLS = _UxGT("Зкидання В-інструментів"); @@ -815,7 +815,7 @@ namespace Language_uk { LSTR MSG_MAZE = _UxGT("Лабіринт"); LSTR MSG_BAD_PAGE = _UxGT("Погана сторінка"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_BAD_PAGE_SPEED = _UxGT("Погана швидкість стор."); #else LSTR MSG_BAD_PAGE_SPEED = _UxGT("Погана швидк. стор."); @@ -888,7 +888,7 @@ namespace Language_uk { LSTR MSG_REHEATING = _UxGT("Нагрівання..."); LSTR MSG_PROBE_WIZARD = _UxGT("Майстер Z-зонда"); - #if LCD_WIDTH > 21 + #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Зондув. контрольної точки Z"); LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Рух до точки зондування"); #else diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index ae0babbf8b34b..a419ddee560ad 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -383,7 +383,7 @@ namespace Language_vi { LSTR MSG_INFO_PROTOCOL = _UxGT("Giao Thức"); // Protocol LSTR MSG_CASE_LIGHT = _UxGT("Đèn Khuông"); // Case light LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Độ Sáng"); // Light Brightness - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("Số In"); // Print Count LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Đã hoàn thành"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Tổng số thời gian in"); // Total print time diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index d61634e431e1d..e641f235e6526 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -489,7 +489,7 @@ namespace Language_zh_CN { LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("打印机不正确"); // "The printer is incorrect" - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("打印计数"); // "Print Count" LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("完成了"); // "Completed" LSTR MSG_INFO_PRINT_TIME = _UxGT("总打印时间"); // "Total print time" diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 7680721b00e04..f168679e4a006 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -437,7 +437,7 @@ namespace Language_zh_TW { LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("燈亮度"); // "Light BRIGHTNESS" LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("打印機不正確"); // "The printer is incorrect" - #if LCD_WIDTH >= 20 + #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_INFO_PRINT_COUNT = _UxGT("列印計數"); // "Print Count" LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("已完成"); // "Completed" LSTR MSG_INFO_PRINT_TIME = _UxGT("總列印時間"); // "Total print time" From 2351b0df849db3a5efb964413574420e988545b3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Dec 2021 05:02:40 -0600 Subject: [PATCH 207/273] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Add?= =?UTF-8?q?=20AXIS=5FCOLLISION=20to=20catch=20broken=20parameters?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/types.h | 2 ++ Marlin/src/gcode/config/M200-M205.cpp | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 9a5b64c22e864..d589abfc1adb5 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -64,6 +64,8 @@ struct IF { typedef L type; }; #define GANG_ITEM_E(N) #endif +#define AXIS_COLLISION(L) (AXIS4_NAME == L || AXIS5_NAME == L || AXIS6_NAME == L) + // // Enumerated axis indices // diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index 7b7ce5e10d7f0..b26a2fe28bf98 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -253,7 +253,7 @@ void GcodeSuite::M205() { if (parser.seenval('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units(); if (parser.seenval('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units(); #if HAS_JUNCTION_DEVIATION - #if HAS_CLASSIC_JERK && (AXIS4_NAME == 'J' || AXIS5_NAME == 'J' || AXIS6_NAME == 'J') + #if HAS_CLASSIC_JERK && AXIS_COLLISION('J') #error "Can't set_max_jerk for 'J' axis because 'J' is used for Junction Deviation." #endif if (parser.seenval('J')) { From 02b4e48c6df1604d3de09cbef072f685fe956e92 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Dec 2021 05:43:10 -0600 Subject: [PATCH 208/273] =?UTF-8?q?=F0=9F=9A=B8=20Refine=20stepper-driver-?= =?UTF-8?q?related=20G-codes=20(#23372)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/tmc_util.h | 43 ++-------- Marlin/src/gcode/feature/L6470/M906.cpp | 86 +++++++++---------- Marlin/src/gcode/feature/trinamic/M569.cpp | 47 +++++----- Marlin/src/gcode/feature/trinamic/M906.cpp | 81 +++++++++-------- .../src/gcode/feature/trinamic/M911-M914.cpp | 83 ++++++++++++------ Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/module/stepper/trinamic.h | 6 -- 8 files changed, 170 insertions(+), 180 deletions(-) diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 1f7d5cf1a5432..2da425170f8f4 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -45,6 +45,12 @@ constexpr uint16_t _tmc_thrs(const uint16_t msteps, const uint32_t thrs, const u return 12650000UL * msteps / (256 * thrs * spmm); } +typedef struct { + uint8_t toff; + int8_t hend; + uint8_t hstrt; +} chopper_timing_t; + template class TMCStorage { protected: @@ -297,43 +303,6 @@ class TMCMarlin : public TMC266 sgt_max = 63; }; -template -void tmc_print_current(TMC &st) { - st.printLabel(); - SERIAL_ECHOLNPGM(" driver current: ", st.getMilliamps()); -} - -#if ENABLED(MONITOR_DRIVER_STATUS) - template - void tmc_report_otpw(TMC &st) { - st.printLabel(); - SERIAL_ECHOPGM(" temperature prewarn triggered: "); - serialprint_truefalse(st.getOTPW()); - SERIAL_EOL(); - } - template - void tmc_clear_otpw(TMC &st) { - st.clear_otpw(); - st.printLabel(); - SERIAL_ECHOLNPGM(" prewarn flag cleared"); - } -#endif -#if ENABLED(HYBRID_THRESHOLD) - template - void tmc_print_pwmthrs(TMC &st) { - st.printLabel(); - SERIAL_ECHOLNPGM(" stealthChop max speed: ", st.get_pwm_thrs()); - } -#endif -#if USE_SENSORLESS - template - void tmc_print_sgt(TMC &st) { - st.printLabel(); - SERIAL_ECHOPGM(" homing sensitivity: "); - SERIAL_PRINTLN(st.homing_threshold(), PrintBase::Dec); - } -#endif - void monitor_tmc_drivers(); void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index d058ce5501ae5..9283cdb945ab2 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -202,12 +202,11 @@ void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) { * On L6474 this sets the TVAL register (same address). * * I - select which driver(s) to change on multi-driver axis - * 0 - (default) all drivers on the axis or E0 - * 1 - monitor only X, Y, Z or E1 - * 2 - monitor only X2, Y2, Z2 or E2 - * 3 - monitor only Z3 or E3 - * 4 - monitor only Z4 or E4 - * 5 - monitor only E5 + * (default) all drivers on the axis + * 0 - monitor only the first XYZ... driver + * 1 - monitor only X2, Y2, Z2 + * 2 - monitor only Z3 + * 3 - monitor only Z4 * Xxxx, Yxxx, Zxxx, Exxx - axis to change (optional) * L6474 - current in mA (4A max) * All others - 0-255 @@ -227,8 +226,10 @@ void GcodeSuite::M906() { uint8_t report_current = true; - #if HAS_L64XX - const uint8_t index = parser.byteval('I'); + #if AXIS_IS_L64XX(X2) || AXIS_IS_L64XX(Y2) || AXIS_IS_L64XX(Z2) || AXIS_IS_L64XX(Z3) || AXIS_IS_L64XX(Z4) + const int8_t index = parser.byteval('I', -1); + #else + constexpr int8_t index = -1; #endif LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(axis_codes[i])) { @@ -243,20 +244,20 @@ void GcodeSuite::M906() { switch (i) { case X_AXIS: #if AXIS_IS_L64XX(X) - if (index == 0) L6470_SET_KVAL_HOLD(X); + if (index < 0 || index == 0) L6470_SET_KVAL_HOLD(X); #endif #if AXIS_IS_L64XX(X2) - if (index == 1) L6470_SET_KVAL_HOLD(X2); + if (index < 0 || index == 1) L6470_SET_KVAL_HOLD(X2); #endif break; #if HAS_Y_AXIS case Y_AXIS: #if AXIS_IS_L64XX(Y) - if (index == 0) L6470_SET_KVAL_HOLD(Y); + if (index < 0 || index == 0) L6470_SET_KVAL_HOLD(Y); #endif #if AXIS_IS_L64XX(Y2) - if (index == 1) L6470_SET_KVAL_HOLD(Y2); + if (index < 0 || index == 1) L6470_SET_KVAL_HOLD(Y2); #endif break; #endif @@ -264,50 +265,47 @@ void GcodeSuite::M906() { #if HAS_Z_AXIS case Z_AXIS: #if AXIS_IS_L64XX(Z) - if (index == 0) L6470_SET_KVAL_HOLD(Z); + if (index < 0 || index == 0) L6470_SET_KVAL_HOLD(Z); #endif #if AXIS_IS_L64XX(Z2) - if (index == 1) L6470_SET_KVAL_HOLD(Z2); + if (index < 0 || index == 1) L6470_SET_KVAL_HOLD(Z2); #endif #if AXIS_IS_L64XX(Z3) - if (index == 2) L6470_SET_KVAL_HOLD(Z3); + if (index < 0 || index == 2) L6470_SET_KVAL_HOLD(Z3); #endif #if AXIS_DRIVER_TYPE_Z4(L6470) - if (index == 3) L6470_SET_KVAL_HOLD(Z4); + if (index < 0 || index == 3) L6470_SET_KVAL_HOLD(Z4); #endif break; #endif #if E_STEPPERS case E_AXIS: { - const int8_t target_e_stepper = get_target_e_stepper_from_command(0); - if (target_e_stepper < 0) return; - switch (target_e_stepper) { - #if AXIS_IS_L64XX(E0) - case 0: L6470_SET_KVAL_HOLD(E0); break; - #endif - #if AXIS_IS_L64XX(E1) - case 1: L6470_SET_KVAL_HOLD(E1); break; - #endif - #if AXIS_IS_L64XX(E2) - case 2: L6470_SET_KVAL_HOLD(E2); break; - #endif - #if AXIS_IS_L64XX(E3) - case 3: L6470_SET_KVAL_HOLD(E3); break; - #endif - #if AXIS_IS_L64XX(E4) - case 4: L6470_SET_KVAL_HOLD(E4); break; - #endif - #if AXIS_IS_L64XX(E5) - case 5: L6470_SET_KVAL_HOLD(E5); break; - #endif - #if AXIS_IS_L64XX(E6) - case 6: L6470_SET_KVAL_HOLD(E6); break; - #endif - #if AXIS_IS_L64XX(E7) - case 7: L6470_SET_KVAL_HOLD(E7); break; - #endif - } + const int8_t eindex = get_target_e_stepper_from_command(); + #if AXIS_IS_L64XX(E0) + if (eindex < 0 || eindex == 0) L6470_SET_KVAL_HOLD(E0); + #endif + #if AXIS_IS_L64XX(E1) + if (eindex < 0 || eindex == 1) L6470_SET_KVAL_HOLD(E1); + #endif + #if AXIS_IS_L64XX(E2) + if (eindex < 0 || eindex == 2) L6470_SET_KVAL_HOLD(E2); + #endif + #if AXIS_IS_L64XX(E3) + if (eindex < 0 || eindex == 3) L6470_SET_KVAL_HOLD(E3); + #endif + #if AXIS_IS_L64XX(E4) + if (eindex < 0 || eindex == 4) L6470_SET_KVAL_HOLD(E4); + #endif + #if AXIS_IS_L64XX(E5) + if (eindex < 0 || eindex == 5) L6470_SET_KVAL_HOLD(E5); + #endif + #if AXIS_IS_L64XX(E6) + if (eindex < 0 || eindex == 6) L6470_SET_KVAL_HOLD(E6); + #endif + #if AXIS_IS_L64XX(E7) + if (eindex < 0 || eindex == 7) L6470_SET_KVAL_HOLD(E7); + #endif } break; #endif } diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index cb33d46d25280..ad1d20e8cb178 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -40,35 +40,35 @@ void tmc_set_stealthChop(TMC &st, const bool enable) { st.refresh_stepping_mode(); } -static void set_stealth_status(const bool enable, const int8_t target_e_stepper) { +static void set_stealth_status(const bool enable, const int8_t eindex) { #define TMC_SET_STEALTH(Q) tmc_set_stealthChop(stepper##Q, enable) - #if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP \ - || I_HAS_STEALTHCHOP || J_HAS_STEALTHCHOP || K_HAS_STEALTHCHOP \ - || X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP || Z3_HAS_STEALTHCHOP || Z4_HAS_STEALTHCHOP - const uint8_t index = parser.byteval('I'); + #if X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP || Z3_HAS_STEALTHCHOP || Z4_HAS_STEALTHCHOP + const int8_t index = parser.byteval('I', -1); + #else + constexpr int8_t index = -1; #endif LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) { switch (i) { case X_AXIS: - TERN_(X_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(X)); - TERN_(X2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(X2)); + TERN_(X_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_STEALTH(X)); + TERN_(X2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_STEALTH(X2)); break; #if HAS_Y_AXIS case Y_AXIS: - TERN_(Y_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(Y)); - TERN_(Y2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Y2)); + TERN_(Y_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_STEALTH(Y)); + TERN_(Y2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_STEALTH(Y2)); break; #endif #if HAS_Z_AXIS case Z_AXIS: - TERN_(Z_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(Z)); - TERN_(Z2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Z2)); - TERN_(Z3_HAS_STEALTHCHOP, if (index == 2) TMC_SET_STEALTH(Z3)); - TERN_(Z4_HAS_STEALTHCHOP, if (index == 3) TMC_SET_STEALTH(Z4)); + TERN_(Z_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_STEALTH(Z)); + TERN_(Z2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_STEALTH(Z2)); + TERN_(Z3_HAS_STEALTHCHOP, if (index < 0 || index == 2) TMC_SET_STEALTH(Z3)); + TERN_(Z4_HAS_STEALTHCHOP, if (index < 0 || index == 3) TMC_SET_STEALTH(Z4)); break; #endif @@ -84,17 +84,14 @@ static void set_stealth_status(const bool enable, const int8_t target_e_stepper) #if E_STEPPERS case E_AXIS: { - if (target_e_stepper < 0) return; - switch (target_e_stepper) { - TERN_(E0_HAS_STEALTHCHOP, case 0: TMC_SET_STEALTH(E0); break;) - TERN_(E1_HAS_STEALTHCHOP, case 1: TMC_SET_STEALTH(E1); break;) - TERN_(E2_HAS_STEALTHCHOP, case 2: TMC_SET_STEALTH(E2); break;) - TERN_(E3_HAS_STEALTHCHOP, case 3: TMC_SET_STEALTH(E3); break;) - TERN_(E4_HAS_STEALTHCHOP, case 4: TMC_SET_STEALTH(E4); break;) - TERN_(E5_HAS_STEALTHCHOP, case 5: TMC_SET_STEALTH(E5); break;) - TERN_(E6_HAS_STEALTHCHOP, case 6: TMC_SET_STEALTH(E6); break;) - TERN_(E7_HAS_STEALTHCHOP, case 7: TMC_SET_STEALTH(E7); break;) - } + TERN_(E0_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 0) TMC_SET_STEALTH(E0)); + TERN_(E1_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 1) TMC_SET_STEALTH(E1)); + TERN_(E2_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 2) TMC_SET_STEALTH(E2)); + TERN_(E3_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 3) TMC_SET_STEALTH(E3)); + TERN_(E4_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 4) TMC_SET_STEALTH(E4)); + TERN_(E5_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 5) TMC_SET_STEALTH(E5)); + TERN_(E6_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 6) TMC_SET_STEALTH(E6)); + TERN_(E7_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 7) TMC_SET_STEALTH(E7)); } break; #endif } @@ -133,7 +130,7 @@ static void say_stealth_status() { */ void GcodeSuite::M569() { if (parser.seen('S')) - set_stealth_status(parser.value_bool(), get_target_e_stepper_from_command(0)); + set_stealth_status(parser.value_bool(), get_target_e_stepper_from_command()); else say_stealth_status(); } diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index f28718c831baa..300b8beb097a6 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -28,6 +28,12 @@ #include "../../../feature/tmc_util.h" #include "../../../module/stepper/indirection.h" +template +static void tmc_print_current(TMC &st) { + st.printLabel(); + SERIAL_ECHOLNPGM(" driver current: ", st.getMilliamps()); +} + /** * M906: Set motor current in milliamps. * @@ -48,8 +54,10 @@ void GcodeSuite::M906() { bool report = true; - #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K) - const uint8_t index = parser.byteval('I'); + #if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) + const int8_t index = parser.byteval('I', -1); + #else + constexpr int8_t index = -1; #endif LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(axis_codes[i])) { @@ -57,20 +65,20 @@ void GcodeSuite::M906() { switch (i) { case X_AXIS: #if AXIS_IS_TMC(X) - if (index == 0) TMC_SET_CURRENT(X); + if (index < 0 || index == 0) TMC_SET_CURRENT(X); #endif #if AXIS_IS_TMC(X2) - if (index == 1) TMC_SET_CURRENT(X2); + if (index < 0 || index == 1) TMC_SET_CURRENT(X2); #endif break; #if HAS_Y_AXIS case Y_AXIS: #if AXIS_IS_TMC(Y) - if (index == 0) TMC_SET_CURRENT(Y); + if (index < 0 || index == 0) TMC_SET_CURRENT(Y); #endif #if AXIS_IS_TMC(Y2) - if (index == 1) TMC_SET_CURRENT(Y2); + if (index < 0 || index == 1) TMC_SET_CURRENT(Y2); #endif break; #endif @@ -78,16 +86,16 @@ void GcodeSuite::M906() { #if HAS_Z_AXIS case Z_AXIS: #if AXIS_IS_TMC(Z) - if (index == 0) TMC_SET_CURRENT(Z); + if (index < 0 || index == 0) TMC_SET_CURRENT(Z); #endif #if AXIS_IS_TMC(Z2) - if (index == 1) TMC_SET_CURRENT(Z2); + if (index < 0 || index == 1) TMC_SET_CURRENT(Z2); #endif #if AXIS_IS_TMC(Z3) - if (index == 2) TMC_SET_CURRENT(Z3); + if (index < 0 || index == 2) TMC_SET_CURRENT(Z3); #endif #if AXIS_IS_TMC(Z4) - if (index == 3) TMC_SET_CURRENT(Z4); + if (index < 0 || index == 3) TMC_SET_CURRENT(Z4); #endif break; #endif @@ -104,34 +112,31 @@ void GcodeSuite::M906() { #if E_STEPPERS case E_AXIS: { - const int8_t target_e_stepper = get_target_e_stepper_from_command(0); - if (target_e_stepper < 0) return; - switch (target_e_stepper) { - #if AXIS_IS_TMC(E0) - case 0: TMC_SET_CURRENT(E0); break; - #endif - #if AXIS_IS_TMC(E1) - case 1: TMC_SET_CURRENT(E1); break; - #endif - #if AXIS_IS_TMC(E2) - case 2: TMC_SET_CURRENT(E2); break; - #endif - #if AXIS_IS_TMC(E3) - case 3: TMC_SET_CURRENT(E3); break; - #endif - #if AXIS_IS_TMC(E4) - case 4: TMC_SET_CURRENT(E4); break; - #endif - #if AXIS_IS_TMC(E5) - case 5: TMC_SET_CURRENT(E5); break; - #endif - #if AXIS_IS_TMC(E6) - case 6: TMC_SET_CURRENT(E6); break; - #endif - #if AXIS_IS_TMC(E7) - case 7: TMC_SET_CURRENT(E7); break; - #endif - } + const int8_t eindex = get_target_e_stepper_from_command(); + #if AXIS_IS_TMC(E0) + if (eindex < 0 || eindex == 0) TMC_SET_CURRENT(E0); + #endif + #if AXIS_IS_TMC(E1) + if (eindex < 0 || eindex == 1) TMC_SET_CURRENT(E1); + #endif + #if AXIS_IS_TMC(E2) + if (eindex < 0 || eindex == 2) TMC_SET_CURRENT(E2); + #endif + #if AXIS_IS_TMC(E3) + if (eindex < 0 || eindex == 3) TMC_SET_CURRENT(E3); + #endif + #if AXIS_IS_TMC(E4) + if (eindex < 0 || eindex == 4) TMC_SET_CURRENT(E4); + #endif + #if AXIS_IS_TMC(E5) + if (eindex < 0 || eindex == 5) TMC_SET_CURRENT(E5); + #endif + #if AXIS_IS_TMC(E6) + if (eindex < 0 || eindex == 6) TMC_SET_CURRENT(E6); + #endif + #if AXIS_IS_TMC(E7) + if (eindex < 0 || eindex == 7) TMC_SET_CURRENT(E7); + #endif } break; #endif } diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 3f83558fd4286..32a2d25e77dcf 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -62,6 +62,21 @@ #error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160." #endif + template + static void tmc_report_otpw(TMC &st) { + st.printLabel(); + SERIAL_ECHOPGM(" temperature prewarn triggered: "); + serialprint_truefalse(st.getOTPW()); + SERIAL_EOL(); + } + + template + static void tmc_clear_otpw(TMC &st) { + st.clear_otpw(); + st.printLabel(); + SERIAL_ECHOLNPGM(" prewarn flag cleared"); + } + /** * M911: Report TMC stepper driver overtemperature pre-warn flag * This flag is held by the library, persisting until cleared by M912 @@ -223,11 +238,17 @@ #endif // MONITOR_DRIVER_STATUS -/** - * M913: Set HYBRID_THRESHOLD speed. - */ #if ENABLED(HYBRID_THRESHOLD) + template + static void tmc_print_pwmthrs(TMC &st) { + st.printLabel(); + SERIAL_ECHOLNPGM(" stealthChop max speed: ", st.get_pwm_thrs()); + } + + /** + * M913: Set HYBRID_THRESHOLD speed. + */ void GcodeSuite::M913() { #define TMC_SAY_PWMTHRS(A,Q) tmc_print_pwmthrs(stepper##Q) #define TMC_SET_PWMTHRS(A,Q) stepper##Q.set_pwm_thrs(value) @@ -235,19 +256,21 @@ #define TMC_SET_PWMTHRS_E(E) stepperE##E.set_pwm_thrs(value) bool report = true; - #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K) - const uint8_t index = parser.byteval('I'); + #if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) + const int8_t index = parser.byteval('I', -1); + #else + constexpr int8_t index = -1; #endif LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(axis_codes[i])) { report = false; switch (i) { case X_AXIS: - TERN_(X_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(X,X)); - TERN_(X2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(X,X2)); + TERN_(X_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_PWMTHRS(X,X)); + TERN_(X2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_PWMTHRS(X,X2)); break; case Y_AXIS: - TERN_(Y_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(Y,Y)); - TERN_(Y2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2)); + TERN_(Y_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_PWMTHRS(Y,Y)); + TERN_(Y2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_PWMTHRS(Y,Y2)); break; #if I_HAS_STEALTHCHOP @@ -261,25 +284,22 @@ #endif case Z_AXIS: - TERN_(Z_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(Z,Z)); - TERN_(Z2_HAS_STEALTHCHOP, if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2)); - TERN_(Z3_HAS_STEALTHCHOP, if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3)); - TERN_(Z4_HAS_STEALTHCHOP, if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4)); + TERN_(Z_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_PWMTHRS(Z,Z)); + TERN_(Z2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_PWMTHRS(Z,Z2)); + TERN_(Z3_HAS_STEALTHCHOP, if (index < 0 || index == 2) TMC_SET_PWMTHRS(Z,Z3)); + TERN_(Z4_HAS_STEALTHCHOP, if (index < 0 || index == 3) TMC_SET_PWMTHRS(Z,Z4)); break; #if E_STEPPERS case E_AXIS: { - const int8_t target_e_stepper = get_target_e_stepper_from_command(0); - if (target_e_stepper < 0) return; - switch (target_e_stepper) { - TERN_(E0_HAS_STEALTHCHOP, case 0: TMC_SET_PWMTHRS_E(0); break;) - TERN_(E1_HAS_STEALTHCHOP, case 1: TMC_SET_PWMTHRS_E(1); break;) - TERN_(E2_HAS_STEALTHCHOP, case 2: TMC_SET_PWMTHRS_E(2); break;) - TERN_(E3_HAS_STEALTHCHOP, case 3: TMC_SET_PWMTHRS_E(3); break;) - TERN_(E4_HAS_STEALTHCHOP, case 4: TMC_SET_PWMTHRS_E(4); break;) - TERN_(E5_HAS_STEALTHCHOP, case 5: TMC_SET_PWMTHRS_E(5); break;) - TERN_(E6_HAS_STEALTHCHOP, case 6: TMC_SET_PWMTHRS_E(6); break;) - TERN_(E7_HAS_STEALTHCHOP, case 7: TMC_SET_PWMTHRS_E(7); break;) - } + const int8_t eindex = get_target_e_stepper_from_command(); + TERN_(E0_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 0) TMC_SET_PWMTHRS_E(0)); + TERN_(E1_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 1) TMC_SET_PWMTHRS_E(1)); + TERN_(E2_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 2) TMC_SET_PWMTHRS_E(2)); + TERN_(E3_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 3) TMC_SET_PWMTHRS_E(3)); + TERN_(E4_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 4) TMC_SET_PWMTHRS_E(4)); + TERN_(E5_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 5) TMC_SET_PWMTHRS_E(5)); + TERN_(E6_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 6) TMC_SET_PWMTHRS_E(6)); + TERN_(E7_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 7) TMC_SET_PWMTHRS_E(7)); } break; #endif // E_STEPPERS } @@ -407,11 +427,18 @@ #endif // HYBRID_THRESHOLD -/** - * M914: Set StallGuard sensitivity. - */ #if USE_SENSORLESS + template + static void tmc_print_sgt(TMC &st) { + st.printLabel(); + SERIAL_ECHOPGM(" homing sensitivity: "); + SERIAL_PRINTLN(st.homing_threshold(), PrintBase::Dec); + } + + /** + * M914: Set StallGuard sensitivity. + */ void GcodeSuite::M914() { bool report = true; diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index c05ac5494d5a2..d3d8f335dfa99 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -159,7 +159,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command(const int8_t dval/*=-1*/) { } /** - * Set XYZIJKE destination and feedrate from the current GCode command + * Set XYZ...E destination and feedrate from the current GCode command * * - Set destination from included axis codes * - Set to current for missing axis codes diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index bbfb31a3fece4..262237d14c9a8 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -284,7 +284,7 @@ * M871 - Print/reset/clear first layer temperature offset values. (Requires PTC_PROBE, PTC_BED, or PTC_HOTEND) * M876 - Handle Prompt Response. (Requires HOST_PROMPT_SUPPORT and not EMERGENCY_PARSER) * M900 - Get or Set Linear Advance K-factor. (Requires LIN_ADVANCE) - * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660 or L6470) + * M906 - Set or get motor current in milliamps using axis codes XYZE, etc. Report values if no axis codes given. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660 or L6470) * M907 - Set digital trimpot motor current using axis codes. (Requires a board with digital trimpots) * M908 - Control digital trimpot directly. (Requires HAS_MOTOR_CURRENT_DAC or DIGIPOTSS_PIN) * M909 - Print digipot/DAC current value. (Requires HAS_MOTOR_CURRENT_DAC) diff --git a/Marlin/src/module/stepper/trinamic.h b/Marlin/src/module/stepper/trinamic.h index 0a956a70b3602..9ed9bdf407a8b 100644 --- a/Marlin/src/module/stepper/trinamic.h +++ b/Marlin/src/module/stepper/trinamic.h @@ -74,12 +74,6 @@ #define TMC_CLASS_E(N) TMC_CLASS(E##N, E) #endif -typedef struct { - uint8_t toff; - int8_t hend; - uint8_t hstrt; -} chopper_timing_t; - #ifndef CHOPPER_TIMING_X #define CHOPPER_TIMING_X CHOPPER_TIMING #endif From 13ce5aa1ed4ab4f8fc01f7ff6f7ad7884fc28ea9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 21 Dec 2021 22:15:48 -0600 Subject: [PATCH 209/273] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/DUE/MarlinSerialUSB.cpp | 2 +- Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp | 2 +- Marlin/src/feature/encoder_i2c.cpp | 8 +- Marlin/src/feature/tmc_util.cpp | 8 +- Marlin/src/gcode/calibrate/G425.cpp | 2 +- Marlin/src/gcode/feature/pause/M600.cpp | 6 +- Marlin/src/gcode/feature/pause/M701_M702.cpp | 12 +-- .../src/gcode/feature/power_monitor/M430.cpp | 4 +- .../lcd/extui/anycubic_chiron/chiron_tft.cpp | 2 +- .../generic/files_screen.cpp | 2 +- Marlin/src/sd/Sd2Card.cpp | 83 ++++++++++--------- .../sd/usb_flashdrive/lib-uhs2/usbhost.cpp | 2 +- buildroot/web-ui/data/www/webmarlin-class.js | 20 ++--- 13 files changed, 75 insertions(+), 78 deletions(-) diff --git a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp index 67c597da80c42..8de2dc7924a0d 100644 --- a/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerialUSB.cpp @@ -41,7 +41,7 @@ extern "C" { int udi_cdc_getc(); bool udi_cdc_is_tx_ready(); int udi_cdc_putc(int value); -}; +} // Pending character static int pending_char = -1; diff --git a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp index 3dcbbaecd28f8..34cc256b30ff0 100644 --- a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp +++ b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp @@ -10,7 +10,7 @@ #include "../../../sd/cardreader.h" extern "C" { -#include "sd_mmc_spi_mem.h" + #include "sd_mmc_spi_mem.h" } #define SD_MMC_BLOCK_SIZE 512 diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index 87e611f86c234..2ccd686a992d4 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -756,7 +756,7 @@ int8_t I2CPositionEncodersMgr::parse() { if (!parser.has_value()) { SERIAL_ECHOLNPGM("?A seen, but no address specified! [30-200]"); return I2CPE_PARSE_ERR; - }; + } I2CPE_addr = parser.value_byte(); if (!WITHIN(I2CPE_addr, 30, 200)) { // reserve the first 30 and last 55 @@ -775,7 +775,7 @@ int8_t I2CPositionEncodersMgr::parse() { if (!parser.has_value()) { SERIAL_ECHOLNPGM("?I seen, but no index specified! [0-", I2CPE_ENCODER_CNT - 1, "]"); return I2CPE_PARSE_ERR; - }; + } I2CPE_idx = parser.value_byte(); if (I2CPE_idx >= I2CPE_ENCODER_CNT) { @@ -791,7 +791,7 @@ int8_t I2CPositionEncodersMgr::parse() { I2CPE_anyaxis = parser.seen_axis(); return I2CPE_PARSE_OK; -}; +} /** * M860: Report the position(s) of position encoder module(s). @@ -934,7 +934,7 @@ void I2CPositionEncodersMgr::M864() { if (!parser.has_value()) { SERIAL_ECHOLNPGM("?S seen, but no address specified! [30-200]"); return; - }; + } newAddress = parser.value_byte(); if (!WITHIN(newAddress, 30, 200)) { diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 82c10e6e8ec2d..e793b4cf222aa 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -472,12 +472,8 @@ void tmc_set_report_interval(const uint16_t update_interval) { if ((report_tmc_status_interval = update_interval)) SERIAL_ECHOLNPGM("axis:pwm_scale" - #if HAS_STEALTHCHOP - "/curr_scale" - #endif - #if HAS_STALLGUARD - "/mech_load" - #endif + TERN_(HAS_STEALTHCHOP, "/curr_scale") + TERN_(HAS_STALLGUARD, "/mech_load") "|flags|warncount" ); } diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 88c906f4937aa..31e0bb2587396 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -666,7 +666,7 @@ inline void calibrate_all_toolheads(measurements_t &m, const float uncertainty) * 1) For each nozzle, touch top and sides of object to determine object position and * nozzle offsets. Do a fast but rough search over a wider area. * 2) With the first nozzle, touch top and sides of object to determine backlash values - * for all axis (if BACKLASH_GCODE is enabled) + * for all axes (if BACKLASH_GCODE is enabled) * 3) For each nozzle, touch top and sides of object slowly to determine precise * position of object. Adjust coordinate system and nozzle offsets so probed object * location corresponds to known object location with a high degree of precision. diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index 665967ca564d4..febb946befb58 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -67,13 +67,13 @@ void GcodeSuite::M600() { #if ENABLED(MIXING_EXTRUDER) - const int8_t target_e_stepper = get_target_e_stepper_from_command(); - if (target_e_stepper < 0) return; + const int8_t eindex = get_target_e_stepper_from_command(); + if (eindex < 0) return; const uint8_t old_mixing_tool = mixer.get_current_vtool(); mixer.T(MIXER_DIRECT_SET_TOOL); - MIXER_STEPPER_LOOP(i) mixer.set_collector(i, i == uint8_t(target_e_stepper) ? 1.0 : 0.0); + MIXER_STEPPER_LOOP(i) mixer.set_collector(i, i == uint8_t(eindex) ? 1.0 : 0.0); mixer.normalize(); const int8_t target_extruder = active_extruder; diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index 21e389a5f2013..135b3d384ec0f 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -60,13 +60,13 @@ void GcodeSuite::M701() { if (TERN0(NO_MOTION_BEFORE_HOMING, axes_should_home())) park_point.z = 0; #if ENABLED(MIXING_EXTRUDER) - const int8_t target_e_stepper = get_target_e_stepper_from_command(); - if (target_e_stepper < 0) return; + const int8_t eindex = get_target_e_stepper_from_command(); + if (eindex < 0) return; const uint8_t old_mixing_tool = mixer.get_current_vtool(); mixer.T(MIXER_DIRECT_SET_TOOL); - MIXER_STEPPER_LOOP(i) mixer.set_collector(i, (i == (uint8_t)target_e_stepper) ? 1.0 : 0.0); + MIXER_STEPPER_LOOP(i) mixer.set_collector(i, i == uint8_t(eindex) ? 1.0 : 0.0); mixer.normalize(); const int8_t target_extruder = active_extruder; @@ -165,10 +165,10 @@ void GcodeSuite::M702() { #endif if (seenT) { - const int8_t target_e_stepper = get_target_e_stepper_from_command(); - if (target_e_stepper < 0) return; + const int8_t eindex = get_target_e_stepper_from_command(); + if (eindex < 0) return; mixer.T(MIXER_DIRECT_SET_TOOL); - MIXER_STEPPER_LOOP(i) mixer.set_collector(i, (i == (uint8_t)target_e_stepper) ? 1.0 : 0.0); + MIXER_STEPPER_LOOP(i) mixer.set_collector(i, i == uint8_t(eindex) ? 1.0 : 0.0); mixer.normalize(); } diff --git a/Marlin/src/gcode/feature/power_monitor/M430.cpp b/Marlin/src/gcode/feature/power_monitor/M430.cpp index 642a75d0612ad..0f3bb4091421f 100644 --- a/Marlin/src/gcode/feature/power_monitor/M430.cpp +++ b/Marlin/src/gcode/feature/power_monitor/M430.cpp @@ -53,9 +53,7 @@ void GcodeSuite::M430() { SERIAL_ECHOLNPGM( #if ENABLED(POWER_MONITOR_CURRENT) "Current: ", power_monitor.getAmps(), "A" - #if ENABLED(POWER_MONITOR_VOLTAGE) - " " - #endif + TERN_(POWER_MONITOR_VOLTAGE, " ") #endif #if ENABLED(POWER_MONITOR_VOLTAGE) "Voltage: ", power_monitor.getVolts(), "V" diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index 6db5972fa70f1..c56d8aa7fbb31 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -366,7 +366,7 @@ int8_t ChironTFT::FindToken(char c) { #endif return pos; } - } while(++pos < command_len); + } while (++pos < command_len); #if ACDEBUG(AC_INFO) SERIAL_ECHOLNPGM("Not found: ", c); #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp index 5076e58adf6e2..6f428fa174872 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/files_screen.cpp @@ -77,7 +77,7 @@ const char *FilesScreen::getSelectedFilename(bool shortName) { } void FilesScreen::drawSelectedFile() { - if(mydata.selected_tag == 0xFF) return; + if (mydata.selected_tag == 0xFF) return; FileList files; files.seek(getSelectedFileIndex(), true); mydata.flags.is_dir = files.isDir(); diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index a81932d49485d..3402bfaee3822 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -392,50 +392,51 @@ bool DiskIODriver_SPI_SD::readData(uint8_t *dst) { #if ENABLED(SD_CHECK_AND_RETRY) #ifdef FAST_CRC - static const uint16_t crctab16[] PROGMEM = { - 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7, - 0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF, - 0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6, - 0x9339, 0x8318, 0xB37B, 0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE, - 0x2462, 0x3443, 0x0420, 0x1401, 0x64E6, 0x74C7, 0x44A4, 0x5485, - 0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE, 0xF5CF, 0xC5AC, 0xD58D, - 0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6, 0x5695, 0x46B4, - 0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D, 0xC7BC, - 0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823, - 0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B, - 0x5AF5, 0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12, - 0xDBFD, 0xCBDC, 0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A, - 0x6CA6, 0x7C87, 0x4CE4, 0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41, - 0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD, 0xAD2A, 0xBD0B, 0x8D68, 0x9D49, - 0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13, 0x2E32, 0x1E51, 0x0E70, - 0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A, 0x9F59, 0x8F78, - 0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E, 0xE16F, - 0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067, - 0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E, - 0x02B1, 0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256, - 0xB5EA, 0xA5CB, 0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D, - 0x34E2, 0x24C3, 0x14A0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405, - 0xA7DB, 0xB7FA, 0x8799, 0x97B8, 0xE75F, 0xF77E, 0xC71D, 0xD73C, - 0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657, 0x7676, 0x4615, 0x5634, - 0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9, 0xB98A, 0xA9AB, - 0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882, 0x28A3, - 0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A, - 0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92, - 0xFD2E, 0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9, - 0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1, - 0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8, - 0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0 - }; + static const uint16_t crctab16[] PROGMEM = { + 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7, + 0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF, + 0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6, + 0x9339, 0x8318, 0xB37B, 0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE, + 0x2462, 0x3443, 0x0420, 0x1401, 0x64E6, 0x74C7, 0x44A4, 0x5485, + 0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE, 0xF5CF, 0xC5AC, 0xD58D, + 0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6, 0x5695, 0x46B4, + 0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D, 0xC7BC, + 0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823, + 0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B, + 0x5AF5, 0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12, + 0xDBFD, 0xCBDC, 0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A, + 0x6CA6, 0x7C87, 0x4CE4, 0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41, + 0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD, 0xAD2A, 0xBD0B, 0x8D68, 0x9D49, + 0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13, 0x2E32, 0x1E51, 0x0E70, + 0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A, 0x9F59, 0x8F78, + 0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E, 0xE16F, + 0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067, + 0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E, + 0x02B1, 0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256, + 0xB5EA, 0xA5CB, 0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D, + 0x34E2, 0x24C3, 0x14A0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405, + 0xA7DB, 0xB7FA, 0x8799, 0x97B8, 0xE75F, 0xF77E, 0xC71D, 0xD73C, + 0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657, 0x7676, 0x4615, 0x5634, + 0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9, 0xB98A, 0xA9AB, + 0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882, 0x28A3, + 0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A, + 0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92, + 0xFD2E, 0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9, + 0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1, + 0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8, + 0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0 + }; // faster CRC-CCITT // uses the x^16,x^12,x^5,x^1 polynomial. - static uint16_t CRC_CCITT(const uint8_t *data, size_t n) { - uint16_t crc = 0; - for (size_t i = 0; i < n; i++) { - crc = pgm_read_word(&crctab16[(crc >> 8 ^ data[i]) & 0xFF]) ^ (crc << 8); + static uint16_t CRC_CCITT(const uint8_t *data, size_t n) { + uint16_t crc = 0; + for (size_t i = 0; i < n; i++) + crc = pgm_read_word(&crctab16[(crc >> 8 ^ data[i]) & 0xFF]) ^ (crc << 8); + return crc; } - return crc; - } + #else + // slower CRC-CCITT // uses the x^16,x^12,x^5,x^1 polynomial. static uint16_t CRC_CCITT(const uint8_t *data, size_t n) { @@ -449,7 +450,9 @@ bool DiskIODriver_SPI_SD::readData(uint8_t *dst) { } return crc; } + #endif + #endif // SD_CHECK_AND_RETRY bool DiskIODriver_SPI_SD::readData(uint8_t *dst, const uint16_t count) { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp index a1a3b7d50eadc..9ff9cd77bc8bc 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp @@ -47,7 +47,7 @@ void MAX3421e::regWr(uint8_t reg, uint8_t data) { spiSend(reg | 0x02); spiSend(data); ncs(); -}; +} // multiple-byte write // return a pointer to memory position after last written diff --git a/buildroot/web-ui/data/www/webmarlin-class.js b/buildroot/web-ui/data/www/webmarlin-class.js index 393fd88eef26a..2cfc4cbfba6ff 100644 --- a/buildroot/web-ui/data/www/webmarlin-class.js +++ b/buildroot/web-ui/data/www/webmarlin-class.js @@ -349,18 +349,18 @@ class jsLog { var wmGCommands = { CustomCmd : new wmGCommandItem('',null,null,'Custom command'), - MoveFw : new wmGCommandItem('G1','Y{0}',10,'Move forward on Y axis'), - MoveBw : new wmGCommandItem('G1','Y-{0}',10,'Move backward on Y axis'), - MoveSx : new wmGCommandItem('G1','X{0}',10,'Move left on X axis'), - MoveDx : new wmGCommandItem('G1','X-{0}',10,'Move right on X axis'), - MoveUp : new wmGCommandItem('G1','Z{0}',10,'Move up on Z axis'), - MoveDw : new wmGCommandItem('G1','Z-{0}',10,'Move down on Z axis'), + MoveFw : new wmGCommandItem('G1','Y{0}',10,'Move Y forward'), + MoveBw : new wmGCommandItem('G1','Y-{0}',10,'Move Y backward'), + MoveSx : new wmGCommandItem('G1','X{0}',10,'Move X left'), + MoveDx : new wmGCommandItem('G1','X-{0}',10,'Move X right'), + MoveUp : new wmGCommandItem('G1','Z{0}',10,'Move Z up'), + MoveDw : new wmGCommandItem('G1','Z-{0}',10,'Move Z down'), FillRetrive : new wmGCommandItem('G10',null,null,'Retract filament'), FillExtrude : new wmGCommandItem('GYYYY',null,null,'Extrude filament'), - MoveHome : new wmGCommandItem('G28',null,null,'Go home on all axis'), - MoveHomeX : new wmGCommandItem('G28','X',null,'Go home on X axis'), - MoveHomeY : new wmGCommandItem('G28','Y',null,'Go home on Y axis'), - MoveHomeZ : new wmGCommandItem('G28','Z',null,'Go home on Z axis'), + MoveHome : new wmGCommandItem('G28',null,null,'Home all axes'), + MoveHomeX : new wmGCommandItem('G28','X',null,'Home X axis'), + MoveHomeY : new wmGCommandItem('G28','Y',null,'Home Y axis'), + MoveHomeZ : new wmGCommandItem('G28','Z',null,'Home Z axis'), StepEnable : new wmGCommandItem('M17','{0}','E X Y Z','Enable stepper'), StepEnableAll : new wmGCommandItem('M17',null,null,'Enable all steppers'), StepDisable : new wmGCommandItem('M18','{0}','E X Y Z','Disable stepper'), From 33fa3aba107eb9b4bb1f90a83d6d81a437ed0347 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Dec 2021 06:02:50 -0600 Subject: [PATCH 210/273] =?UTF-8?q?=F0=9F=A9=BA=20Check=20some=20axis-para?= =?UTF-8?q?meter=20collisions?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/L6470/M906.cpp | 4 ++++ Marlin/src/gcode/feature/trinamic/M569.cpp | 4 ++++ Marlin/src/gcode/motion/G5.cpp | 4 ++++ 3 files changed, 12 insertions(+) diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index 9283cdb945ab2..67d11493abf54 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -24,6 +24,10 @@ #if HAS_L64XX +#if AXIS_COLLISION('I') + #error "M906 parameter collision with axis name." +#endif + #include "../../gcode.h" #include "../../../libs/L64XX/L64XX_Marlin.h" #include "../../../module/stepper/indirection.h" diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index ad1d20e8cb178..3f4b0c6372a33 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -24,6 +24,10 @@ #if HAS_STEALTHCHOP +#if AXIS_COLLISION('I') + #error "M569 parameter collision with axis name." +#endif + #include "../../gcode.h" #include "../../../feature/tmc_util.h" #include "../../../module/stepper/indirection.h" diff --git a/Marlin/src/gcode/motion/G5.cpp b/Marlin/src/gcode/motion/G5.cpp index 2c98fae845221..316a59b6506c8 100644 --- a/Marlin/src/gcode/motion/G5.cpp +++ b/Marlin/src/gcode/motion/G5.cpp @@ -24,6 +24,10 @@ #if ENABLED(BEZIER_CURVE_SUPPORT) +#if AXIS_COLLISION('I') || AXIS_COLLISION('J') + #error "G5 parameter collision with axis name." +#endif + #include "../../module/motion.h" #include "../../module/planner_bezier.h" From 6fb2d8a25f096d084348a6f6930f515d947474d4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Dec 2021 02:57:24 -0600 Subject: [PATCH 211/273] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Rem?= =?UTF-8?q?ove=20extraneous=20'inline'=20hints?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/MarlinSerial.h | 2 +- Marlin/src/HAL/DUE/MarlinSerial.h | 2 +- Marlin/src/HAL/LPC1768/include/SPI.h | 2 +- Marlin/src/HAL/LPC1768/tft/xpt2046.h | 4 +- Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h | 4 +- Marlin/src/HAL/STM32/tft/xpt2046.h | 4 +- Marlin/src/HAL/STM32F1/SPI.h | 2 +- Marlin/src/HAL/STM32F1/pinsDebug.h | 14 +- Marlin/src/HAL/STM32F1/tft/xpt2046.h | 4 +- Marlin/src/HAL/shared/eeprom_api.h | 6 +- Marlin/src/core/macros.h | 16 +- Marlin/src/core/serial_hook.h | 2 +- Marlin/src/feature/babystep.h | 6 +- Marlin/src/feature/backlash.h | 10 +- .../feature/bedlevel/mbl/mesh_bed_leveling.h | 10 +- Marlin/src/feature/bedlevel/ubl/ubl.h | 22 +-- Marlin/src/feature/bltouch.h | 2 +- Marlin/src/feature/cancel_object.h | 8 +- Marlin/src/feature/caselight.h | 4 +- Marlin/src/feature/controllerfan.h | 6 +- Marlin/src/feature/fancheck.h | 8 +- Marlin/src/feature/filwidth.h | 16 +- Marlin/src/feature/host_actions.h | 4 +- Marlin/src/feature/leds/leds.h | 52 +++--- Marlin/src/feature/leds/neopixel.h | 28 ++-- Marlin/src/feature/leds/printer_event_leds.h | 16 +- Marlin/src/feature/max7219.h | 6 +- Marlin/src/feature/mixing.h | 10 +- Marlin/src/feature/mmu/mmu2.h | 12 +- Marlin/src/feature/power.h | 2 +- Marlin/src/feature/powerloss.h | 22 +-- Marlin/src/feature/probe_temp_comp.h | 6 +- Marlin/src/feature/repeat.h | 4 +- Marlin/src/feature/runout.h | 54 +++---- Marlin/src/feature/spindle_laser.h | 42 ++--- Marlin/src/feature/twibus.h | 8 +- Marlin/src/gcode/gcode.h | 18 +-- Marlin/src/gcode/parser.h | 118 +++++++------- Marlin/src/gcode/queue.h | 14 +- Marlin/src/lcd/e3v2/enhanced/lockscreen.h | 2 +- Marlin/src/lcd/e3v2/marlinui/dwin_string.h | 16 +- Marlin/src/lcd/extui/dgus/DGUSDisplay.h | 4 +- .../lcd/extui/dgus/fysetc/DGUSScreenHandler.h | 12 +- .../extui/dgus/hiprecy/DGUSScreenHandler.h | 12 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.h | 12 +- .../lcd/extui/dgus/origin/DGUSScreenHandler.h | 12 +- .../src/lcd/extui/dgus_reloaded/DGUSDisplay.h | 2 +- .../src/lcd/extui/ftdi_eve_touch_ui/compat.h | 4 +- .../ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 28 ++-- .../ftdi_eve_lib/extended/sound_list.h | 4 +- Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h | 4 +- Marlin/src/lcd/marlinui.h | 62 ++++---- Marlin/src/lcd/menu/menu.h | 4 +- Marlin/src/lcd/menu/menu_item.h | 26 +-- Marlin/src/lcd/tft/tft.h | 32 ++-- Marlin/src/lcd/tft/tft_string.h | 8 +- Marlin/src/lcd/tft/touch.h | 4 +- Marlin/src/libs/L64XX/L64XX_Marlin.h | 4 +- Marlin/src/libs/buzzer.h | 4 +- Marlin/src/libs/stopwatch.h | 4 +- Marlin/src/module/endstops.h | 4 +- Marlin/src/module/planner.h | 20 +-- Marlin/src/module/printcounter.h | 6 +- Marlin/src/module/settings.h | 2 +- Marlin/src/module/stepper.h | 24 +-- Marlin/src/module/temperature.h | 150 +++++++++--------- Marlin/src/sd/cardreader.h | 38 ++--- 67 files changed, 537 insertions(+), 537 deletions(-) diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h index 0565c7b9db9ee..84c5ddd2978ee 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -217,7 +217,7 @@ #endif enum { HasEmergencyParser = Cfg::EMERGENCYPARSER }; - static inline bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; } + static bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; } FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; } FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; } diff --git a/Marlin/src/HAL/DUE/MarlinSerial.h b/Marlin/src/HAL/DUE/MarlinSerial.h index 4a62e2834f7f4..5a61bffee0da0 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.h +++ b/Marlin/src/HAL/DUE/MarlinSerial.h @@ -118,7 +118,7 @@ class MarlinSerial { static size_t write(const uint8_t c); static void flushTX(); - static inline bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; } + static bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; } FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; } FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; } diff --git a/Marlin/src/HAL/LPC1768/include/SPI.h b/Marlin/src/HAL/LPC1768/include/SPI.h index ecd91f6a3b736..24f4759315bd8 100644 --- a/Marlin/src/HAL/LPC1768/include/SPI.h +++ b/Marlin/src/HAL/LPC1768/include/SPI.h @@ -77,7 +77,7 @@ class SPISettings { //uint32_t spiRate() const { return spi_speed; } - static inline uint32_t spiRate2Clock(uint32_t spiRate) { + static uint32_t spiRate2Clock(uint32_t spiRate) { uint32_t Marlin_speed[7]; // CPSR is always 2 Marlin_speed[0] = 8333333; //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED Marlin_speed[1] = 4166667; //(SCR: 5) desired: 4,000,000 actual: 4,166,667 +4.2% SPI_HALF_SPEED diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.h b/Marlin/src/HAL/LPC1768/tft/xpt2046.h index aba0799e445f8..7c456cf00e1be 100644 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.h +++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.h @@ -65,8 +65,8 @@ class XPT2046 { static uint16_t getRawData(const XPTCoordinate coordinate); static bool isTouched(); - static inline void DataTransferBegin() { WRITE(TOUCH_CS_PIN, LOW); }; - static inline void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; + static void DataTransferBegin() { WRITE(TOUCH_CS_PIN, LOW); }; + static void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; #if ENABLED(TOUCH_BUTTONS_HW_SPI) static uint16_t HardwareIO(uint16_t data); #endif diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h index 9ef1816c7b169..b131853643a8b 100644 --- a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h +++ b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h @@ -62,8 +62,8 @@ class XPT2046 { static uint16_t getRawData(const XPTCoordinate coordinate); static bool isTouched(); - static inline void DataTransferBegin(); - static inline void DataTransferEnd(); + static void DataTransferBegin(); + static void DataTransferEnd(); #if ENABLED(TOUCH_BUTTONS_HW_SPI) static uint16_t HardwareIO(uint16_t data); #endif diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.h b/Marlin/src/HAL/STM32/tft/xpt2046.h index 2cff3e29d05be..71de6b00251b1 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.h +++ b/Marlin/src/HAL/STM32/tft/xpt2046.h @@ -69,8 +69,8 @@ class XPT2046 { static uint16_t getRawData(const XPTCoordinate coordinate); static bool isTouched(); - static inline void DataTransferBegin() { if (SPIx.Instance) { HAL_SPI_Init(&SPIx); } WRITE(TOUCH_CS_PIN, LOW); }; - static inline void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; + static void DataTransferBegin() { if (SPIx.Instance) { HAL_SPI_Init(&SPIx); } WRITE(TOUCH_CS_PIN, LOW); }; + static void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; static uint16_t HardwareIO(uint16_t data); static uint16_t SoftwareIO(uint16_t data); static uint16_t IO(uint16_t data = 0) { return SPIx.Instance ? HardwareIO(data) : SoftwareIO(data); } diff --git a/Marlin/src/HAL/STM32F1/SPI.h b/Marlin/src/HAL/STM32F1/SPI.h index 2467432e07184..92f42263014a6 100644 --- a/Marlin/src/HAL/STM32F1/SPI.h +++ b/Marlin/src/HAL/STM32F1/SPI.h @@ -417,7 +417,7 @@ class SPIClass { /** * @brief Wait until TXE (tx empty) flag is set and BSY (busy) flag unset. */ -static inline void waitSpiTxEnd(spi_dev *spi_d) { +static void waitSpiTxEnd(spi_dev *spi_d) { while (spi_is_tx_empty(spi_d) == 0) { /* nada */ } // wait until TXE=1 while (spi_is_busy(spi_d) != 0) { /* nada */ } // wait until BSY=0 } diff --git a/Marlin/src/HAL/STM32F1/pinsDebug.h b/Marlin/src/HAL/STM32F1/pinsDebug.h index 27f4b6732bfb3..7828479658a9e 100644 --- a/Marlin/src/HAL/STM32F1/pinsDebug.h +++ b/Marlin/src/HAL/STM32F1/pinsDebug.h @@ -54,11 +54,11 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]; #define M43_NEVER_TOUCH(Q) (Q >= 9 && Q <= 12) // SERIAL/USB pins PA9(TX) PA10(RX) #endif -static inline int8_t get_pin_mode(pin_t pin) { +static int8_t get_pin_mode(pin_t pin) { return VALID_PIN(pin) ? _GET_MODE(pin) : -1; } -static inline pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) { +static pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) { if (!VALID_PIN(pin)) return -1; int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel); #ifdef NUM_ANALOG_INPUTS @@ -67,7 +67,7 @@ static inline pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) { return pin_t(adc_channel); } -static inline bool IS_ANALOG(pin_t pin) { +static bool IS_ANALOG(pin_t pin) { if (!VALID_PIN(pin)) return false; if (PIN_MAP[pin].adc_channel != ADCx) { #ifdef NUM_ANALOG_INPUTS @@ -78,11 +78,11 @@ static inline bool IS_ANALOG(pin_t pin) { return false; } -static inline bool GET_PINMODE(const pin_t pin) { +static bool GET_PINMODE(const pin_t pin) { return VALID_PIN(pin) && !IS_INPUT(pin); } -static inline bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) { +static bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) { const pin_t pin = GET_ARRAY_PIN(array_pin); return (!IS_ANALOG(pin) #ifdef NUM_ANALOG_INPUTS @@ -93,7 +93,7 @@ static inline bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) { #include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density -static inline void pwm_details(const pin_t pin) { +static void pwm_details(const pin_t pin) { if (PWM_PIN(pin)) { timer_dev * const tdev = PIN_MAP[pin].timer_device; const uint8_t channel = PIN_MAP[pin].timer_channel; @@ -113,7 +113,7 @@ static inline void pwm_details(const pin_t pin) { } } -static inline void print_port(pin_t pin) { +static void print_port(pin_t pin) { const char port = 'A' + char(pin >> 4); // pin div 16 const int16_t gbit = PIN_MAP[pin].gpio_bit; char buffer[8]; diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.h b/Marlin/src/HAL/STM32F1/tft/xpt2046.h index aba0799e445f8..7c456cf00e1be 100644 --- a/Marlin/src/HAL/STM32F1/tft/xpt2046.h +++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.h @@ -65,8 +65,8 @@ class XPT2046 { static uint16_t getRawData(const XPTCoordinate coordinate); static bool isTouched(); - static inline void DataTransferBegin() { WRITE(TOUCH_CS_PIN, LOW); }; - static inline void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; + static void DataTransferBegin() { WRITE(TOUCH_CS_PIN, LOW); }; + static void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; #if ENABLED(TOUCH_BUTTONS_HW_SPI) static uint16_t HardwareIO(uint16_t data); #endif diff --git a/Marlin/src/HAL/shared/eeprom_api.h b/Marlin/src/HAL/shared/eeprom_api.h index 1f38639930dc8..cd744f82dc791 100644 --- a/Marlin/src/HAL/shared/eeprom_api.h +++ b/Marlin/src/HAL/shared/eeprom_api.h @@ -49,7 +49,7 @@ class PersistentStore { // Write one or more bytes of data // Return 'true' on write error - static inline bool write_data(const int pos, const uint8_t *value, const size_t size=sizeof(uint8_t)) { + static bool write_data(const int pos, const uint8_t *value, const size_t size=sizeof(uint8_t)) { int data_pos = pos; uint16_t crc = 0; return write_data(data_pos, value, size, &crc); @@ -57,11 +57,11 @@ class PersistentStore { // Write a single byte of data // Return 'true' on write error - static inline bool write_data(const int pos, const uint8_t value) { return write_data(pos, &value); } + static bool write_data(const int pos, const uint8_t value) { return write_data(pos, &value); } // Read one or more bytes of data // Return 'true' on read error - static inline bool read_data(const int pos, uint8_t *value, const size_t size=1) { + static bool read_data(const int pos, uint8_t *value, const size_t size=1) { int data_pos = pos; uint16_t crc = 0; return read_data(data_pos, value, size, &crc); diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 62675d1319721..34fc3bc4108e7 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -131,13 +131,13 @@ #ifdef __cplusplus // C++11 solution that is standards compliant. - template static inline constexpr void NOLESS(V& v, const N n) { + template static constexpr void NOLESS(V& v, const N n) { if (n > v) v = n; } - template static inline constexpr void NOMORE(V& v, const N n) { + template static constexpr void NOMORE(V& v, const N n) { if (n < v) v = n; } - template static inline constexpr void LIMIT(V& v, const N1 n1, const N2 n2) { + template static constexpr void LIMIT(V& v, const N1 n1, const N2 n2) { if (n1 > v) v = n1; else if (n2 < v) v = n2; } @@ -366,7 +366,7 @@ #undef ABS #ifdef __cplusplus - template static inline constexpr const T ABS(const T v) { return v >= 0 ? v : -v; } + template static constexpr const T ABS(const T v) { return v >= 0 ? v : -v; } #else #define ABS(a) ({__typeof__(a) _a = (a); _a >= 0 ? _a : -_a;}) #endif @@ -409,14 +409,14 @@ extern "C++" { // C++11 solution that is standards compliant. Return type is deduced automatically - template static inline constexpr auto _MIN(const L lhs, const R rhs) -> decltype(lhs + rhs) { + template static constexpr auto _MIN(const L lhs, const R rhs) -> decltype(lhs + rhs) { return lhs < rhs ? lhs : rhs; } - template static inline constexpr auto _MAX(const L lhs, const R rhs) -> decltype(lhs + rhs) { + template static constexpr auto _MAX(const L lhs, const R rhs) -> decltype(lhs + rhs) { return lhs > rhs ? lhs : rhs; } - template static inline constexpr const T _MIN(T V, Ts... Vs) { return _MIN(V, _MIN(Vs...)); } - template static inline constexpr const T _MAX(T V, Ts... Vs) { return _MAX(V, _MAX(Vs...)); } + template static constexpr const T _MIN(T V, Ts... Vs) { return _MIN(V, _MIN(Vs...)); } + template static constexpr const T _MAX(T V, Ts... Vs) { return _MAX(V, _MAX(Vs...)); } } diff --git a/Marlin/src/core/serial_hook.h b/Marlin/src/core/serial_hook.h index 2019b389e4977..9b9fa8fa38287 100644 --- a/Marlin/src/core/serial_hook.h +++ b/Marlin/src/core/serial_hook.h @@ -37,7 +37,7 @@ class SerialMask { inline constexpr bool enabled(const SerialMask PortMask) const { return mask & PortMask.mask; } inline constexpr SerialMask combine(const SerialMask other) const { return SerialMask(mask | other.mask); } inline constexpr SerialMask operator<< (const int offset) const { return SerialMask(mask << offset); } - static inline SerialMask from(const serial_index_t index) { + static SerialMask from(const serial_index_t index) { if (index.valid()) return SerialMask(_BV(index.index)); return SerialMask(0); // A invalid index mean no output } diff --git a/Marlin/src/feature/babystep.h b/Marlin/src/feature/babystep.h index f8037678ca16f..5693afb4fc5b1 100644 --- a/Marlin/src/feature/babystep.h +++ b/Marlin/src/feature/babystep.h @@ -54,7 +54,7 @@ class Babystep { #if ENABLED(BABYSTEP_DISPLAY_TOTAL) static int16_t axis_total[BS_TOTAL_IND(Z_AXIS) + 1]; // Total babysteps since G28 - static inline void reset_total(const AxisEnum axis) { + static void reset_total(const AxisEnum axis) { if (TERN1(BABYSTEP_XY, axis == Z_AXIS)) axis_total[BS_TOTAL_IND(axis)] = 0; } @@ -63,7 +63,7 @@ class Babystep { static void add_steps(const AxisEnum axis, const int16_t distance); static void add_mm(const AxisEnum axis, const_float_t mm); - static inline bool has_steps() { + static bool has_steps() { return steps[BS_AXIS_IND(X_AXIS)] || steps[BS_AXIS_IND(Y_AXIS)] || steps[BS_AXIS_IND(Z_AXIS)]; } @@ -71,7 +71,7 @@ class Babystep { // Called by the Temperature or Stepper ISR to // apply accumulated babysteps to the axes. // - static inline void task() { + static void task() { LOOP_LE_N(i, BS_AXIS_IND(Z_AXIS)) step_axis(BS_AXIS(i)); } diff --git a/Marlin/src/feature/backlash.h b/Marlin/src/feature/backlash.h index 4d4e2940382c2..17504cc781819 100644 --- a/Marlin/src/feature/backlash.h +++ b/Marlin/src/feature/backlash.h @@ -35,8 +35,8 @@ class Backlash { static float smoothing_mm; #endif - static inline void set_correction(const_float_t v) { correction = _MAX(0, _MIN(1.0, v)) * all_on; } - static inline float get_correction() { return float(ui8_to_percent(correction)) / 100.0f; } + static void set_correction(const_float_t v) { correction = _MAX(0, _MIN(1.0, v)) * all_on; } + static float get_correction() { return float(ui8_to_percent(correction)) / 100.0f; } #else static constexpr uint8_t correction = (BACKLASH_CORRECTION) * 0xFF; static const xyz_float_t distance_mm; @@ -53,7 +53,7 @@ class Backlash { static void measure_with_probe(); #endif - static inline float get_measurement(const AxisEnum a) { + static float get_measurement(const AxisEnum a) { UNUSED(a); // Return the measurement averaged over all readings return TERN(MEASURE_BACKLASH_WHEN_PROBING @@ -62,12 +62,12 @@ class Backlash { ); } - static inline bool has_measurement(const AxisEnum a) { + static bool has_measurement(const AxisEnum a) { UNUSED(a); return TERN0(MEASURE_BACKLASH_WHEN_PROBING, measured_count[a] > 0); } - static inline bool has_any_measurement() { + static bool has_any_measurement() { return has_measurement(X_AXIS) || has_measurement(Y_AXIS) || has_measurement(Z_AXIS); } diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h index cc54695771893..06fae16c21e9b 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h @@ -58,7 +58,7 @@ class mesh_bed_leveling { static void set_z(const int8_t px, const int8_t py, const_float_t z) { z_values[px][py] = z; } - static inline void zigzag(const int8_t index, int8_t &px, int8_t &py) { + static void zigzag(const int8_t index, int8_t &px, int8_t &py) { px = index % (GRID_MAX_POINTS_X); py = index / (GRID_MAX_POINTS_X); if (py & 1) px = (GRID_MAX_POINTS_X) - 1 - px; // Zig zag @@ -78,10 +78,10 @@ class mesh_bed_leveling { int8_t cy = (y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST); return constrain(cy, 0, GRID_MAX_CELLS_Y - 1); } - static inline xy_int8_t cell_indexes(const_float_t x, const_float_t y) { + static xy_int8_t cell_indexes(const_float_t x, const_float_t y) { return { cell_index_x(x), cell_index_y(y) }; } - static inline xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } + static xy_int8_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); @@ -91,10 +91,10 @@ class mesh_bed_leveling { int8_t py = (y - (MESH_MIN_Y) + 0.5f * (MESH_Y_DIST)) * RECIPROCAL(MESH_Y_DIST); return WITHIN(py, 0, (GRID_MAX_POINTS_Y) - 1) ? py : -1; } - static inline xy_int8_t probe_indexes(const_float_t x, const_float_t y) { + static xy_int8_t probe_indexes(const_float_t x, const_float_t y) { return { probe_index_x(x), probe_index_y(y) }; } - static inline xy_int8_t probe_indexes(const xy_pos_t &xy) { return probe_indexes(xy.x, xy.y); } + static xy_int8_t probe_indexes(const xy_pos_t &xy) { return probe_indexes(xy.x, xy.y); } static float calc_z0(const_float_t a0, const_float_t a1, const_float_t z1, const_float_t a2, const_float_t z2) { const float delta_z = (z2 - z1) / (a2 - a1), diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index ffabadd990b38..73581504b7876 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -80,7 +80,7 @@ class unified_bed_leveling { static void tilt_mesh_based_on_3pts(const_float_t z1, const_float_t z2, const_float_t z3); static void tilt_mesh_based_on_probed_grid(const bool do_ubl_mesh_map); static bool smart_fill_one(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir); - static inline bool smart_fill_one(const xy_uint8_t &pos, const xy_uint8_t &dir) { + static bool smart_fill_one(const xy_uint8_t &pos, const xy_uint8_t &dir) { return smart_fill_one(pos.x, pos.y, dir.x, dir.y); } static void smart_fill_mesh(); @@ -124,7 +124,7 @@ class unified_bed_leveling { static bool lcd_map_control; static void steppers_were_disabled(); #else - static inline void steppers_were_disabled() {} + static void steppers_were_disabled() {} #endif static volatile int16_t encoder_diff; // Volatile because buttons may change it at interrupt time @@ -157,10 +157,10 @@ class unified_bed_leveling { return constrain(cell_index_y_raw(y), 0, GRID_MAX_CELLS_Y - 1); } - static inline xy_int8_t cell_indexes(const_float_t x, const_float_t y) { + static xy_int8_t cell_indexes(const_float_t x, const_float_t y) { return { cell_index_x(x), cell_index_y(y) }; } - static inline xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } + static xy_int8_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); @@ -170,7 +170,7 @@ class unified_bed_leveling { const int8_t py = (y - (MESH_MIN_Y) + (MESH_Y_DIST) * 0.5) * RECIPROCAL(MESH_Y_DIST); return WITHIN(py, 0, (GRID_MAX_POINTS_Y) - 1) ? py : -1; } - static inline xy_int8_t closest_indexes(const xy_pos_t &xy) { + static xy_int8_t closest_indexes(const xy_pos_t &xy) { return { closest_x_index(xy.x), closest_y_index(xy.y) }; } @@ -203,7 +203,7 @@ class unified_bed_leveling { * z_correction_for_x_on_horizontal_mesh_line is an optimization for * the case where the printer is making a vertical line that only crosses horizontal mesh lines. */ - static inline float z_correction_for_x_on_horizontal_mesh_line(const_float_t rx0, const int x1_i, const int yi) { + static float z_correction_for_x_on_horizontal_mesh_line(const_float_t rx0, const int x1_i, const int yi) { if (!WITHIN(x1_i, 0, (GRID_MAX_POINTS_X) - 1) || !WITHIN(yi, 0, (GRID_MAX_POINTS_Y) - 1)) { if (DEBUGGING(LEVELING)) { @@ -226,7 +226,7 @@ class unified_bed_leveling { // // See comments above for z_correction_for_x_on_horizontal_mesh_line // - static inline float z_correction_for_y_on_vertical_mesh_line(const_float_t ry0, const int xi, const int y1_i) { + static float z_correction_for_y_on_vertical_mesh_line(const_float_t ry0, const int xi, const int y1_i) { if (!WITHIN(xi, 0, (GRID_MAX_POINTS_X) - 1) || !WITHIN(y1_i, 0, (GRID_MAX_POINTS_Y) - 1)) { if (DEBUGGING(LEVELING)) { @@ -285,12 +285,12 @@ class unified_bed_leveling { return z0; } - static inline float get_z_correction(const xy_pos_t &pos) { return get_z_correction(pos.x, pos.y); } + static float get_z_correction(const xy_pos_t &pos) { return get_z_correction(pos.x, pos.y); } - static inline float mesh_index_to_xpos(const uint8_t i) { + static float mesh_index_to_xpos(const uint8_t i) { return i < (GRID_MAX_POINTS_X) ? pgm_read_float(&_mesh_index_to_xpos[i]) : MESH_MIN_X + i * (MESH_X_DIST); } - static inline float mesh_index_to_ypos(const uint8_t i) { + static float mesh_index_to_ypos(const uint8_t i) { return i < (GRID_MAX_POINTS_Y) ? pgm_read_float(&_mesh_index_to_ypos[i]) : MESH_MIN_Y + i * (MESH_Y_DIST); } @@ -300,7 +300,7 @@ class unified_bed_leveling { static void line_to_destination_cartesian(const_feedRate_t scaled_fr_mm_s, const uint8_t e); #endif - static inline bool mesh_is_valid() { + static bool mesh_is_valid() { GRID_LOOP(x, y) if (isnan(z_values[x][y])) return false; return true; } diff --git a/Marlin/src/feature/bltouch.h b/Marlin/src/feature/bltouch.h index ae3ab66300365..fa857bb96ab6f 100644 --- a/Marlin/src/feature/bltouch.h +++ b/Marlin/src/feature/bltouch.h @@ -76,7 +76,7 @@ class BLTouch { static constexpr bool high_speed_mode = false; #endif - static inline float z_extra_clearance() { return high_speed_mode ? 7 : 0; } + static float z_extra_clearance() { return high_speed_mode ? 7 : 0; } // DEPLOY and STOW are wrapped for error handling - these are used by homing and by probing static bool deploy() { return deploy_proc(); } diff --git a/Marlin/src/feature/cancel_object.h b/Marlin/src/feature/cancel_object.h index 1d2d77f20334e..62548a371937d 100644 --- a/Marlin/src/feature/cancel_object.h +++ b/Marlin/src/feature/cancel_object.h @@ -32,10 +32,10 @@ class CancelObject { static void cancel_object(const int8_t obj); static void uncancel_object(const int8_t obj); static void report(); - static inline bool is_canceled(const int8_t obj) { return TEST(canceled, obj); } - static inline void clear_active_object() { set_active_object(-1); } - static inline void cancel_active_object() { cancel_object(active_object); } - static inline void reset() { canceled = 0x0000; object_count = 0; clear_active_object(); } + static bool is_canceled(const int8_t obj) { return TEST(canceled, obj); } + static void clear_active_object() { set_active_object(-1); } + static void cancel_active_object() { cancel_object(active_object); } + static void reset() { canceled = 0x0000; object_count = 0; clear_active_object(); } }; extern CancelObject cancelable; diff --git a/Marlin/src/feature/caselight.h b/Marlin/src/feature/caselight.h index b2e82f9b838f8..2e85b59ef9388 100644 --- a/Marlin/src/feature/caselight.h +++ b/Marlin/src/feature/caselight.h @@ -49,8 +49,8 @@ class CaseLight { } static void update(const bool sflag); - static inline void update_brightness() { update(false); } - static inline void update_enabled() { update(true); } + static void update_brightness() { update(false); } + static void update_enabled() { update(true); } #if ENABLED(CASE_LIGHT_IS_COLOR_LED) private: diff --git a/Marlin/src/feature/controllerfan.h b/Marlin/src/feature/controllerfan.h index 55f2d5cfc7aa2..55eb2359b0677 100644 --- a/Marlin/src/feature/controllerfan.h +++ b/Marlin/src/feature/controllerfan.h @@ -60,9 +60,9 @@ class ControllerFan { #else static const controllerFan_settings_t &settings; #endif - static inline bool state() { return speed > 0; } - static inline void init() { reset(); } - static inline void reset() { TERN_(CONTROLLER_FAN_EDITABLE, settings = controllerFan_defaults); } + static bool state() { return speed > 0; } + static void init() { reset(); } + static void reset() { TERN_(CONTROLLER_FAN_EDITABLE, settings = controllerFan_defaults); } static void setup(); static void update(); }; diff --git a/Marlin/src/feature/fancheck.h b/Marlin/src/feature/fancheck.h index 6e8038b498e7c..c8665a0e96e8a 100644 --- a/Marlin/src/feature/fancheck.h +++ b/Marlin/src/feature/fancheck.h @@ -56,7 +56,7 @@ class FanCheck { static uint8_t rps[TACHO_COUNT]; static TachoError error; - static inline void report_speed_error(uint8_t fan); + static void report_speed_error(uint8_t fan); public: @@ -67,11 +67,11 @@ class FanCheck { static void compute_speed(uint16_t elapsedTime); static void print_fan_states(); #if HAS_PWMFANCHECK - static inline void toggle_measuring() { measuring = !measuring; } - static inline bool is_measuring() { return measuring; } + static void toggle_measuring() { measuring = !measuring; } + static bool is_measuring() { return measuring; } #endif - static inline void check_deferred_error() { + static void check_deferred_error() { if (error == TachoError::DETECTED) { error = TachoError::REPORTED; TERN(PARK_HEAD_ON_PAUSE, queue.inject(F("M125")), kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT))); diff --git a/Marlin/src/feature/filwidth.h b/Marlin/src/feature/filwidth.h index e63d3d719ffb6..e234380e981a9 100644 --- a/Marlin/src/feature/filwidth.h +++ b/Marlin/src/feature/filwidth.h @@ -41,9 +41,9 @@ class FilamentWidthSensor { FilamentWidthSensor() { init(); } static void init(); - static inline void enable(const bool ena) { enabled = ena; } + static void enable(const bool ena) { enabled = ena; } - static inline void set_delay_cm(const uint8_t cm) { + static void set_delay_cm(const uint8_t cm) { meas_delay_cm = _MIN(cm, MAX_MEASUREMENT_DELAY); } @@ -67,18 +67,18 @@ class FilamentWidthSensor { } // Convert raw measurement to mm - static inline float raw_to_mm(const uint16_t v) { return v * 5.0f * RECIPROCAL(float(MAX_RAW_THERMISTOR_VALUE)); } - static inline float raw_to_mm() { return raw_to_mm(raw); } + static float raw_to_mm(const uint16_t v) { return v * 5.0f * RECIPROCAL(float(MAX_RAW_THERMISTOR_VALUE)); } + static float raw_to_mm() { return raw_to_mm(raw); } // A scaled reading is ready // Divide to get to 0-16384 range since we used 1/128 IIR filter approach - static inline void reading_ready() { raw = accum >> 10; } + static void reading_ready() { raw = accum >> 10; } // Update mm from the raw measurement - static inline void update_measured_mm() { measured_mm = raw_to_mm(); } + static void update_measured_mm() { measured_mm = raw_to_mm(); } // Update ring buffer used to delay filament measurements - static inline void advance_e(const_float_t e_move) { + static void advance_e(const_float_t e_move) { // Increment counters with the E distance e_count += e_move; @@ -106,7 +106,7 @@ class FilamentWidthSensor { } // Dynamically set the volumetric multiplier based on the delayed width measurement. - static inline void update_volumetric() { + static void update_volumetric() { if (enabled) { int8_t read_index = index_r - meas_delay_cm; if (read_index < 0) read_index += MMD_CM; // Loop around buffer if needed diff --git a/Marlin/src/feature/host_actions.h b/Marlin/src/feature/host_actions.h index 45379afc29ec3..78a7821eba856 100644 --- a/Marlin/src/feature/host_actions.h +++ b/Marlin/src/feature/host_actions.h @@ -97,7 +97,7 @@ class HostUI { static void handle_response(const uint8_t response); static void notify_P(PGM_P const message); - static inline void notify(FSTR_P const fmsg) { notify_P(FTOP(fmsg)); } + static void notify(FSTR_P const fmsg) { notify_P(FTOP(fmsg)); } static void notify(const char * const message); static void prompt_begin(const PromptReason reason, FSTR_P const fstr, const char extra_char='\0'); @@ -105,7 +105,7 @@ class HostUI { static void prompt_end(); static void prompt_do(const PromptReason reason, FSTR_P const pstr, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr); static void prompt_do(const PromptReason reason, FSTR_P const pstr, const char extra_char, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr); - static inline void prompt_open(const PromptReason reason, FSTR_P const pstr, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr) { + static void prompt_open(const PromptReason reason, FSTR_P const pstr, FSTR_P const btn1=nullptr, FSTR_P const btn2=nullptr) { if (host_prompt_reason == PROMPT_NOT_DEFINED) prompt_do(reason, pstr, btn1, btn2); } diff --git a/Marlin/src/feature/leds/leds.h b/Marlin/src/feature/leds/leds.h index 74964b51a8e46..7110a9ba82554 100644 --- a/Marlin/src/feature/leds/leds.h +++ b/Marlin/src/feature/leds/leds.h @@ -118,7 +118,7 @@ class LEDLights { OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence=false) ); - static inline void set_color(uint8_t r, uint8_t g, uint8_t b + static void set_color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w=0) OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS) OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence=false) @@ -126,23 +126,23 @@ class LEDLights { set_color(LEDColor(r, g, b OPTARG(HAS_WHITE_LED, w) OPTARG(NEOPIXEL_LED, i)) OPTARG(NEOPIXEL_IS_SEQUENTIAL, isSequence)); } - static inline void set_off() { set_color(LEDColorOff()); } - static inline void set_green() { set_color(LEDColorGreen()); } - static inline void set_white() { set_color(LEDColorWhite()); } + static void set_off() { set_color(LEDColorOff()); } + static void set_green() { set_color(LEDColorGreen()); } + static void set_white() { set_color(LEDColorWhite()); } #if ENABLED(LED_COLOR_PRESETS) static const LEDColor defaultLEDColor; - static inline void set_default() { set_color(defaultLEDColor); } - static inline void set_red() { set_color(LEDColorRed()); } - static inline void set_orange() { set_color(LEDColorOrange()); } - static inline void set_yellow() { set_color(LEDColorYellow()); } - static inline void set_blue() { set_color(LEDColorBlue()); } - static inline void set_indigo() { set_color(LEDColorIndigo()); } - static inline void set_violet() { set_color(LEDColorViolet()); } + static void set_default() { set_color(defaultLEDColor); } + static void set_red() { set_color(LEDColorRed()); } + static void set_orange() { set_color(LEDColorOrange()); } + static void set_yellow() { set_color(LEDColorYellow()); } + static void set_blue() { set_color(LEDColorBlue()); } + static void set_indigo() { set_color(LEDColorIndigo()); } + static void set_violet() { set_color(LEDColorViolet()); } #endif #if ENABLED(PRINTER_EVENT_LEDS) - static inline LEDColor get_color() { return lights_on ? color : LEDColorOff(); } + static LEDColor get_color() { return lights_on ? color : LEDColorOff(); } #endif #if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS, CASE_LIGHT_IS_COLOR_LED) @@ -154,14 +154,14 @@ class LEDLights { static void toggle(); // swap "off" with color #endif #if EITHER(LED_CONTROL_MENU, CASE_LIGHT_USE_RGB_LED) - static inline void update() { set_color(color); } + static void update() { set_color(color); } #endif #ifdef LED_BACKLIGHT_TIMEOUT private: static millis_t led_off_time; public: - static inline void reset_timeout(const millis_t &ms) { + static void reset_timeout(const millis_t &ms) { led_off_time = ms + LED_BACKLIGHT_TIMEOUT; if (!lights_on) update(); } @@ -181,7 +181,7 @@ extern LEDLights leds; static void set_color(const LEDColor &color); - static inline void set_color(uint8_t r, uint8_t g, uint8_t b + static void set_color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w=0) OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS) ) { @@ -191,26 +191,26 @@ extern LEDLights leds; )); } - static inline void set_off() { set_color(LEDColorOff()); } - static inline void set_green() { set_color(LEDColorGreen()); } - static inline void set_white() { set_color(LEDColorWhite()); } + static void set_off() { set_color(LEDColorOff()); } + static void set_green() { set_color(LEDColorGreen()); } + static void set_white() { set_color(LEDColorWhite()); } #if ENABLED(NEO2_COLOR_PRESETS) static const LEDColor defaultLEDColor; - static inline void set_default() { set_color(defaultLEDColor); } - static inline void set_red() { set_color(LEDColorRed()); } - static inline void set_orange() { set_color(LEDColorOrange()); } - static inline void set_yellow() { set_color(LEDColorYellow()); } - static inline void set_blue() { set_color(LEDColorBlue()); } - static inline void set_indigo() { set_color(LEDColorIndigo()); } - static inline void set_violet() { set_color(LEDColorViolet()); } + static void set_default() { set_color(defaultLEDColor); } + static void set_red() { set_color(LEDColorRed()); } + static void set_orange() { set_color(LEDColorOrange()); } + static void set_yellow() { set_color(LEDColorYellow()); } + static void set_blue() { set_color(LEDColorBlue()); } + static void set_indigo() { set_color(LEDColorIndigo()); } + static void set_violet() { set_color(LEDColorViolet()); } #endif #if ENABLED(NEOPIXEL2_SEPARATE) static LEDColor color; // last non-off color static bool lights_on; // the last set color was "on" static void toggle(); // swap "off" with color - static inline void update() { set_color(color); } + static void update() { set_color(color); } #endif }; diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h index 814ae9c8d839d..ae75316b8ffce 100644 --- a/Marlin/src/feature/leds/neopixel.h +++ b/Marlin/src/feature/leds/neopixel.h @@ -94,12 +94,12 @@ class Marlin_NeoPixel { static void reset_background_color(); #endif - static inline void begin() { + static void begin() { adaneo1.begin(); TERN_(CONJOINED_NEOPIXEL, adaneo2.begin()); } - static inline void set_pixel_color(const uint16_t n, const uint32_t c) { + static void set_pixel_color(const uint16_t n, const uint32_t c) { #if ENABLED(NEOPIXEL2_INSERIES) if (n >= NEOPIXEL_PIXELS) adaneo2.setPixelColor(n - (NEOPIXEL_PIXELS), c); else adaneo1.setPixelColor(n, c); @@ -109,12 +109,12 @@ class Marlin_NeoPixel { #endif } - static inline void set_brightness(const uint8_t b) { + static void set_brightness(const uint8_t b) { adaneo1.setBrightness(b); TERN_(CONJOINED_NEOPIXEL, adaneo2.setBrightness(b)); } - static inline void show() { + static void show() { // Some platforms cannot maintain PWM output when NeoPixel disables interrupts for long durations. TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); adaneo1.show(); @@ -130,11 +130,11 @@ class Marlin_NeoPixel { } // Accessors - static inline uint16_t pixels() { return adaneo1.numPixels() * TERN1(NEOPIXEL2_INSERIES, 2); } + static uint16_t pixels() { return adaneo1.numPixels() * TERN1(NEOPIXEL2_INSERIES, 2); } - static inline uint8_t brightness() { return adaneo1.getBrightness(); } + static uint8_t brightness() { return adaneo1.getBrightness(); } - static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w)) { + static uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w)) { return adaneo1.Color(r, g, b OPTARG(HAS_WHITE_LED, w)); } }; @@ -165,18 +165,18 @@ extern Marlin_NeoPixel neo; static void set_color(const uint32_t c); - static inline void begin() { adaneo.begin(); } - static inline void set_pixel_color(const uint16_t n, const uint32_t c) { adaneo.setPixelColor(n, c); } - static inline void set_brightness(const uint8_t b) { adaneo.setBrightness(b); } - static inline void show() { + static void begin() { adaneo.begin(); } + static void set_pixel_color(const uint16_t n, const uint32_t c) { adaneo.setPixelColor(n, c); } + static void set_brightness(const uint8_t b) { adaneo.setBrightness(b); } + static void show() { adaneo.show(); adaneo.setPin(NEOPIXEL2_PIN); } // Accessors - static inline uint16_t pixels() { return adaneo.numPixels();} - static inline uint8_t brightness() { return adaneo.getBrightness(); } - static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED2, uint8_t w)) { + static uint16_t pixels() { return adaneo.numPixels();} + static uint8_t brightness() { return adaneo.getBrightness(); } + static uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED2, uint8_t w)) { return adaneo.Color(r, g, b OPTARG(HAS_WHITE_LED2, w)); } }; diff --git a/Marlin/src/feature/leds/printer_event_leds.h b/Marlin/src/feature/leds/printer_event_leds.h index b2201433d8211..2a4342e8f55cb 100644 --- a/Marlin/src/feature/leds/printer_event_leds.h +++ b/Marlin/src/feature/leds/printer_event_leds.h @@ -36,32 +36,32 @@ class PrinterEventLEDs { static bool leds_off_after_print; #endif - static inline void set_done() { TERN(LED_COLOR_PRESETS, leds.set_default(), leds.set_off()); } + static void set_done() { TERN(LED_COLOR_PRESETS, leds.set_default(), leds.set_off()); } public: #if HAS_TEMP_HOTEND - static inline LEDColor onHotendHeatingStart() { old_intensity = 0; return leds.get_color(); } + static LEDColor onHotendHeatingStart() { old_intensity = 0; return leds.get_color(); } static void onHotendHeating(const celsius_t start, const celsius_t current, const celsius_t target); #endif #if HAS_HEATED_BED - static inline LEDColor onBedHeatingStart() { old_intensity = 127; return leds.get_color(); } + static LEDColor onBedHeatingStart() { old_intensity = 127; return leds.get_color(); } static void onBedHeating(const celsius_t start, const celsius_t current, const celsius_t target); #endif #if HAS_HEATED_CHAMBER - static inline LEDColor onChamberHeatingStart() { old_intensity = 127; return leds.get_color(); } + static LEDColor onChamberHeatingStart() { old_intensity = 127; return leds.get_color(); } static void onChamberHeating(const celsius_t start, const celsius_t current, const celsius_t target); #endif #if HAS_TEMP_HOTEND || HAS_HEATED_BED || HAS_HEATED_CHAMBER - static inline void onHeatingDone() { leds.set_white(); } - static inline void onPidTuningDone(LEDColor c) { leds.set_color(c); } + static void onHeatingDone() { leds.set_white(); } + static void onPidTuningDone(LEDColor c) { leds.set_color(c); } #endif #if ENABLED(SDSUPPORT) - static inline void onPrintCompleted() { + static void onPrintCompleted() { leds.set_green(); #if HAS_LEDS_OFF_FLAG leds_off_after_print = true; @@ -71,7 +71,7 @@ class PrinterEventLEDs { #endif } - static inline void onResumeAfterWait() { + static void onResumeAfterWait() { #if HAS_LEDS_OFF_FLAG if (leds_off_after_print) { set_done(); diff --git a/Marlin/src/feature/max7219.h b/Marlin/src/feature/max7219.h index c25fef1730601..809bda6d4b351 100644 --- a/Marlin/src/feature/max7219.h +++ b/Marlin/src/feature/max7219.h @@ -88,13 +88,13 @@ class Max7219 { static void send(const uint8_t reg, const uint8_t data); // Refresh all units - static inline void refresh() { for (uint8_t i = 0; i < 8; i++) refresh_line(i); } + static void refresh() { for (uint8_t i = 0; i < 8; i++) refresh_line(i); } // Suspend / resume updates to the LED unit // Use these methods to speed up multiple changes // or to apply updates from interrupt context. - static inline void suspend() { suspended++; } - static inline void resume() { suspended--; suspended |= 0x80; } + static void suspend() { suspended++; } + static void resume() { suspended--; suspended |= 0x80; } // Update a single native line on all units static void refresh_line(const uint8_t line); diff --git a/Marlin/src/feature/mixing.h b/Marlin/src/feature/mixing.h index f700c7b65b7d6..85d52d69c8f31 100644 --- a/Marlin/src/feature/mixing.h +++ b/Marlin/src/feature/mixing.h @@ -126,7 +126,7 @@ class Mixer { static mixer_perc_t mix[MIXING_STEPPERS]; // Scratch array for the Mix in proportion to 100 - static inline void copy_mix_to_color(mixer_comp_t (&tcolor)[MIXING_STEPPERS]) { + static void copy_mix_to_color(mixer_comp_t (&tcolor)[MIXING_STEPPERS]) { // Scale each component to the largest one in terms of COLOR_A_MASK // So the largest component will be COLOR_A_MASK and the other will be in proportion to it const float scale = (COLOR_A_MASK) * RECIPROCAL(_MAX( @@ -145,7 +145,7 @@ class Mixer { #endif } - static inline void update_mix_from_vtool(const uint8_t j=selected_vtool) { + static void update_mix_from_vtool(const uint8_t j=selected_vtool) { float ctot = 0; MIXER_STEPPER_LOOP(i) ctot += color[j][i]; //MIXER_STEPPER_LOOP(i) mix[i] = 100.0f * color[j][i] / ctot; @@ -165,7 +165,7 @@ class Mixer { #if HAS_DUAL_MIXING // Update the virtual tool from an edited mix - static inline void update_vtool_from_mix() { + static void update_vtool_from_mix() { copy_mix_to_color(color[selected_vtool]); TERN_(GRADIENT_MIX, refresh_gradient()); // MIXER_STEPPER_LOOP(i) collector[i] = mix[i]; @@ -182,7 +182,7 @@ class Mixer { // Update the current mix from the gradient for a given Z static void update_gradient_for_z(const_float_t z); static void update_gradient_for_planner_z(); - static inline void gradient_control(const_float_t z) { + static void gradient_control(const_float_t z) { if (gradient.enabled) { if (z >= gradient.end_z) T(gradient.end_vtool); @@ -191,7 +191,7 @@ class Mixer { } } - static inline void update_mix_from_gradient() { + static void update_mix_from_gradient() { float ctot = 0; MIXER_STEPPER_LOOP(i) ctot += gradient.color[i]; MIXER_STEPPER_LOOP(i) mix[i] = (mixer_perc_t)CEIL(100.0f * gradient.color[i] / ctot); diff --git a/Marlin/src/feature/mmu/mmu2.h b/Marlin/src/feature/mmu/mmu2.h index 9574e2217f82d..7d3d9ec4df38a 100644 --- a/Marlin/src/feature/mmu/mmu2.h +++ b/Marlin/src/feature/mmu/mmu2.h @@ -43,7 +43,7 @@ class MMU2 { static void init(); static void reset(); - static inline bool enabled() { return _enabled; } + static bool enabled() { return _enabled; } static void mmu_loop(); static void tool_change(const uint8_t index); static void tool_change(const char *special); @@ -57,10 +57,10 @@ class MMU2 { static bool eject_filament(const uint8_t index, const bool recover); private: - static inline bool rx_str(FSTR_P fstr); - static inline void tx_str(FSTR_P fstr); - static inline void tx_printf(FSTR_P ffmt, const int argument); - static inline void tx_printf(FSTR_P ffmt, const int argument1, const int argument2); + static bool rx_str(FSTR_P fstr); + static void tx_str(FSTR_P fstr); + static void tx_printf(FSTR_P ffmt, const int argument); + static void tx_printf(FSTR_P ffmt, const int argument1, const int argument2); static void clear_rx_buffer(); static bool rx_ok(); @@ -99,7 +99,7 @@ class MMU2 { static millis_t prev_request, prev_P0_request; static char rx_buffer[MMU_RX_SIZE], tx_buffer[MMU_TX_SIZE]; - static inline void set_runout_valid(const bool valid) { + static void set_runout_valid(const bool valid) { finda_runout_valid = valid; #if HAS_FILAMENT_SENSOR if (valid) runout.reset(); diff --git a/Marlin/src/feature/power.h b/Marlin/src/feature/power.h index 7f5a97e6df830..42c2c8494288e 100644 --- a/Marlin/src/feature/power.h +++ b/Marlin/src/feature/power.h @@ -40,7 +40,7 @@ class Power { #if ENABLED(AUTO_POWER_CONTROL) && POWER_OFF_DELAY > 0 static void power_off_soon(); #else - static inline void power_off_soon() { power_off(); } + static void power_off_soon() { power_off(); } #endif #if ENABLED(AUTO_POWER_CONTROL) diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 76cb398af2a14..50abad92220f1 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -152,7 +152,7 @@ class PrintJobRecovery { static void init(); static void prepare(); - static inline void setup() { + static void setup() { #if PIN_EXISTS(POWER_LOSS) #if ENABLED(POWER_LOSS_PULLUP) SET_INPUT_PULLUP(POWER_LOSS_PIN); @@ -165,28 +165,28 @@ class PrintJobRecovery { } // Track each command's file offsets - static inline uint32_t command_sdpos() { return sdpos[queue_index_r]; } - static inline void commit_sdpos(const uint8_t index_w) { sdpos[index_w] = cmd_sdpos; } + static uint32_t command_sdpos() { return sdpos[queue_index_r]; } + static void commit_sdpos(const uint8_t index_w) { sdpos[index_w] = cmd_sdpos; } static bool enabled; static void enable(const bool onoff); static void changed(); - static inline bool exists() { return card.jobRecoverFileExists(); } - static inline void open(const bool read) { card.openJobRecoveryFile(read); } - static inline void close() { file.close(); } + static bool exists() { return card.jobRecoverFileExists(); } + static void open(const bool read) { card.openJobRecoveryFile(read); } + static void close() { file.close(); } static void check(); static void resume(); static void purge(); - static inline void cancel() { purge(); IF_DISABLED(NO_SD_AUTOSTART, card.autofile_begin()); } + static void cancel() { purge(); IF_DISABLED(NO_SD_AUTOSTART, card.autofile_begin()); } static void load(); static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=POWER_LOSS_ZRAISE, const bool raised=false); #if PIN_EXISTS(POWER_LOSS) - static inline void outage() { + static void outage() { static constexpr uint8_t OUTAGE_THRESHOLD = 3; static uint8_t outage_counter = 0; if (enabled && READ(POWER_LOSS_PIN) == POWER_LOSS_STATE) { @@ -199,14 +199,14 @@ class PrintJobRecovery { #endif // The referenced file exists - static inline bool interrupted_file_exists() { return card.fileExists(info.sd_filename); } + static bool interrupted_file_exists() { return card.fileExists(info.sd_filename); } - static inline bool valid() { return info.valid() && interrupted_file_exists(); } + static bool valid() { return info.valid() && interrupted_file_exists(); } #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) static void debug(FSTR_P const prefix); #else - static inline void debug(FSTR_P const) {} + static void debug(FSTR_P const) {} #endif private: diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h index 4579f2187cd41..1db7d04e89dca 100644 --- a/Marlin/src/feature/probe_temp_comp.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -74,11 +74,11 @@ class ProbeTempComp { static int16_t z_offsets_hotend[PTC_HOTEND_COUNT]; // (µm) #endif - static inline void reset_index() { calib_idx = 0; }; - static inline uint8_t get_index() { return calib_idx; } + static void reset_index() { calib_idx = 0; }; + static uint8_t get_index() { return calib_idx; } static void reset(); static void clear_offsets(const TempSensorID tsi); - static inline void clear_all_offsets() { + static void clear_all_offsets() { TERN_(PTC_PROBE, clear_offsets(TSI_PROBE)); TERN_(PTC_BED, clear_offsets(TSI_BED)); TERN_(PTC_HOTEND, clear_offsets(TSI_EXT)); diff --git a/Marlin/src/feature/repeat.h b/Marlin/src/feature/repeat.h index 0f4d9425b7682..fc11e4a9e2cff 100644 --- a/Marlin/src/feature/repeat.h +++ b/Marlin/src/feature/repeat.h @@ -38,8 +38,8 @@ class Repeat { static repeat_marker_t marker[MAX_REPEAT_NESTING]; static uint8_t index; public: - static inline void reset() { index = 0; } - static inline bool is_active() { + static void reset() { index = 0; } + static bool is_active() { LOOP_L_N(i, index) if (marker[i].counter) return true; return false; } diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index 8065e515559f6..e74d857a79eda 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -83,30 +83,30 @@ class TFilamentMonitor : public FilamentMonitorBase { static sensor_t sensor; public: - static inline void setup() { + static void setup() { sensor.setup(); reset(); } - static inline void reset() { + static void reset() { filament_ran_out = false; response.reset(); } // Call this method when filament is present, // so the response can reset its counter. - static inline void filament_present(const uint8_t extruder) { + static void filament_present(const uint8_t extruder) { response.filament_present(extruder); } #if HAS_FILAMENT_RUNOUT_DISTANCE - static inline float& runout_distance() { return response.runout_distance_mm; } - static inline void set_runout_distance(const_float_t mm) { response.runout_distance_mm = mm; } + static float& runout_distance() { return response.runout_distance_mm; } + static void set_runout_distance(const_float_t mm) { response.runout_distance_mm = mm; } #endif // Handle a block completion. RunoutResponseDelayed uses this to // add up the length of filament moved while the filament is out. - static inline void block_completed(const block_t * const b) { + static void block_completed(const block_t * const b) { if (enabled) { response.block_completed(b); sensor.block_completed(b); @@ -114,7 +114,7 @@ class TFilamentMonitor : public FilamentMonitorBase { } // Give the response a chance to update its counter. - static inline void run() { + static void run() { if (enabled && !filament_ran_out && (printingIsActive() || did_pause_print)) { TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, cli()); // Prevent RunoutResponseDelayed::block_completed from accumulating here response.run(); @@ -168,12 +168,12 @@ class FilamentSensorBase { * Called by FilamentSensorSwitch::run when filament is detected. * Called by FilamentSensorEncoder::block_completed when motion is detected. */ - static inline void filament_present(const uint8_t extruder) { + static void filament_present(const uint8_t extruder) { runout.filament_present(extruder); // ...which calls response.filament_present(extruder) } public: - static inline void setup() { + static void setup() { #define _INIT_RUNOUT_PIN(P,S,U,D) do{ if (ENABLED(U)) SET_INPUT_PULLUP(P); else if (ENABLED(D)) SET_INPUT_PULLDOWN(P); else SET_INPUT(P); }while(0) #define INIT_RUNOUT_PIN(N) _INIT_RUNOUT_PIN(FIL_RUNOUT##N##_PIN, FIL_RUNOUT##N##_STATE, FIL_RUNOUT##N##_PULLUP, FIL_RUNOUT##N##_PULLDOWN) #if NUM_RUNOUT_SENSORS >= 1 @@ -205,14 +205,14 @@ class FilamentSensorBase { } // Return a bitmask of runout pin states - static inline uint8_t poll_runout_pins() { + static uint8_t poll_runout_pins() { #define _OR_RUNOUT(N) | (READ(FIL_RUNOUT##N##_PIN) ? _BV((N) - 1) : 0) return (0 REPEAT_1(NUM_RUNOUT_SENSORS, _OR_RUNOUT)); #undef _OR_RUNOUT } // Return a bitmask of runout flag states (1 bits always indicates runout) - static inline uint8_t poll_runout_states() { + static uint8_t poll_runout_states() { return poll_runout_pins() ^ uint8_t(0 #if NUM_RUNOUT_SENSORS >= 1 | (FIL_RUNOUT1_STATE ? 0 : _BV(1 - 1)) @@ -254,7 +254,7 @@ class FilamentSensorBase { private: static uint8_t motion_detected; - static inline void poll_motion_sensor() { + static void poll_motion_sensor() { static uint8_t old_state; const uint8_t new_state = poll_runout_pins(), change = old_state ^ new_state; @@ -273,7 +273,7 @@ class FilamentSensorBase { } public: - static inline void block_completed(const block_t * const b) { + static void block_completed(const block_t * const b) { // If the sensor wheel has moved since the last call to // this method reset the runout counter for the extruder. if (TEST(motion_detected, b->extruder)) @@ -283,7 +283,7 @@ class FilamentSensorBase { motion_detected = 0; } - static inline void run() { poll_motion_sensor(); } + static void run() { poll_motion_sensor(); } }; #else @@ -294,7 +294,7 @@ class FilamentSensorBase { */ class FilamentSensorSwitch : public FilamentSensorBase { private: - static inline bool poll_runout_state(const uint8_t extruder) { + static bool poll_runout_state(const uint8_t extruder) { const uint8_t runout_states = poll_runout_states(); #if MULTI_FILAMENT_SENSOR if ( !TERN0(DUAL_X_CARRIAGE, idex_is_duplicating()) @@ -307,9 +307,9 @@ class FilamentSensorBase { } public: - static inline void block_completed(const block_t * const) {} + static void block_completed(const block_t * const) {} - static inline void run() { + static void run() { LOOP_L_N(s, NUM_RUNOUT_SENSORS) { const bool out = poll_runout_state(s); if (!out) filament_present(s); @@ -341,11 +341,11 @@ class FilamentSensorBase { public: static float runout_distance_mm; - static inline void reset() { + static void reset() { LOOP_L_N(i, NUM_RUNOUT_SENSORS) filament_present(i); } - static inline void run() { + static void run() { #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) static millis_t t = 0; const millis_t ms = millis(); @@ -358,17 +358,17 @@ class FilamentSensorBase { #endif } - static inline uint8_t has_run_out() { + static uint8_t has_run_out() { uint8_t runout_flags = 0; LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (runout_mm_countdown[i] < 0) SBI(runout_flags, i); return runout_flags; } - static inline void filament_present(const uint8_t extruder) { + static void filament_present(const uint8_t extruder) { runout_mm_countdown[extruder] = runout_distance_mm; } - static inline void block_completed(const block_t * const b) { + static void block_completed(const block_t * const b) { if (b->steps.x || b->steps.y || b->steps.z || did_pause_print) { // Allow pause purge move to re-trigger runout state // Only trigger on extrusion with XYZ movement to allow filament change and retract/recover. const uint8_t e = b->extruder; @@ -389,23 +389,23 @@ class FilamentSensorBase { static int8_t runout_count[NUM_RUNOUT_SENSORS]; public: - static inline void reset() { + static void reset() { LOOP_L_N(i, NUM_RUNOUT_SENSORS) filament_present(i); } - static inline void run() { + static void run() { LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (runout_count[i] >= 0) runout_count[i]--; } - static inline uint8_t has_run_out() { + 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); return runout_flags; } - static inline void block_completed(const block_t * const) { } + static void block_completed(const block_t * const) { } - static inline void filament_present(const uint8_t extruder) { + static void filament_present(const uint8_t extruder) { runout_count[extruder] = runout_threshold; } }; diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 95d60ae486748..7a8cd2c830043 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -103,12 +103,12 @@ class SpindleLaser { static void init(); #if ENABLED(MARLIN_DEV_MODE) - static inline void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } + static void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } #endif // Modifying this function should update everywhere - static inline bool enabled(const cutter_power_t opwr) { return opwr > 0; } - static inline bool enabled() { return enabled(power); } + static bool enabled(const cutter_power_t opwr) { return opwr > 0; } + static bool enabled() { return enabled(power); } static void apply_power(const uint8_t inpow); @@ -124,13 +124,13 @@ class SpindleLaser { public: static void set_ocr(const uint8_t ocr); - static inline void ocr_set_power(const uint8_t ocr) { power = ocr; set_ocr(ocr); } + static void ocr_set_power(const uint8_t ocr) { power = ocr; set_ocr(ocr); } static void ocr_off(); /** * Update output for power->OCR translation */ - static inline uint8_t upower_to_ocr(const cutter_power_t upwr) { + static uint8_t upower_to_ocr(const cutter_power_t upwr) { return uint8_t( #if CUTTER_UNIT_IS(PWM255) upwr @@ -145,11 +145,11 @@ class SpindleLaser { /** * Correct power to configured range */ - static inline cutter_power_t power_to_range(const cutter_power_t pwr) { + static cutter_power_t power_to_range(const cutter_power_t pwr) { return power_to_range(pwr, _CUTTER_POWER(CUTTER_POWER_UNIT)); } - static inline cutter_power_t power_to_range(const cutter_power_t pwr, const uint8_t pwrUnit) { + static cutter_power_t power_to_range(const cutter_power_t pwr, const uint8_t pwrUnit) { static constexpr float min_pct = TERN(CUTTER_POWER_RELATIVE, 0, TERN(SPINDLE_FEATURE, round(100.0f * (SPEED_POWER_MIN) / (SPEED_POWER_MAX)), SPEED_POWER_MIN)), max_pct = TERN(SPINDLE_FEATURE, 100, SPEED_POWER_MAX); @@ -188,7 +188,7 @@ class SpindleLaser { * Enable/Disable spindle/laser * @param enable true = enable; false = disable */ - static inline void set_enabled(const bool enable) { + static void set_enabled(const bool enable) { uint8_t value = 0; if (enable) { #if ENABLED(SPINDLE_LASER_USE_PWM) @@ -203,14 +203,14 @@ class SpindleLaser { set_power(value); } - static inline void disable() { isReady = false; set_enabled(false); } + static void disable() { isReady = false; set_enabled(false); } /** * Wait for spindle to spin up or spin down * * @param on true = state to on; false = state to off. */ - static inline void power_delay(const bool on) { + static void power_delay(const bool on) { #if DISABLED(LASER_POWER_INLINE) safe_delay(on ? SPINDLE_LASER_POWERUP_DELAY : SPINDLE_LASER_POWERDOWN_DELAY); #endif @@ -220,7 +220,7 @@ class SpindleLaser { static void set_reverse(const bool reverse); static bool is_reverse() { return READ(SPINDLE_DIR_PIN) == SPINDLE_INVERT_DIR; } #else - static inline void set_reverse(const bool) {} + static void set_reverse(const bool) {} static bool is_reverse() { return false; } #endif @@ -228,7 +228,7 @@ class SpindleLaser { static void air_evac_enable(); // Turn On Cutter Vacuum or Laser Blower motor static void air_evac_disable(); // Turn Off Cutter Vacuum or Laser Blower motor static void air_evac_toggle(); // Toggle Cutter Vacuum or Laser Blower motor - static inline bool air_evac_state() { // Get current state + static bool air_evac_state() { // Get current state return (READ(AIR_EVACUATION_PIN) == AIR_EVACUATION_ACTIVE); } #endif @@ -237,13 +237,13 @@ class SpindleLaser { static void air_assist_enable(); // Turn on air assist static void air_assist_disable(); // Turn off air assist static void air_assist_toggle(); // Toggle air assist - static inline bool air_assist_state() { // Get current state + static bool air_assist_state() { // Get current state return (READ(AIR_ASSIST_PIN) == AIR_ASSIST_ACTIVE); } #endif #if HAS_LCD_MENU - static inline void enable_with_dir(const bool reverse) { + static void enable_with_dir(const bool reverse) { isReady = true; const uint8_t ocr = TERN(SPINDLE_LASER_USE_PWM, upower_to_ocr(menuPower), 255); if (menuPower) @@ -259,7 +259,7 @@ class SpindleLaser { FORCE_INLINE static void enable_same_dir() { enable_with_dir(is_reverse()); } #if ENABLED(SPINDLE_LASER_USE_PWM) - static inline void update_from_mpower() { + static void update_from_mpower() { if (isReady) power = upower_to_ocr(menuPower); unitPower = menuPower; } @@ -271,7 +271,7 @@ class SpindleLaser { * Also fires with any PWM power that was previous set * If not set defaults to 80% power */ - static inline void test_fire_pulse() { + static void test_fire_pulse() { TERN_(USE_BEEPER, buzzer.tone(30, 3000)); enable_forward(); // Turn Laser on (Spindle speak but same funct) delay(testPulse); // Delay for time set by user in pulse ms menu screen. @@ -288,7 +288,7 @@ class SpindleLaser { */ // Force disengage planner power control - static inline void inline_disable() { + static void inline_disable() { isReady = false; unitPower = 0; planner.laser_inline.status.isPlanned = false; @@ -297,7 +297,7 @@ class SpindleLaser { } // Inline modes of all other functions; all enable planner inline power control - static inline void set_inline_enabled(const bool enable) { + static void set_inline_enabled(const bool enable) { if (enable) inline_power(255); else { @@ -326,10 +326,10 @@ class SpindleLaser { #endif } - static inline void inline_direction(const bool) { /* never */ } + static void inline_direction(const bool) { /* never */ } #if ENABLED(SPINDLE_LASER_USE_PWM) - static inline void inline_ocr_power(const uint8_t ocrpwr) { + static void inline_ocr_power(const uint8_t ocrpwr) { isReady = ocrpwr > 0; planner.laser_inline.status.isEnabled = ocrpwr > 0; planner.laser_inline.power = ocrpwr; @@ -337,7 +337,7 @@ class SpindleLaser { #endif #endif // LASER_POWER_INLINE - static inline void kill() { + static void kill() { TERN_(LASER_POWER_INLINE, inline_disable()); disable(); } diff --git a/Marlin/src/feature/twibus.h b/Marlin/src/feature/twibus.h index d2c7270303c72..806e2a147a7d3 100644 --- a/Marlin/src/feature/twibus.h +++ b/Marlin/src/feature/twibus.h @@ -244,11 +244,11 @@ class TWIBus { static void debug(FSTR_P const func, char c); static void debug(FSTR_P const func, char adr[]); #else - static inline void debug(FSTR_P const, uint32_t) {} - static inline void debug(FSTR_P const, char) {} - static inline void debug(FSTR_P const, char[]) {} + static void debug(FSTR_P const, uint32_t) {} + static void debug(FSTR_P const, char) {} + static void debug(FSTR_P const, char[]) {} #endif - static inline void debug(FSTR_P const func, uint8_t v) { debug(func, (uint32_t)v); } + static void debug(FSTR_P const func, uint8_t v) { debug(func, (uint32_t)v); } }; extern TWIBus i2c; diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 262237d14c9a8..92c1459a326c9 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -349,7 +349,7 @@ class GcodeSuite { static axis_bits_t axis_relative; - static inline bool axis_is_relative(const AxisEnum a) { + static bool axis_is_relative(const AxisEnum a) { #if HAS_EXTRUDERS if (a == E_AXIS) { if (TEST(axis_relative, E_MODE_REL)) return true; @@ -358,7 +358,7 @@ class GcodeSuite { #endif return TEST(axis_relative, a); } - static inline void set_relative_mode(const bool rel) { + static void set_relative_mode(const bool rel) { axis_relative = rel ? (0 LOGICAL_AXIS_GANG( | _BV(REL_E), | _BV(REL_X), | _BV(REL_Y), | _BV(REL_Z), @@ -366,11 +366,11 @@ class GcodeSuite { )) : 0; } #if HAS_EXTRUDERS - static inline void set_e_relative() { + static void set_e_relative() { CBI(axis_relative, E_MODE_ABS); SBI(axis_relative, E_MODE_REL); } - static inline void set_e_absolute() { + static void set_e_absolute() { CBI(axis_relative, E_MODE_REL); SBI(axis_relative, E_MODE_ABS); } @@ -403,7 +403,7 @@ class GcodeSuite { static void report_echo_start(const bool forReplay); static void report_heading(const bool forReplay, FSTR_P const fstr, const bool eol=true); - static inline void report_heading_etc(const bool forReplay, FSTR_P const fstr, const bool eol=true) { + static void report_heading_etc(const bool forReplay, FSTR_P const fstr, const bool eol=true) { report_heading(forReplay, fstr, eol); report_echo_start(forReplay); } @@ -420,20 +420,20 @@ class GcodeSuite { static void process_subcommands_now(FSTR_P fgcode); static void process_subcommands_now(char * gcode); - static inline void home_all_axes(const bool keep_leveling=false) { + static void home_all_axes(const bool keep_leveling=false) { 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) static bool autoreport_paused; - static inline bool set_autoreport_paused(const bool p) { + static bool set_autoreport_paused(const bool p) { const bool was = autoreport_paused; autoreport_paused = p; return was; } #else static constexpr bool autoreport_paused = false; - static inline bool set_autoreport_paused(const bool) { return false; } + static bool set_autoreport_paused(const bool) { return false; } #endif #if ENABLED(HOST_KEEPALIVE_FEATURE) @@ -453,7 +453,7 @@ class GcodeSuite { static uint8_t host_keepalive_interval; static void host_keepalive(); - static inline bool host_keepalive_is_paused() { return busy_state >= PAUSED_FOR_USER; } + static bool host_keepalive_is_paused() { return busy_state >= PAUSED_FOR_USER; } #define KEEPALIVE_STATE(N) REMEMBER(_KA_, gcode.busy_state, gcode.N) #else diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index 83fda5483608d..bd08467298837 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -126,7 +126,7 @@ class GCodeParser { } // Set the flag and pointer for a parameter - static inline void set(const char c, char * const ptr) { + static void set(const char c, char * const ptr) { const uint8_t ind = LETTER_BIT(c); if (ind >= COUNT(param)) return; // Only A-Z SBI32(codebits, ind); // parameter exists @@ -142,7 +142,7 @@ class GCodeParser { // Code seen bit was set. If not found, value_ptr is unchanged. // This allows "if (seen('A')||seen('B'))" to use the last-found value. - static inline bool seen(const char c) { + static bool seen(const char c) { const uint8_t ind = LETTER_BIT(c); if (ind >= COUNT(param)) return false; // Only A-Z const bool b = TEST32(codebits, ind); @@ -183,7 +183,7 @@ class GCodeParser { } #endif - static inline bool seen_any() { return !!codebits; } + static bool seen_any() { return !!codebits; } FORCE_INLINE static bool seen_test(const char c) { return TEST32(codebits, LETTER_BIT(c)); } @@ -204,19 +204,19 @@ class GCodeParser { // Code is found in the string. If not found, value_ptr is unchanged. // This allows "if (seen('A')||seen('B'))" to use the last-found value. - static inline bool seen(const char c) { + static bool seen(const char c) { char *p = strgchr(command_args, c); const bool b = !!p; if (b) value_ptr = valid_number(&p[1]) ? &p[1] : nullptr; return b; } - static inline bool seen_any() { return *command_args == '\0'; } + static bool seen_any() { return *command_args == '\0'; } FORCE_INLINE static bool seen_test(const char c) { return (bool)strgchr(command_args, c); } // At least one of a list of code letters was seen - static inline bool seen(const char * const str) { + static bool seen(const char * const str) { for (uint8_t i = 0; const char c = str[i]; i++) if (seen_test(c)) return true; return false; @@ -225,7 +225,7 @@ class GCodeParser { #endif // !FASTER_GCODE_PARSER // Seen any axis parameter - static inline bool seen_axis() { return seen(LOGICAL_AXES_STRING); } + static bool seen_axis() { return seen(LOGICAL_AXES_STRING); } #if ENABLED(GCODE_QUOTED_STRINGS) static char* unescape_string(char* &src); @@ -243,19 +243,19 @@ class GCodeParser { #endif // Test whether the parsed command matches the input - static inline bool is_command(const char ltr, const uint16_t num) { return command_letter == ltr && codenum == num; } + static bool is_command(const char ltr, const uint16_t num) { return command_letter == ltr && codenum == num; } // The code value pointer was set FORCE_INLINE static bool has_value() { return !!value_ptr; } // Seen a parameter with a value - static inline bool seenval(const char c) { return seen(c) && has_value(); } + static bool seenval(const char c) { return seen(c) && has_value(); } // The value as a string - static inline char* value_string() { return value_ptr; } + static char* value_string() { return value_ptr; } // Float removes 'E' to prevent scientific notation interpretation - static inline float value_float() { + static float value_float() { if (value_ptr) { char *e = value_ptr; for (;;) { @@ -275,31 +275,31 @@ class GCodeParser { } // Code value as a long or ulong - static inline int32_t value_long() { return value_ptr ? strtol(value_ptr, nullptr, 10) : 0L; } - static inline uint32_t value_ulong() { return value_ptr ? strtoul(value_ptr, nullptr, 10) : 0UL; } + static int32_t value_long() { return value_ptr ? strtol(value_ptr, nullptr, 10) : 0L; } + static uint32_t value_ulong() { return value_ptr ? strtoul(value_ptr, nullptr, 10) : 0UL; } // Code value for use as time - static inline millis_t value_millis() { return value_ulong(); } - static inline millis_t value_millis_from_seconds() { return (millis_t)SEC_TO_MS(value_float()); } + static millis_t value_millis() { return value_ulong(); } + static millis_t value_millis_from_seconds() { return (millis_t)SEC_TO_MS(value_float()); } // Reduce to fewer bits - static inline int16_t value_int() { return (int16_t)value_long(); } - static inline uint16_t value_ushort() { return (uint16_t)value_long(); } - static inline uint8_t value_byte() { return (uint8_t)constrain(value_long(), 0, 255); } + static int16_t value_int() { return (int16_t)value_long(); } + static uint16_t value_ushort() { return (uint16_t)value_long(); } + static uint8_t value_byte() { return (uint8_t)constrain(value_long(), 0, 255); } // Bool is true with no value or non-zero - static inline bool value_bool() { return !has_value() || !!value_byte(); } + static bool value_bool() { return !has_value() || !!value_byte(); } // Units modes: Inches, Fahrenheit, Kelvin #if ENABLED(INCH_MODE_SUPPORT) - static inline float mm_to_linear_unit(const_float_t mm) { return mm / linear_unit_factor; } - static inline float mm_to_volumetric_unit(const_float_t mm) { return mm / (volumetric_enabled ? volumetric_unit_factor : linear_unit_factor); } + static float mm_to_linear_unit(const_float_t mm) { return mm / linear_unit_factor; } + static float mm_to_volumetric_unit(const_float_t mm) { return mm / (volumetric_enabled ? volumetric_unit_factor : linear_unit_factor); } // Init linear units by constructor GCodeParser() { set_input_linear_units(LINEARUNIT_MM); } - static inline void set_input_linear_units(const LinearUnit units) { + static void set_input_linear_units(const LinearUnit units) { switch (units) { default: case LINEARUNIT_MM: linear_unit_factor = 1.0f; break; @@ -308,7 +308,7 @@ class GCodeParser { volumetric_unit_factor = POW(linear_unit_factor, 3); } - static inline float axis_unit_factor(const AxisEnum axis) { + static float axis_unit_factor(const AxisEnum axis) { return ( #if HAS_EXTRUDERS axis >= E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor @@ -318,46 +318,46 @@ class GCodeParser { ); } - static inline float linear_value_to_mm(const_float_t v) { return v * linear_unit_factor; } - static inline float axis_value_to_mm(const AxisEnum axis, const float v) { return v * axis_unit_factor(axis); } - static inline float per_axis_value(const AxisEnum axis, const float v) { return v / axis_unit_factor(axis); } + static float linear_value_to_mm(const_float_t v) { return v * linear_unit_factor; } + static float axis_value_to_mm(const AxisEnum axis, const float v) { return v * axis_unit_factor(axis); } + static float per_axis_value(const AxisEnum axis, const float v) { return v / axis_unit_factor(axis); } #else - static inline float mm_to_linear_unit(const_float_t mm) { return mm; } - static inline float mm_to_volumetric_unit(const_float_t mm) { return mm; } + static float mm_to_linear_unit(const_float_t mm) { return mm; } + static float mm_to_volumetric_unit(const_float_t mm) { return mm; } - static inline float linear_value_to_mm(const_float_t v) { return v; } - static inline float axis_value_to_mm(const AxisEnum, const float v) { return v; } - static inline float per_axis_value(const AxisEnum, const float v) { return v; } + static float linear_value_to_mm(const_float_t v) { return v; } + static float axis_value_to_mm(const AxisEnum, const float v) { return v; } + static float per_axis_value(const AxisEnum, const float v) { return v; } #endif - static inline bool using_inch_units() { return mm_to_linear_unit(1.0f) != 1.0f; } + static bool using_inch_units() { return mm_to_linear_unit(1.0f) != 1.0f; } #define IN_TO_MM(I) ((I) * 25.4f) #define MM_TO_IN(M) ((M) / 25.4f) #define LINEAR_UNIT(V) parser.mm_to_linear_unit(V) #define VOLUMETRIC_UNIT(V) parser.mm_to_volumetric_unit(V) - static inline float value_linear_units() { return linear_value_to_mm(value_float()); } - static inline float value_axis_units(const AxisEnum axis) { return axis_value_to_mm(axis, value_float()); } - static inline float value_per_axis_units(const AxisEnum axis) { return per_axis_value(axis, value_float()); } + static float value_linear_units() { return linear_value_to_mm(value_float()); } + static float value_axis_units(const AxisEnum axis) { return axis_value_to_mm(axis, value_float()); } + static float value_per_axis_units(const AxisEnum axis) { return per_axis_value(axis, value_float()); } #if ENABLED(TEMPERATURE_UNITS_SUPPORT) - static inline void set_input_temp_units(const TempUnit units) { input_temp_units = units; } + static void set_input_temp_units(const TempUnit units) { input_temp_units = units; } - static inline char temp_units_code() { + static char temp_units_code() { return input_temp_units == TEMPUNIT_K ? 'K' : input_temp_units == TEMPUNIT_F ? 'F' : 'C'; } - static inline FSTR_P temp_units_name() { + static FSTR_P temp_units_name() { return input_temp_units == TEMPUNIT_K ? F("Kelvin") : input_temp_units == TEMPUNIT_F ? F("Fahrenheit") : F("Celsius"); } #if HAS_LCD_MENU && DISABLED(DISABLE_M503) - static inline float to_temp_units(celsius_t c) { + static float to_temp_units(celsius_t c) { switch (input_temp_units) { default: case TEMPUNIT_C: return c; @@ -368,7 +368,7 @@ class GCodeParser { #endif // HAS_LCD_MENU && !DISABLE_M503 - static inline celsius_t value_celsius() { + static celsius_t value_celsius() { float f = value_float(); switch (input_temp_units) { default: @@ -379,7 +379,7 @@ class GCodeParser { return LROUND(f); } - static inline celsius_t value_celsius_diff() { + static celsius_t value_celsius_diff() { float f = value_float(); switch (input_temp_units) { default: @@ -392,35 +392,35 @@ class GCodeParser { #else // !TEMPERATURE_UNITS_SUPPORT - static inline float to_temp_units(int16_t c) { return (float)c; } + static float to_temp_units(int16_t c) { return (float)c; } - static inline celsius_t value_celsius() { return value_int(); } - static inline celsius_t value_celsius_diff() { return value_int(); } + static celsius_t value_celsius() { return value_int(); } + static celsius_t value_celsius_diff() { return value_int(); } #endif // !TEMPERATURE_UNITS_SUPPORT - static inline feedRate_t value_feedrate() { return MMM_TO_MMS(value_linear_units()); } + static feedRate_t value_feedrate() { return MMM_TO_MMS(value_linear_units()); } void unknown_command_warning(); // Provide simple value accessors with default option - static inline char* stringval(const char c, char * const dval=nullptr) { return seenval(c) ? value_string() : dval; } - static inline float floatval(const char c, const float dval=0.0) { return seenval(c) ? value_float() : dval; } - static inline bool boolval(const char c, const bool dval=false) { return seenval(c) ? value_bool() : (seen(c) ? true : dval); } - static inline uint8_t byteval(const char c, const uint8_t dval=0) { return seenval(c) ? value_byte() : dval; } - static inline int16_t intval(const char c, const int16_t dval=0) { return seenval(c) ? value_int() : dval; } - static inline uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort() : dval; } - static inline int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; } - static inline uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; } - static inline float linearval(const char c, const float dval=0) { return seenval(c) ? value_linear_units() : dval; } - static inline float axisunitsval(const char c, const AxisEnum a, const float dval=0) + static char* stringval(const char c, char * const dval=nullptr) { return seenval(c) ? value_string() : dval; } + static float floatval(const char c, const float dval=0.0) { return seenval(c) ? value_float() : dval; } + static bool boolval(const char c, const bool dval=false) { return seenval(c) ? value_bool() : (seen(c) ? true : dval); } + static uint8_t byteval(const char c, const uint8_t dval=0) { return seenval(c) ? value_byte() : dval; } + static int16_t intval(const char c, const int16_t dval=0) { return seenval(c) ? value_int() : dval; } + static uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort() : dval; } + static int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; } + static uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; } + static float linearval(const char c, const float dval=0) { return seenval(c) ? value_linear_units() : dval; } + static float axisunitsval(const char c, const AxisEnum a, const float dval=0) { return seenval(c) ? value_axis_units(a) : dval; } - static inline celsius_t celsiusval(const char c, const celsius_t dval=0) { return seenval(c) ? value_celsius() : dval; } - static inline feedRate_t feedrateval(const char c, const feedRate_t dval=0) { return seenval(c) ? value_feedrate() : dval; } + static celsius_t celsiusval(const char c, const celsius_t dval=0) { return seenval(c) ? value_celsius() : dval; } + static feedRate_t feedrateval(const char c, const feedRate_t dval=0) { return seenval(c) ? value_feedrate() : dval; } #if ENABLED(MARLIN_DEV_MODE) - static inline uint8_t* hex_adr_val(const char c, uint8_t * const dval=nullptr) { + static uint8_t* hex_adr_val(const char c, uint8_t * const dval=nullptr) { if (!seen(c) || *value_ptr != 'x') return dval; uint8_t *out = nullptr; for (char *vp = value_ptr + 1; HEXCHR(*vp) >= 0; vp++) @@ -428,7 +428,7 @@ class GCodeParser { return out; } - static inline uint16_t hex_val(const char c, uint16_t const dval=0) { + static uint16_t hex_val(const char c, uint16_t const dval=0) { if (!seen(c) || *value_ptr != 'x') return dval; uint16_t out = 0; for (char *vp = value_ptr + 1; HEXCHR(*vp) >= 0; vp++) diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 82e2a7a0e4da2..1a2baaa6bbc40 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -126,14 +126,14 @@ class GCodeQueue { * Don't inject comments or use leading spaces! * Aborts the current PROGMEM queue so only use for one or two commands. */ - static inline void inject_P(PGM_P const pgcode) { injected_commands_P = pgcode; } - static inline void inject(FSTR_P const fgcode) { inject_P(FTOP(fgcode)); } + static void inject_P(PGM_P const pgcode) { injected_commands_P = pgcode; } + static void inject(FSTR_P const fgcode) { inject_P(FTOP(fgcode)); } /** * Enqueue command(s) to run from SRAM. Drained by process_injected_command(). * Aborts the current SRAM queue so only use for one or two commands. */ - static inline void inject(const char * const gcode) { + static void inject(const char * const gcode) { strncpy(injected_commands, gcode, sizeof(injected_commands) - 1); } @@ -158,7 +158,7 @@ class GCodeQueue { * Enqueue from program memory and return only when commands are actually enqueued */ static void enqueue_now_P(PGM_P const pcmd); - static inline void enqueue_now(FSTR_P const fcmd) { enqueue_now_P(FTOP(fcmd)); } + static void enqueue_now(FSTR_P const fcmd) { enqueue_now_P(FTOP(fcmd)); } /** * Check whether there are any commands yet to be executed @@ -192,7 +192,7 @@ class GCodeQueue { * P Planner space remaining * B Block queue space remaining */ - static inline void ok_to_send() { ring_buffer.ok_to_send(); } + static void ok_to_send() { ring_buffer.ok_to_send(); } /** * Clear the serial line and request a resend of @@ -203,7 +203,7 @@ class GCodeQueue { /** * (Re)Set the current line number for the last received command */ - static inline void set_current_line_number(long n) { serial_state[ring_buffer.command_port().index].last_N = n; } + static void set_current_line_number(long n) { serial_state[ring_buffer.command_port().index].last_N = n; } #if ENABLED(BUFFER_MONITORING) @@ -237,7 +237,7 @@ class GCodeQueue { static void auto_report_buffer_statistics(); - static inline void set_auto_report_interval(uint8_t v) { + static void set_auto_report_interval(uint8_t v) { NOMORE(v, 60); auto_buffer_report_interval = v; next_buffer_report_ms = millis() + 1000UL * v; diff --git a/Marlin/src/lcd/e3v2/enhanced/lockscreen.h b/Marlin/src/lcd/e3v2/enhanced/lockscreen.h index f44ca418f1b62..a51c82f34e5ca 100644 --- a/Marlin/src/lcd/e3v2/enhanced/lockscreen.h +++ b/Marlin/src/lcd/e3v2/enhanced/lockscreen.h @@ -40,7 +40,7 @@ class LockScreenClass { static void init(); static void onEncoder(EncoderState encoder_diffState); static void draw(); - static inline bool isUnlocked() { return unlocked; } + static bool isUnlocked() { return unlocked; } }; extern LockScreenClass lockScreen; diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h index 30af387bdcbab..64676dddfdaf6 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h @@ -55,7 +55,7 @@ class DWIN_String { //static font_t *font() { return font_header; }; //static uint16_t font_height() { return font_header->FontAscent - font_header->FontDescent; } //static glyph_t *glyph(uint8_t character) { return glyphs[character] ?: glyphs[0x3F]; } /* Use '?' for unknown glyphs */ - //static inline glyph_t *glyph(uint8_t *character) { return glyph(*character); } + //static glyph_t *glyph(uint8_t *character) { return glyph(*character); } static void set(); //static void add(uint8_t character) { add_character(character); eol(); } @@ -65,10 +65,10 @@ class DWIN_String { static void set(uint8_t *string) { set(); add(string); } static void set(wchar_t character) { set(); add(character); } static void set(uint8_t *string, int8_t index, const char *itemString=nullptr) { set(); add(string, index, (uint8_t *)itemString); } - static inline void set(FSTR_P fstring) { set((uint8_t *)fstring); } - static inline void set(const char *string) { set((uint8_t *)string); } - static inline void set(const char *string, int8_t index, const char *itemString=nullptr) { set((uint8_t *)string, index, itemString); } - static inline void add(const char *string) { add((uint8_t *)string); } + static void set(FSTR_P fstring) { set((uint8_t *)fstring); } + static void set(const char *string) { set((uint8_t *)string); } + static void set(const char *string, int8_t index, const char *itemString=nullptr) { set((uint8_t *)string, index, itemString); } + static void add(const char *string) { add((uint8_t *)string); } static void trim(const uint8_t character=0x20); static void rtrim(const uint8_t character=0x20); @@ -76,9 +76,9 @@ class DWIN_String { static void truncate(uint8_t maxlen) { if (len > maxlen) { len = maxlen; eol(); } } - static inline uint8_t length() { return len; } - static inline uint16_t width() { return span; } - static inline uint8_t *string() { return data; } + static uint8_t length() { return len; } + static uint16_t width() { return span; } + static uint8_t *string() { return data; } static uint16_t center(uint16_t width) { return span > width ? 0 : (width - span) / 2; } }; diff --git a/Marlin/src/lcd/extui/dgus/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h index e486a00145700..3040225d071aa 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h @@ -95,14 +95,14 @@ class DGUSDisplay { // 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 inline 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 inline uint16_t swap16(const uint16_t value) { return (value & 0xFFU) << 8U | (value >> 8U); } + static uint16_t swap16(const uint16_t value) { return (value & 0xFFU) << 8U | (value >> 8U); } static rx_datagram_state_t rx_datagram_state; static uint8_t rx_datagram_len; static bool Initialized, no_reentrance; diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h index bb0bd2bd3b423..d4fdf1d27e2ad 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h @@ -38,10 +38,10 @@ class DGUSScreenHandler { // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); - static inline void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); } - static inline 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) { + 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); } @@ -213,13 +213,13 @@ class DGUSScreenHandler { } // Force an update of all VP on the current screen. - static inline void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } + static void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } // Has all VPs sent to the screen - static inline bool IsScreenComplete() { return ScreenComplete; } + static bool IsScreenComplete() { return ScreenComplete; } - static inline DGUSLCD_Screens getCurrentScreen() { return current_screen; } + static DGUSLCD_Screens getCurrentScreen() { return current_screen; } - static inline void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } + static void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } private: static DGUSLCD_Screens current_screen; //< currently on screen diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h index bb0bd2bd3b423..d4fdf1d27e2ad 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h @@ -38,10 +38,10 @@ class DGUSScreenHandler { // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); - static inline void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); } - static inline 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) { + 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); } @@ -213,13 +213,13 @@ class DGUSScreenHandler { } // Force an update of all VP on the current screen. - static inline void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } + static void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } // Has all VPs sent to the screen - static inline bool IsScreenComplete() { return ScreenComplete; } + static bool IsScreenComplete() { return ScreenComplete; } - static inline DGUSLCD_Screens getCurrentScreen() { return current_screen; } + static DGUSLCD_Screens getCurrentScreen() { return current_screen; } - static inline void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } + static void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } private: static DGUSLCD_Screens current_screen; //< currently on screen diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index 0c80cd260ef99..2e6c8af9852bc 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -38,10 +38,10 @@ class DGUSScreenHandler { // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); - static inline void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); } - static inline 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) { + 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); } @@ -280,13 +280,13 @@ class DGUSScreenHandler { } // Force an update of all VP on the current screen. - static inline void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } + static void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } // Has all VPs sent to the screen - static inline bool IsScreenComplete() { return ScreenComplete; } + static bool IsScreenComplete() { return ScreenComplete; } - static inline DGUSLCD_Screens getCurrentScreen() { return current_screen; } + static DGUSLCD_Screens getCurrentScreen() { return current_screen; } - static inline void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } + static void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } private: static DGUSLCD_Screens current_screen; //< currently on screen diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h index bb0bd2bd3b423..d4fdf1d27e2ad 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h @@ -38,10 +38,10 @@ class DGUSScreenHandler { // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); - static inline void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); } - static inline 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) { + 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); } @@ -213,13 +213,13 @@ class DGUSScreenHandler { } // Force an update of all VP on the current screen. - static inline void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } + static void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } // Has all VPs sent to the screen - static inline bool IsScreenComplete() { return ScreenComplete; } + static bool IsScreenComplete() { return ScreenComplete; } - static inline DGUSLCD_Screens getCurrentScreen() { return current_screen; } + static DGUSLCD_Screens getCurrentScreen() { return current_screen; } - static inline void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } + static void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } private: static DGUSLCD_Screens current_screen; //< currently on screen diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h index 265e2fe584bdd..332108d81a303 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h @@ -98,7 +98,7 @@ class DGUSDisplay { // 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 inline bool IsInitialized() { + static bool IsInitialized() { return initialized; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h index 3b63b0fd5be62..afb380aa90ad2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/compat.h @@ -43,8 +43,8 @@ #define min(a,b) ((a)<(b)?(a):(b)) #else namespace UI { - static inline uint32_t safe_millis() { return millis(); } - static inline void yield() {} + static uint32_t safe_millis() { return millis(); } + static void yield() {} }; #endif 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 b8e687147ba90..da911c772daa9 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 @@ -40,13 +40,13 @@ template struct port_pin { typedef port_t port; - static inline void set_high() {port::port() = (port::port() | bits);} - static inline void set_low() {port::port() = (port::port() & (~bits));} - static inline void set_input() {port::ddr() = (port::ddr() & (~bits));} - static inline void set_input_pullup() {set_input(); set_high();} - static inline void set_output() {port::ddr() = (port::ddr() | bits);} - static inline uint8_t read() {return port::pin() & bits;} - static inline void write(bool v) {if (v) set_high(); else set_low();} + static void set_high() {port::port() = (port::port() | bits);} + static void set_low() {port::port() = (port::port() & (~bits));} + static void set_input() {port::ddr() = (port::ddr() & (~bits));} + static void set_input_pullup() {set_input(); set_high();} + static void set_output() {port::ddr() = (port::ddr() | bits);} + static uint8_t read() {return port::pin() & bits;} + static void write(bool v) {if (v) set_high(); else set_low();} }; #define MAKE_AVR_PORT_PINS(ID) \ @@ -109,13 +109,13 @@ template struct arduino_digital_pin { static constexpr uint8_t pin = p; - static inline void set_high() {digitalWrite(p, HIGH);} - static inline void set_low() {digitalWrite(p, LOW);} - static inline void set_input() {pinMode(p, INPUT);} - static inline void set_input_pullup() {pinMode(p, INPUT_PULLUP);} - static inline void set_output() {pinMode(p, OUTPUT);} - static inline uint8_t read() {return digitalRead(p);} - static inline void write(bool v) {digitalWrite(p, v ? HIGH : LOW);} + static void set_high() {digitalWrite(p, HIGH);} + static void set_low() {digitalWrite(p, LOW);} + static void set_input() {pinMode(p, INPUT);} + static void set_input_pullup() {pinMode(p, INPUT_PULLUP);} + static void set_output() {pinMode(p, OUTPUT);} + static uint8_t read() {return digitalRead(p);} + static void write(bool v) {digitalWrite(p, v ? HIGH : LOW);} }; #define MAKE_ARDUINO_PINS(ID) typedef arduino_digital_pin ARDUINO_DIGITAL_##ID; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h index 2ddab1b818b46..b204f04743a41 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/sound_list.h @@ -29,10 +29,10 @@ class SoundList { } list[]; public: static const uint8_t n; - static inline const char* name(uint8_t val) { + static const char* name(uint8_t val) { return (const char* ) pgm_read_ptr_far(&list[val].name); } - static inline FTDI::SoundPlayer::sound_t* data(uint8_t val) { + static FTDI::SoundPlayer::sound_t* data(uint8_t val) { return (FTDI::SoundPlayer::sound_t*) pgm_read_ptr_far(&list[val].data); } }; diff --git a/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h index 4683ff935187a..72394286ac58b 100644 --- a/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h +++ b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.h @@ -96,12 +96,12 @@ class SPIFlashStorage { static uint8_t m_pageData[SPI_FLASH_PageSize]; static uint32_t m_currentPage; static uint16_t m_pageDataUsed; - static inline uint16_t pageDataFree() { return SPI_FLASH_PageSize - m_pageDataUsed; } + static uint16_t pageDataFree() { return SPI_FLASH_PageSize - m_pageDataUsed; } static uint32_t m_startAddress; #if HAS_SPI_FLASH_COMPRESSION static uint8_t m_compressedData[SPI_FLASH_PageSize]; static uint16_t m_compressedDataUsed; - static inline uint16_t compressedDataFree() { return SPI_FLASH_PageSize - m_compressedDataUsed; } + static uint16_t compressedDataFree() { return SPI_FLASH_PageSize - m_compressedDataUsed; } #endif }; diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 7014040097c44..e9aa0a6da543a 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -274,8 +274,8 @@ class MarlinUI { static bool detected(); static void init_lcd(); #else - static inline bool detected() { return true; } - static inline void init_lcd() {} + static bool detected() { return true; } + static void init_lcd() {} #endif #if HAS_PRINT_PROGRESS @@ -294,7 +294,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); } #if ENABLED(SHOW_REMAINING_TIME) - static inline uint32_t _calculated_remaining_time() { + static uint32_t _calculated_remaining_time() { const duration_t elapsed = print_job_timer.duration(); const progress_t progress = _get_progress(); return progress ? elapsed.value * (100 * (PROGRESS_SCALE) - progress) / progress : 0; @@ -342,12 +342,12 @@ class MarlinUI { static bool has_status(); static void reset_status(const bool no_welcome=false); static void set_alert_status(FSTR_P const fstr); - static inline void reset_alert_level() { alert_level = 0; } + static void reset_alert_level() { alert_level = 0; } #else static constexpr bool has_status() { return false; } - static inline void reset_status(const bool=false) {} - static inline void set_alert_status(FSTR_P const) {} - static inline void reset_alert_level() {} + static void reset_status(const bool=false) {} + static void set_alert_status(FSTR_P const) {} + static void reset_alert_level() {} #endif static void set_status(const char * const cstr, const bool persist=false); @@ -360,7 +360,7 @@ class MarlinUI { static void draw_status_message(const bool blink); #endif #else - static inline void kill_screen(FSTR_P const, FSTR_P const) {} + static void kill_screen(FSTR_P const, FSTR_P const) {} #endif #if HAS_DISPLAY @@ -444,7 +444,7 @@ class MarlinUI { #if HAS_BUZZER static void completion_feedback(const bool good=true); #else - static inline void completion_feedback(const bool=true) { TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); } + static void completion_feedback(const bool=true) { TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); } #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -479,9 +479,9 @@ class MarlinUI { #else // No LCD - static inline void init() {} - static inline void update() {} - static inline void return_to_status() {} + static void init() {} + static void update() {} + static void return_to_status() {} #endif @@ -500,17 +500,17 @@ class MarlinUI { static preheat_t material_preset[PREHEAT_COUNT]; static PGM_P get_preheat_label(const uint8_t m); static void apply_preheat(const uint8_t m, const uint8_t pmask, const uint8_t e=active_extruder); - static inline void preheat_set_fan(const uint8_t m) { TERN_(HAS_FAN, apply_preheat(m, PM_FAN)); } - static inline void preheat_hotend(const uint8_t m, const uint8_t e=active_extruder) { TERN_(HAS_HOTEND, apply_preheat(m, PM_HOTEND)); } - static inline void preheat_hotend_and_fan(const uint8_t m, const uint8_t e=active_extruder) { preheat_hotend(m, e); preheat_set_fan(m); } - static inline void preheat_bed(const uint8_t m) { TERN_(HAS_HEATED_BED, apply_preheat(m, PM_BED)); } - static inline void preheat_all(const uint8_t m) { apply_preheat(m, 0xFF); } + static void preheat_set_fan(const uint8_t m) { TERN_(HAS_FAN, apply_preheat(m, PM_FAN)); } + static void preheat_hotend(const uint8_t m, const uint8_t e=active_extruder) { TERN_(HAS_HOTEND, apply_preheat(m, PM_HOTEND)); } + static void preheat_hotend_and_fan(const uint8_t m, const uint8_t e=active_extruder) { preheat_hotend(m, e); preheat_set_fan(m); } + static void preheat_bed(const uint8_t m) { TERN_(HAS_HEATED_BED, apply_preheat(m, PM_BED)); } + static void preheat_all(const uint8_t m) { apply_preheat(m, 0xFF); } #endif #if SCREENS_CAN_TIME_OUT - static inline void reset_status_timeout(const millis_t ms) { return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS; } + static void reset_status_timeout(const millis_t ms) { return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS; } #else - static inline void reset_status_timeout(const millis_t) {} + static void reset_status_timeout(const millis_t) {} #endif #if HAS_LCD_MENU @@ -548,11 +548,11 @@ class MarlinUI { // goto_previous_screen and go_back may also be used as menu item callbacks static void _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_back)); - static inline void goto_previous_screen() { _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, false)); } - static inline void go_back() { _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, true)); } + static void goto_previous_screen() { _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, false)); } + static void go_back() { _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, true)); } static void return_to_status(); - static inline bool on_status_screen() { return currentScreen == status_screen; } + static bool on_status_screen() { return currentScreen == status_screen; } FORCE_INLINE static void run_current_screen() { (*currentScreen)(); } #if ENABLED(LIGHTWEIGHT_UI) @@ -567,7 +567,7 @@ class MarlinUI { TERN(SCREENS_CAN_TIME_OUT, defer_return_to_status = defer, UNUSED(defer)); } - static inline void goto_previous_screen_no_defer() { + static void goto_previous_screen_no_defer() { defer_status_screen(false); goto_previous_screen(); } @@ -599,20 +599,20 @@ class MarlinUI { #if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) static bool lcd_clicked; - static inline bool use_click() { + static bool use_click() { const bool click = lcd_clicked; lcd_clicked = false; return click; } #else static constexpr bool lcd_clicked = false; - static inline bool use_click() { return false; } + static bool use_click() { return false; } #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_LCD_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI) static void pause_show_message(const PauseMessage message, const PauseMode mode=PAUSE_MODE_SAME, const uint8_t extruder=active_extruder); #else - static inline void _pause_show_message() {} + static void _pause_show_message() {} #define pause_show_message(...) _pause_show_message() #endif @@ -631,9 +631,9 @@ class MarlinUI { #endif #if DISABLED(EEPROM_AUTO_INIT) static void eeprom_alert(const uint8_t msgid); - static inline void eeprom_alert_crc() { eeprom_alert(0); } - static inline void eeprom_alert_index() { eeprom_alert(1); } - static inline void eeprom_alert_version() { eeprom_alert(2); } + static void eeprom_alert_crc() { eeprom_alert(0); } + static void eeprom_alert_index() { eeprom_alert(1); } + static void eeprom_alert_version() { eeprom_alert(2); } #endif #endif @@ -674,7 +674,7 @@ class MarlinUI { #endif static void update_buttons(); - static inline bool button_pressed() { return BUTTON_CLICK() || TERN(TOUCH_SCREEN, touch_pressed(), false); } + static bool button_pressed() { return BUTTON_CLICK() || TERN(TOUCH_SCREEN, touch_pressed(), false); } #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) static void wait_for_release(); #endif @@ -705,7 +705,7 @@ class MarlinUI { #else - static inline void update_buttons() {} + static void update_buttons() {} #endif diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 048dab9b73158..72826262f456a 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -109,7 +109,7 @@ class MenuItem_confirm : public MenuItemBase { selectFunc_t yesFunc, selectFunc_t noFunc, PGM_P const pref, const char * const string=nullptr, PGM_P const suff=nullptr ); - static inline void select_screen( + static void select_screen( PGM_P const yes, PGM_P const no, selectFunc_t yesFunc, selectFunc_t noFunc, PGM_P const pref, FSTR_P const string, PGM_P const suff=nullptr @@ -178,7 +178,7 @@ class MenuEditItemBase : public MenuItemBase { static void draw_edit_screen(PGM_P const pstr, const char * const value); // This method is for the current menu item - static inline void draw_edit_screen(const char * const value) { draw_edit_screen(editLabel, value); } + static void draw_edit_screen(const char * const value) { draw_edit_screen(editLabel, value); } }; #if ENABLED(SDSUPPORT) diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index 624b9b303d080..1834b56a88759 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -39,14 +39,14 @@ class MenuItem_submenu : public MenuItemBase { FORCE_INLINE static void draw(const bool sel, const uint8_t row, PGM_P const pstr, ...) { _draw(sel, row, pstr, '>', LCD_STR_ARROW_RIGHT[0]); } - static inline void action(PGM_P const, const screenFunc_t func) { ui.push_current_screen(); ui.goto_screen(func); } + static void action(PGM_P const, const screenFunc_t func) { ui.push_current_screen(); ui.goto_screen(func); } }; // Any menu item that invokes an immediate action class MenuItem_button : public MenuItemBase { public: // Button-y Items are selectable lines with no other indicator - static inline void draw(const bool sel, const uint8_t row, PGM_P const pstr, ...) { + static void draw(const bool sel, const uint8_t row, PGM_P const pstr, ...) { _draw(sel, row, pstr, '>', ' '); } }; @@ -54,8 +54,8 @@ class MenuItem_button : public MenuItemBase { // ACTION_ITEM(LABEL, FUNC) class MenuItem_function : public MenuItem_button { public: - //static inline void action(PGM_P const, const uint8_t, const menuAction_t func) { (*func)(); }; - static inline void action(PGM_P const, const menuAction_t func) { if (func) (*func)(); }; + //static void action(PGM_P const, const uint8_t, const menuAction_t func) { (*func)(); }; + static void action(PGM_P const, const menuAction_t func) { if (func) (*func)(); }; }; // GCODES_ITEM(LABEL, GCODES) @@ -65,7 +65,7 @@ class MenuItem_gcode : public MenuItem_button { _draw(sel, row, pstr, '>', ' '); } static void action(PGM_P const, PGM_P const pgcode) { queue.inject(FPSTR(pgcode)); } - static inline void action(PGM_P const pstr, const uint8_t, PGM_P const pgcode) { action(pstr, pgcode); } + static void action(PGM_P const pstr, const uint8_t, PGM_P const pgcode) { action(pstr, pgcode); } }; //////////////////////////////////////////// @@ -77,8 +77,8 @@ template class TMenuEditItem : MenuEditItemBase { private: typedef typename NAME::type_t type_t; - static inline float scale(const_float_t value) { return NAME::scale(value); } - static inline float unscale(const_float_t value) { return NAME::unscale(value); } + static float scale(const_float_t value) { return NAME::scale(value); } + static float unscale(const_float_t value) { return NAME::unscale(value); } static const char* to_string(const int32_t value) { return NAME::strfunc(unscale(value)); } static void load(void *ptr, const int32_t value) { *((type_t*)ptr) = unscale(value); } public: @@ -117,9 +117,9 @@ class TMenuEditItem : MenuEditItemBase { * * struct MenuEditItemInfo_percent { * typedef uint8_t type_t; - * static inline float scale(const_float_t value) { return value * (100.f/255.f) +0.5f; } - * static inline float unscale(const_float_t value) { return value / (100.f/255.f) +0.5f; } - * static inline const char* strfunc(const_float_t value) { return ui8tostr4pctrj(_DOFIX(uint8_t,value)); } + * static float scale(const_float_t value) { return value * (100.f/255.f) +0.5f; } + * static float unscale(const_float_t value) { return value / (100.f/255.f) +0.5f; } + * static const char* strfunc(const_float_t value) { return ui8tostr4pctrj(_DOFIX(uint8_t,value)); } * }; * typedef TMenuEditItem MenuItem_percent */ @@ -128,9 +128,9 @@ class TMenuEditItem : MenuEditItemBase { #define DEFINE_MENU_EDIT_ITEM_TYPE(NAME, TYPE, STRFUNC, SCALE, ETC...) \ struct MenuEditItemInfo_##NAME { \ typedef TYPE type_t; \ - static inline float scale(const_float_t value) { return value * (SCALE) ETC; } \ - static inline float unscale(const_float_t value) { return value / (SCALE) ETC; } \ - static inline const char* strfunc(const_float_t value) { return STRFUNC(_DOFIX(TYPE,value)); } \ + static float scale(const_float_t value) { return value * (SCALE) ETC; } \ + static float unscale(const_float_t value) { return value / (SCALE) ETC; } \ + static const char* strfunc(const_float_t value) { return STRFUNC(_DOFIX(TYPE,value)); } \ }; \ typedef TMenuEditItem MenuItem_##NAME diff --git a/Marlin/src/lcd/tft/tft.h b/Marlin/src/lcd/tft/tft.h index 1576518b4bb78..435e7c30bf518 100644 --- a/Marlin/src/lcd/tft/tft.h +++ b/Marlin/src/lcd/tft/tft.h @@ -81,24 +81,24 @@ class TFT { static uint16_t buffer[TFT_BUFFER_SIZE]; static void init(); - static inline void set_font(const uint8_t *Font) { string.set_font(Font); } - static inline void add_glyphs(const uint8_t *Font) { string.add_glyphs(Font); } + static void set_font(const uint8_t *Font) { string.set_font(Font); } + static void add_glyphs(const uint8_t *Font) { string.add_glyphs(Font); } - static inline bool is_busy() { return io.isBusy(); } - static inline void abort() { io.Abort(); } - static inline void write_multiple(uint16_t Data, uint16_t Count) { io.WriteMultiple(Data, Count); } - static inline void write_sequence(uint16_t *Data, uint16_t Count) { io.WriteSequence(Data, Count); } - static inline void set_window(uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ymax) { io.set_window(Xmin, Ymin, Xmax, Ymax); } + static bool is_busy() { return io.isBusy(); } + static void abort() { io.Abort(); } + static void write_multiple(uint16_t Data, uint16_t Count) { io.WriteMultiple(Data, Count); } + static void write_sequence(uint16_t *Data, uint16_t Count) { io.WriteSequence(Data, Count); } + static void set_window(uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ymax) { io.set_window(Xmin, Ymin, Xmax, Ymax); } - static inline void fill(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { queue.fill(x, y, width, height, color); } - static inline void canvas(uint16_t x, uint16_t y, uint16_t width, uint16_t height) { queue.canvas(x, y, width, height); } - static inline void set_background(uint16_t color) { queue.set_background(color); } - static inline void add_text(uint16_t x, uint16_t y, uint16_t color, TFT_String tft_string, uint16_t maxWidth = 0) { queue.add_text(x, y, color, tft_string.string(), maxWidth); } - static inline void add_text(uint16_t x, uint16_t y, uint16_t color, const char *string, uint16_t maxWidth = 0) { queue.add_text(x, y, color, (uint8_t *)string, maxWidth); } - static inline void add_image(int16_t x, int16_t y, MarlinImage image, uint16_t *colors) { queue.add_image(x, y, image, colors); } - static inline void add_image(int16_t x, int16_t y, MarlinImage image, uint16_t color_main = COLOR_WHITE, uint16_t color_background = COLOR_BACKGROUND, uint16_t color_shadow = COLOR_BLACK) { queue.add_image(x, y, image, color_main, color_background, color_shadow); } - static inline void add_bar(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { queue.add_bar(x, y, width, height, color); } - static inline void add_rectangle(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { queue.add_rectangle(x, y, width, height, color); } + static void fill(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { queue.fill(x, y, width, height, color); } + static void canvas(uint16_t x, uint16_t y, uint16_t width, uint16_t height) { queue.canvas(x, y, width, height); } + static void set_background(uint16_t color) { queue.set_background(color); } + static void add_text(uint16_t x, uint16_t y, uint16_t color, TFT_String tft_string, uint16_t maxWidth = 0) { queue.add_text(x, y, color, tft_string.string(), maxWidth); } + static void add_text(uint16_t x, uint16_t y, uint16_t color, const char *string, uint16_t maxWidth = 0) { queue.add_text(x, y, color, (uint8_t *)string, maxWidth); } + static void add_image(int16_t x, int16_t y, MarlinImage image, uint16_t *colors) { queue.add_image(x, y, image, colors); } + static void add_image(int16_t x, int16_t y, MarlinImage image, uint16_t color_main = COLOR_WHITE, uint16_t color_background = COLOR_BACKGROUND, uint16_t color_shadow = COLOR_BLACK) { queue.add_image(x, y, image, color_main, color_background, color_shadow); } + static void add_bar(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { queue.add_bar(x, y, width, height, color); } + static void add_rectangle(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { queue.add_rectangle(x, y, width, height, color); } static void draw_edit_screen_buttons(); }; diff --git a/Marlin/src/lcd/tft/tft_string.h b/Marlin/src/lcd/tft/tft_string.h index 133889d9ae547..e486c2ee91c86 100644 --- a/Marlin/src/lcd/tft/tft_string.h +++ b/Marlin/src/lcd/tft/tft_string.h @@ -81,7 +81,7 @@ class TFT_String { static font_t *font() { return font_header; }; static uint16_t font_height() { return font_header->FontAscent - font_header->FontDescent; } static glyph_t *glyph(uint8_t character) { return glyphs[character] ?: glyphs[0x3F]; } /* Use '?' for unknown glyphs */ - static inline glyph_t *glyph(uint8_t *character) { return glyph(*character); } + static glyph_t *glyph(uint8_t *character) { return glyph(*character); } static void set(); static void add(uint8_t character) { add_character(character); eol(); } @@ -89,9 +89,9 @@ class TFT_String { static void add(uint8_t *string, int8_t index, uint8_t *itemString=nullptr); static void set(uint8_t *string) { set(); add(string); }; static void set(uint8_t *string, int8_t index, const char *itemString=nullptr) { set(); add(string, index, (uint8_t *)itemString); }; - static inline void set(const char *string) { set((uint8_t *)string); } - static inline void set(const char *string, int8_t index, const char *itemString=nullptr) { set((uint8_t *)string, index, itemString); } - static inline void add(const char *string) { add((uint8_t *)string); } + static void set(const char *string) { set((uint8_t *)string); } + static void set(const char *string, int8_t index, const char *itemString=nullptr) { set((uint8_t *)string, index, itemString); } + static void add(const char *string) { add((uint8_t *)string); } static void trim(uint8_t character=0x20); static void rtrim(uint8_t character=0x20); diff --git a/Marlin/src/lcd/tft/touch.h b/Marlin/src/lcd/tft/touch.h index 238453f765ed1..6021a840b65e3 100644 --- a/Marlin/src/lcd/tft/touch.h +++ b/Marlin/src/lcd/tft/touch.h @@ -106,7 +106,7 @@ class Touch { static millis_t last_touch_ms, time_to_hold, repeat_delay, touch_time; static TouchControlType touch_control_type; - static inline bool get_point(int16_t *x, int16_t *y); + static bool get_point(int16_t *x, int16_t *y); static void touch(touch_control_t *control); static void hold(touch_control_t *control, millis_t delay = 0); @@ -126,7 +126,7 @@ class Touch { static void enable() { enabled = true; } #if HAS_TOUCH_SLEEP static millis_t next_sleep_ms; - static inline bool isSleeping() { return next_sleep_ms == TSLP_SLEEPING; } + static bool isSleeping() { return next_sleep_ms == TSLP_SLEEPING; } static void sleepTimeout(); static void wakeUp(); #endif diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.h b/Marlin/src/libs/L64XX/L64XX_Marlin.h index e11d8e872e60a..de7c0d605740c 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.h +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.h @@ -118,11 +118,11 @@ class L64XX_Marlin : public L64XXHelper { #if ENABLED(MONITOR_L6470_DRIVER_STATUS) static bool monitor_paused; - static inline void pause_monitor(const bool p) { monitor_paused = p; } + static void pause_monitor(const bool p) { monitor_paused = p; } static void monitor_update(L64XX_axis_t stepper_index); static void monitor_driver(); #else - static inline void pause_monitor(const bool) {} + static void pause_monitor(const bool) {} #endif //protected: diff --git a/Marlin/src/libs/buzzer.h b/Marlin/src/libs/buzzer.h index 21b69002ffd3c..db5e3ee4ca795 100644 --- a/Marlin/src/libs/buzzer.h +++ b/Marlin/src/libs/buzzer.h @@ -77,7 +77,7 @@ * @brief Resets the state of the class * @details Brings the class state to a known one. */ - static inline void reset() { + static void reset() { off(); state.endtime = 0; } @@ -86,7 +86,7 @@ /** * @brief Init Buzzer */ - static inline void init() { + static void init() { SET_OUTPUT(BEEPER_PIN); reset(); } diff --git a/Marlin/src/libs/stopwatch.h b/Marlin/src/libs/stopwatch.h index fe5101a5beaa9..829d510050d35 100644 --- a/Marlin/src/libs/stopwatch.h +++ b/Marlin/src/libs/stopwatch.h @@ -53,7 +53,7 @@ class Stopwatch { * @return true on success */ static bool stop(); - static inline bool abort() { return stop(); } // Alias by default + static bool abort() { return stop(); } // Alias by default /** * @brief Pause the stopwatch @@ -114,7 +114,7 @@ class Stopwatch { #else - static inline void debug(FSTR_P const) {} + static void debug(FSTR_P const) {} #endif }; diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index a35966a98c913..e1ee933e83ba7 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -136,7 +136,7 @@ class Endstops { return enabled || TERN0(HAS_BED_PROBE, z_probe_enabled); } - static inline bool global_enabled() { return enabled_globally; } + static bool global_enabled() { return enabled_globally; } /** * Periodic call to poll endstops if required. Called from temperature ISR @@ -168,7 +168,7 @@ class Endstops { ; } - static inline bool probe_switch_activated() { + static bool probe_switch_activated() { return (true #if ENABLED(PROBE_ACTIVATION_SWITCH) && READ(PROBE_ACTIVATION_SWITCH_PIN) == PROBE_ACTIVATION_SWITCH_STATE diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 69e3f035ba9de..380c35755c964 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -431,15 +431,15 @@ class Planner { static int8_t xy_freq_limit_hz; // Minimum XY frequency setting static float xy_freq_min_speed_factor; // Minimum speed factor setting static int32_t xy_freq_min_interval_us; // Minimum segment time based on xy_freq_limit_hz - static inline void refresh_frequency_limit() { + static void refresh_frequency_limit() { //xy_freq_min_interval_us = xy_freq_limit_hz ?: LROUND(1000000.0f / xy_freq_limit_hz); if (xy_freq_limit_hz) xy_freq_min_interval_us = LROUND(1000000.0f / xy_freq_limit_hz); } - static inline void set_min_speed_factor_u8(const uint8_t v255) { + static void set_min_speed_factor_u8(const uint8_t v255) { xy_freq_min_speed_factor = float(ui8_to_percent(v255)) / 100; } - static inline void set_frequency_limit(const uint8_t hz) { + static void set_frequency_limit(const uint8_t hz) { xy_freq_limit_hz = constrain(hz, 0, 100); refresh_frequency_limit(); } @@ -508,7 +508,7 @@ class Planner { #if HAS_CLASSIC_JERK static void set_max_jerk(const AxisEnum axis, float inMaxJerkMMS); #else - static inline void set_max_jerk(const AxisEnum, const_float_t) {} + static void set_max_jerk(const AxisEnum, const_float_t) {} #endif #if HAS_EXTRUDERS @@ -516,7 +516,7 @@ class Planner { e_factor[e] = flow_percentage[e] * 0.01f * TERN(NO_VOLUMETRICS, 1.0f, volumetric_multiplier[e]); } - static inline void set_flow(const uint8_t e, const int16_t flow) { + static void set_flow(const uint8_t e, const int16_t flow) { flow_percentage[e] = flow; refresh_e_factor(e); } @@ -539,7 +539,7 @@ class Planner { #if ENABLED(FILAMENT_WIDTH_SENSOR) void apply_filament_width_sensor(const int8_t encoded_ratio); - static inline float volumetric_percent(const bool vol) { + static float volumetric_percent(const bool vol) { return 100.0f * (vol ? volumetric_area_nominal / volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] : volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] @@ -588,7 +588,7 @@ class Planner { * Returns 1.0 if planner.z_fade_height is 0.0. * Returns 0.0 if Z is past the specified 'Fade Height'. */ - static inline float fade_scaling_factor_for_z(const_float_t rz) { + static float fade_scaling_factor_for_z(const_float_t rz) { static float z_fade_factor = 1; if (!z_fade_height) return 1; if (rz >= z_fade_height) return 0; @@ -838,7 +838,7 @@ class Planner { */ static float get_axis_position_mm(const AxisEnum axis); - static inline abce_pos_t get_axis_positions_mm() { + static abce_pos_t get_axis_positions_mm() { const abce_pos_t out = LOGICAL_AXIS_ARRAY( get_axis_position_mm(E_AXIS), get_axis_position_mm(A_AXIS), get_axis_position_mm(B_AXIS), get_axis_position_mm(C_AXIS), @@ -870,7 +870,7 @@ class Planner { static float triggered_position_mm(const AxisEnum axis); // Blocks are queued, or we're running out moves, or the closed loop controller is waiting - static inline bool busy() { + static bool busy() { return (has_blocks_queued() || cleaning_buffer_counter || TERN0(EXTERNAL_CLOSED_LOOP_CONTROLLER, CLOSED_LOOP_WAITING()) ); @@ -938,7 +938,7 @@ class Planner { #if ENABLED(AUTOTEMP_PROPORTIONAL) static void _autotemp_update_from_hotend(); #else - static inline void _autotemp_update_from_hotend() {} + static void _autotemp_update_from_hotend() {} #endif #endif diff --git a/Marlin/src/module/printcounter.h b/Marlin/src/module/printcounter.h index 4deae45a656dc..931d14ded6da4 100644 --- a/Marlin/src/module/printcounter.h +++ b/Marlin/src/module/printcounter.h @@ -112,7 +112,7 @@ class PrintCounter: public Stopwatch { /** * @brief Initialize the print counter */ - static inline void init() { + static void init() { super::init(); loadStats(); } @@ -176,8 +176,8 @@ class PrintCounter: public Stopwatch { */ static bool start(); static bool _stop(const bool completed); - static inline bool stop() { return _stop(true); } - static inline bool abort() { return _stop(false); } + static bool stop() { return _stop(true); } + static bool abort() { return _stop(false); } static void reset(); diff --git a/Marlin/src/module/settings.h b/Marlin/src/module/settings.h index 967d49c0738e1..a8fca60baa12a 100644 --- a/Marlin/src/module/settings.h +++ b/Marlin/src/module/settings.h @@ -59,7 +59,7 @@ class MarlinSettings { static bool load(); // Return 'true' if data was loaded ok static bool validate(); // Return 'true' if EEPROM data is ok - static inline void first_load() { + static void first_load() { static bool loaded = false; if (!loaded && load()) loaded = true; } diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index f170dd410458d..6b190889cd31c 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -457,11 +457,11 @@ class Stepper { // The stepper subsystem goes to sleep when it runs out of things to execute. // Call this to notify the subsystem that it is time to go to work. - static inline void wake_up() { ENABLE_STEPPER_DRIVER_INTERRUPT(); } + static void wake_up() { ENABLE_STEPPER_DRIVER_INTERRUPT(); } - static inline bool is_awake() { return STEPPER_ISR_ENABLED(); } + static bool is_awake() { return STEPPER_ISR_ENABLED(); } - static inline bool suspend() { + static bool suspend() { const bool awake = is_awake(); if (awake) DISABLE_STEPPER_DRIVER_INTERRUPT(); return awake; @@ -564,7 +564,7 @@ class Stepper { FORCE_INLINE static void set_z4_lock(const bool state) { locked_Z4_motor = state; } #endif #endif - static inline void set_all_z_lock(const bool lock, const int8_t except=-1) { + static void set_all_z_lock(const bool lock, const int8_t except=-1) { set_z1_lock(lock ^ (except == 0)); set_z2_lock(lock ^ (except == 1)); #if NUM_Z_STEPPER_DRIVERS >= 3 @@ -586,16 +586,16 @@ class Stepper { static axis_flags_t axis_enabled; // Axis stepper(s) ENABLED states - static inline bool axis_is_enabled(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { + static bool axis_is_enabled(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { return TEST(axis_enabled.bits, INDEX_OF_AXIS(axis, eindex)); } - static inline void mark_axis_enabled(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { + static void mark_axis_enabled(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { SBI(axis_enabled.bits, INDEX_OF_AXIS(axis, eindex)); } - static inline void mark_axis_disabled(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { + static void mark_axis_disabled(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { CBI(axis_enabled.bits, INDEX_OF_AXIS(axis, eindex)); } - static inline bool can_axis_disable(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { + static bool can_axis_disable(const AxisEnum axis E_OPTARG(const uint8_t eindex=0)) { return !any_enable_overlap() || !(axis_enabled.bits & enable_overlap[INDEX_OF_AXIS(axis, eindex)]); } @@ -608,10 +608,10 @@ class Stepper { static void enable_e_steppers(); static void disable_e_steppers(); #else - static inline void enable_extruder() {} - static inline bool disable_extruder() { return true; } - static inline void enable_e_steppers() {} - static inline void disable_e_steppers() {} + static void enable_extruder() {} + static bool disable_extruder() { return true; } + static void enable_e_steppers() {} + static void disable_e_steppers() {} #endif #define ENABLE_EXTRUDER(N) enable_extruder(E_TERN_(N)) diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 0e4302938eda6..1ca0f3e88cd53 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -359,7 +359,7 @@ class Temperature { #if HAS_HOTEND static hotend_info_t temp_hotend[HOTENDS]; static const celsius_t hotend_maxtemp[HOTENDS]; - static inline celsius_t hotend_max_target(const uint8_t e) { return hotend_maxtemp[e] - (HOTEND_OVERSHOOT); } + static celsius_t hotend_max_target(const uint8_t e) { return hotend_maxtemp[e] - (HOTEND_OVERSHOOT); } #endif #if HAS_HEATED_BED static bed_info_t temp_bed; @@ -402,16 +402,16 @@ class Temperature { #if ENABLED(PREVENT_COLD_EXTRUSION) static bool allow_cold_extrude; static celsius_t extrude_min_temp; - static inline bool tooCold(const celsius_t temp) { return allow_cold_extrude ? false : temp < extrude_min_temp - (TEMP_WINDOW); } - static inline bool tooColdToExtrude(const uint8_t E_NAME) { return tooCold(wholeDegHotend(HOTEND_INDEX)); } - static inline bool targetTooColdToExtrude(const uint8_t E_NAME) { return tooCold(degTargetHotend(HOTEND_INDEX)); } + static bool tooCold(const celsius_t temp) { return allow_cold_extrude ? false : temp < extrude_min_temp - (TEMP_WINDOW); } + static bool tooColdToExtrude(const uint8_t E_NAME) { return tooCold(wholeDegHotend(HOTEND_INDEX)); } + static bool targetTooColdToExtrude(const uint8_t E_NAME) { return tooCold(degTargetHotend(HOTEND_INDEX)); } #else - static inline bool tooColdToExtrude(const uint8_t) { return false; } - static inline bool targetTooColdToExtrude(const uint8_t) { return false; } + static bool tooColdToExtrude(const uint8_t) { return false; } + static bool targetTooColdToExtrude(const uint8_t) { return false; } #endif - static inline bool hotEnoughToExtrude(const uint8_t e) { return !tooColdToExtrude(e); } - static inline bool targetHotEnoughToExtrude(const uint8_t e) { return !targetTooColdToExtrude(e); } + 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 ENABLED(SINGLENOZZLE_STANDBY_TEMP) @@ -449,7 +449,7 @@ class Temperature { }; // Convert the given heater_id_t to idle array index - static inline IdleIndex idle_index_for_id(const int8_t heater_id) { + static IdleIndex idle_index_for_id(const int8_t heater_id) { TERN_(HAS_HEATED_BED, if (heater_id == H_BED) return IDLE_INDEX_BED); return (IdleIndex)_MAX(heater_id, 0); } @@ -525,7 +525,7 @@ class Temperature { #if HAS_FAN_LOGIC static millis_t fan_update_ms; - static inline void manage_extruder_fans(millis_t ms) { + static void manage_extruder_fans(millis_t ms) { if (ELAPSED(ms, fan_update_ms)) { // only need to check fan state very infrequently const millis_t next_ms = ms + fan_update_interval_ms; #if HAS_PWMFANCHECK @@ -566,25 +566,25 @@ class Temperature { static void M305_report(const uint8_t t_index, const bool forReplay=true); static void reset_user_thermistors(); static celsius_float_t user_thermistor_to_deg_c(const uint8_t t_index, const int16_t raw); - static inline bool set_pull_up_res(int8_t t_index, float value) { + static bool set_pull_up_res(int8_t t_index, float value) { //if (!WITHIN(t_index, 0, USER_THERMISTORS - 1)) return false; if (!WITHIN(value, 1, 1000000)) return false; user_thermistor[t_index].series_res = value; return true; } - static inline bool set_res25(int8_t t_index, float value) { + static bool set_res25(int8_t t_index, float value) { if (!WITHIN(value, 1, 10000000)) return false; user_thermistor[t_index].res_25 = value; user_thermistor[t_index].pre_calc = true; return true; } - static inline bool set_beta(int8_t t_index, float value) { + static bool set_beta(int8_t t_index, float value) { if (!WITHIN(value, 1, 1000000)) return false; user_thermistor[t_index].beta = value; user_thermistor[t_index].pre_calc = true; return true; } - static inline bool set_sh_coeff(int8_t t_index, float value) { + static bool set_sh_coeff(int8_t t_index, float value) { if (!WITHIN(value, -0.01f, 0.01f)) return false; user_thermistor[t_index].sh_c_coeff = value; user_thermistor[t_index].pre_calc = true; @@ -634,18 +634,18 @@ class Temperature { static uint8_t fan_speed_scaler[FAN_COUNT]; #endif - static inline uint8_t scaledFanSpeed(const uint8_t fan, const uint8_t fs) { + static uint8_t scaledFanSpeed(const uint8_t fan, const uint8_t fs) { UNUSED(fan); // Potentially unused! return (fs * uint16_t(TERN(ADAPTIVE_FAN_SLOWING, fan_speed_scaler[fan], 128))) >> 7; } - static inline uint8_t scaledFanSpeed(const uint8_t fan) { + static uint8_t scaledFanSpeed(const uint8_t fan) { return scaledFanSpeed(fan, fan_speed[fan]); } static constexpr inline uint8_t pwmToPercent(const uint8_t speed) { return ui8_to_percent(speed); } - static inline uint8_t fanSpeedPercent(const uint8_t fan) { return ui8_to_percent(fan_speed[fan]); } - static inline uint8_t scaledFanSpeedPercent(const uint8_t fan) { return ui8_to_percent(scaledFanSpeed(fan)); } + static uint8_t fanSpeedPercent(const uint8_t fan) { return ui8_to_percent(fan_speed[fan]); } + static uint8_t scaledFanSpeedPercent(const uint8_t fan) { return ui8_to_percent(scaledFanSpeed(fan)); } #if ENABLED(EXTRA_FAN_SPEED) typedef struct { uint8_t saved, speed; } extra_fan_t; @@ -659,7 +659,7 @@ class Temperature { #endif // HAS_FAN - static inline void zero_fan_speeds() { + static void zero_fan_speeds() { #if HAS_FAN FANS_LOOP(i) set_fan_speed(i, 0); #endif @@ -680,13 +680,13 @@ class Temperature { * Preheating hotends */ #if MILLISECONDS_PREHEAT_TIME > 0 - static inline bool is_preheating(const uint8_t E_NAME) { + static bool is_preheating(const uint8_t E_NAME) { return preheat_end_time[HOTEND_INDEX] && PENDING(millis(), preheat_end_time[HOTEND_INDEX]); } - static inline void start_preheat_time(const uint8_t E_NAME) { + static void start_preheat_time(const uint8_t E_NAME) { preheat_end_time[HOTEND_INDEX] = millis() + MILLISECONDS_PREHEAT_TIME; } - static inline void reset_preheat_time(const uint8_t E_NAME) { + static void reset_preheat_time(const uint8_t E_NAME) { preheat_end_time[HOTEND_INDEX] = 0; } #else @@ -697,21 +697,21 @@ class Temperature { //inline so that there is no performance decrease. //deg=degreeCelsius - static inline celsius_float_t degHotend(const uint8_t E_NAME) { + static celsius_float_t degHotend(const uint8_t E_NAME) { return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].celsius); } - static inline celsius_t wholeDegHotend(const uint8_t E_NAME) { + static celsius_t wholeDegHotend(const uint8_t E_NAME) { return TERN0(HAS_HOTEND, static_cast(temp_hotend[HOTEND_INDEX].celsius + 0.5f)); } #if ENABLED(SHOW_TEMP_ADC_VALUES) - static inline int16_t rawHotendTemp(const uint8_t E_NAME) { + static int16_t rawHotendTemp(const uint8_t E_NAME) { return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].raw); } #endif - static inline celsius_t degTargetHotend(const uint8_t E_NAME) { + static celsius_t degTargetHotend(const uint8_t E_NAME) { return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].target); } @@ -730,11 +730,11 @@ class Temperature { start_watching_hotend(ee); } - static inline bool isHeatingHotend(const uint8_t E_NAME) { + static bool isHeatingHotend(const uint8_t E_NAME) { return temp_hotend[HOTEND_INDEX].target > temp_hotend[HOTEND_INDEX].celsius; } - static inline bool isCoolingHotend(const uint8_t E_NAME) { + static bool isCoolingHotend(const uint8_t E_NAME) { return temp_hotend[HOTEND_INDEX].target < temp_hotend[HOTEND_INDEX].celsius; } @@ -748,16 +748,16 @@ class Temperature { #endif #endif - static inline bool still_heating(const uint8_t e) { + static bool still_heating(const uint8_t e) { return degTargetHotend(e) > TEMP_HYSTERESIS && ABS(wholeDegHotend(e) - degTargetHotend(e)) > TEMP_HYSTERESIS; } - static inline bool degHotendNear(const uint8_t e, const celsius_t temp) { + static bool degHotendNear(const uint8_t e, const celsius_t temp) { return ABS(wholeDegHotend(e) - temp) < (TEMP_HYSTERESIS); } // Start watching a Hotend to make sure it's really heating up - static inline void start_watching_hotend(const uint8_t E_NAME) { + static void start_watching_hotend(const uint8_t E_NAME) { UNUSED(HOTEND_INDEX); #if WATCH_HOTENDS watch_hotend[HOTEND_INDEX].restart(degHotend(HOTEND_INDEX), degTargetHotend(HOTEND_INDEX)); @@ -769,16 +769,16 @@ class Temperature { #if HAS_HEATED_BED #if ENABLED(SHOW_TEMP_ADC_VALUES) - static inline int16_t rawBedTemp() { return temp_bed.raw; } + static int16_t rawBedTemp() { return temp_bed.raw; } #endif - static inline celsius_float_t degBed() { return temp_bed.celsius; } - static inline celsius_t wholeDegBed() { return static_cast(degBed() + 0.5f); } - static inline celsius_t degTargetBed() { return temp_bed.target; } - static inline bool isHeatingBed() { return temp_bed.target > temp_bed.celsius; } - static inline bool isCoolingBed() { return temp_bed.target < temp_bed.celsius; } + static celsius_float_t degBed() { return temp_bed.celsius; } + static celsius_t wholeDegBed() { return static_cast(degBed() + 0.5f); } + static celsius_t degTargetBed() { return temp_bed.target; } + static bool isHeatingBed() { return temp_bed.target > temp_bed.celsius; } + static bool isCoolingBed() { return temp_bed.target < temp_bed.celsius; } // Start watching the Bed to make sure it's really heating up - static inline void start_watching_bed() { TERN_(WATCH_BED, watch_bed.restart(degBed(), degTargetBed())); } + static void start_watching_bed() { TERN_(WATCH_BED, watch_bed.restart(degBed(), degTargetBed())); } static void setTargetBed(const celsius_t celsius) { TERN_(AUTO_POWER_CONTROL, if (celsius) powerManager.power_on()); @@ -792,7 +792,7 @@ class Temperature { static void wait_for_bed_heating(); - static inline bool degBedNear(const celsius_t temp) { + static bool degBedNear(const celsius_t temp) { return ABS(wholeDegBed() - temp) < (TEMP_BED_HYSTERESIS); } @@ -800,25 +800,25 @@ class Temperature { #if HAS_TEMP_PROBE #if ENABLED(SHOW_TEMP_ADC_VALUES) - static inline int16_t rawProbeTemp() { return temp_probe.raw; } + static int16_t rawProbeTemp() { return temp_probe.raw; } #endif - static inline celsius_float_t degProbe() { return temp_probe.celsius; } - static inline celsius_t wholeDegProbe() { return static_cast(degProbe() + 0.5f); } - static inline bool isProbeBelowTemp(const celsius_t target_temp) { return wholeDegProbe() < target_temp; } - static inline bool isProbeAboveTemp(const celsius_t target_temp) { return wholeDegProbe() > target_temp; } + static celsius_float_t degProbe() { return temp_probe.celsius; } + static celsius_t wholeDegProbe() { return static_cast(degProbe() + 0.5f); } + static bool isProbeBelowTemp(const celsius_t target_temp) { return wholeDegProbe() < target_temp; } + static bool isProbeAboveTemp(const celsius_t target_temp) { return wholeDegProbe() > target_temp; } static bool wait_for_probe(const celsius_t target_temp, bool no_wait_for_cooling=true); #endif #if HAS_TEMP_CHAMBER #if ENABLED(SHOW_TEMP_ADC_VALUES) - static inline int16_t rawChamberTemp() { return temp_chamber.raw; } + static int16_t rawChamberTemp() { return temp_chamber.raw; } #endif - static inline celsius_float_t degChamber() { return temp_chamber.celsius; } - static inline celsius_t wholeDegChamber() { return static_cast(degChamber() + 0.5f); } + static celsius_float_t degChamber() { return temp_chamber.celsius; } + static celsius_t wholeDegChamber() { return static_cast(degChamber() + 0.5f); } #if HAS_HEATED_CHAMBER - static inline celsius_t degTargetChamber() { return temp_chamber.target; } - static inline bool isHeatingChamber() { return temp_chamber.target > temp_chamber.celsius; } - static inline bool isCoolingChamber() { return temp_chamber.target < temp_chamber.celsius; } + static celsius_t degTargetChamber() { return temp_chamber.target; } + static bool isHeatingChamber() { return temp_chamber.target > temp_chamber.celsius; } + static bool isCoolingChamber() { return temp_chamber.target < temp_chamber.celsius; } static bool wait_for_chamber(const bool no_wait_for_cooling=true); #endif #endif @@ -829,49 +829,49 @@ class Temperature { start_watching_chamber(); } // Start watching the Chamber to make sure it's really heating up - static inline void start_watching_chamber() { TERN_(WATCH_CHAMBER, watch_chamber.restart(degChamber(), degTargetChamber())); } + static void start_watching_chamber() { TERN_(WATCH_CHAMBER, watch_chamber.restart(degChamber(), degTargetChamber())); } #endif #if HAS_TEMP_COOLER #if ENABLED(SHOW_TEMP_ADC_VALUES) - static inline int16_t rawCoolerTemp() { return temp_cooler.raw; } + static int16_t rawCoolerTemp() { return temp_cooler.raw; } #endif - static inline celsius_float_t degCooler() { return temp_cooler.celsius; } - static inline celsius_t wholeDegCooler() { return static_cast(temp_cooler.celsius + 0.5f); } + static celsius_float_t degCooler() { return temp_cooler.celsius; } + static celsius_t wholeDegCooler() { return static_cast(temp_cooler.celsius + 0.5f); } #if HAS_COOLER - static inline celsius_t degTargetCooler() { return temp_cooler.target; } - static inline bool isLaserHeating() { return temp_cooler.target > temp_cooler.celsius; } - static inline bool isLaserCooling() { return temp_cooler.target < temp_cooler.celsius; } + static celsius_t degTargetCooler() { return temp_cooler.target; } + static bool isLaserHeating() { return temp_cooler.target > temp_cooler.celsius; } + static bool isLaserCooling() { return temp_cooler.target < temp_cooler.celsius; } static bool wait_for_cooler(const bool no_wait_for_cooling=true); #endif #endif #if HAS_TEMP_BOARD #if ENABLED(SHOW_TEMP_ADC_VALUES) - static inline int16_t rawBoardTemp() { return temp_board.raw; } + static int16_t rawBoardTemp() { return temp_board.raw; } #endif - static inline celsius_float_t degBoard() { return temp_board.celsius; } - static inline celsius_t wholeDegBoard() { return static_cast(temp_board.celsius + 0.5f); } + static celsius_float_t degBoard() { return temp_board.celsius; } + static celsius_t wholeDegBoard() { return static_cast(temp_board.celsius + 0.5f); } #endif #if HAS_TEMP_REDUNDANT #if ENABLED(SHOW_TEMP_ADC_VALUES) - static inline int16_t rawRedundantTemp() { return temp_redundant.raw; } - static inline int16_t rawRedundanTargetTemp() { return (*temp_redundant.target).raw; } + static int16_t rawRedundantTemp() { return temp_redundant.raw; } + static int16_t rawRedundanTargetTemp() { return (*temp_redundant.target).raw; } #endif - static inline celsius_float_t degRedundant() { return temp_redundant.celsius; } - static inline celsius_float_t degRedundantTarget() { return (*temp_redundant.target).celsius; } - static inline celsius_t wholeDegRedundant() { return static_cast(temp_redundant.celsius + 0.5f); } - static inline celsius_t wholeDegRedundantTarget() { return static_cast((*temp_redundant.target).celsius + 0.5f); } + static celsius_float_t degRedundant() { return temp_redundant.celsius; } + static celsius_float_t degRedundantTarget() { return (*temp_redundant.target).celsius; } + static celsius_t wholeDegRedundant() { return static_cast(temp_redundant.celsius + 0.5f); } + static celsius_t wholeDegRedundantTarget() { return static_cast((*temp_redundant.target).celsius + 0.5f); } #endif #if HAS_COOLER - static inline void setTargetCooler(const celsius_t celsius) { + static void setTargetCooler(const celsius_t celsius) { temp_cooler.target = constrain(celsius, COOLER_MIN_TARGET, COOLER_MAX_TARGET); start_watching_cooler(); } // Start watching the Cooler to make sure it's really cooling down - static inline void start_watching_cooler() { TERN_(WATCH_COOLER, watch_cooler.restart(degCooler(), degTargetCooler())); } + static void start_watching_cooler() { TERN_(WATCH_COOLER, watch_cooler.restart(degCooler(), degTargetCooler())); } #endif /** @@ -887,7 +887,7 @@ class Temperature { /** * Cooldown, as from the LCD. Disables all heaters and fans. */ - static inline void cooldown() { + static void cooldown() { zero_fan_speeds(); disable_all_heaters(); } @@ -921,7 +921,7 @@ class Temperature { * Update the temp manager when PID values change */ #if ENABLED(PIDTEMP) - static inline void updatePID() { + static void updatePID() { TERN_(PID_EXTRUSION_SCALING, last_e_position = 0); } #endif @@ -934,13 +934,13 @@ class Temperature { #if HEATER_IDLE_HANDLER - static inline void reset_hotend_idle_timer(const uint8_t E_NAME) { + static void reset_hotend_idle_timer(const uint8_t E_NAME) { heater_idle[HOTEND_INDEX].reset(); start_watching_hotend(HOTEND_INDEX); } #if HAS_HEATED_BED - static inline void reset_bed_idle_timer() { + static void reset_bed_idle_timer() { heater_idle[IDLE_INDEX_BED].reset(); start_watching_bed(); } @@ -961,7 +961,7 @@ class Temperature { #if HAS_HOTEND && HAS_STATUS_MESSAGE static void set_heating_message(const uint8_t e); #else - static inline void set_heating_message(const uint8_t) {} + static void set_heating_message(const uint8_t) {} #endif #if HAS_LCD_MENU && HAS_TEMPERATURE @@ -974,7 +974,7 @@ class Temperature { static volatile bool raw_temps_ready; static void update_raw_temperatures(); static void updateTemperaturesFromRawValues(); - static inline bool updateTemperaturesIfReady() { + static bool updateTemperaturesIfReady() { if (!raw_temps_ready) return false; updateTemperaturesFromRawValues(); raw_temps_ready = false; @@ -1028,7 +1028,7 @@ class Temperature { }; // Convert the given heater_id_t to runaway state array index - static inline RunawayIndex runaway_index_for_id(const int8_t heater_id) { + static RunawayIndex runaway_index_for_id(const int8_t heater_id) { TERN_(HAS_THERMALLY_PROTECTED_CHAMBER, if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER); TERN_(HAS_THERMALLY_PROTECTED_CHAMBER, if (heater_id == H_COOLER) return RUNAWAY_IND_COOLER); TERN_(HAS_THERMALLY_PROTECTED_BED, if (heater_id == H_BED) return RUNAWAY_IND_BED); diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 53e1a7ffc3cbd..97e9bba867574 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -115,7 +115,7 @@ class CardReader { static void mount(); static void release(); - static inline bool isMounted() { return flag.mounted; } + static bool isMounted() { return flag.mounted; } // Handle media insert/remove static void manage_media(); @@ -128,7 +128,7 @@ class CardReader { static uint8_t autofile_index; // Next auto#.g index to run, plus one. Ignored by autofile_check when zero. static void autofile_begin(); // Begin check. Called automatically after boot-up. static bool autofile_check(); // Check for the next auto-start file and run it. - static inline void autofile_cancel() { autofile_index = 0; } + static void autofile_cancel() { autofile_index = 0; } #endif // Basic file ops @@ -138,7 +138,7 @@ class CardReader { static bool fileExists(const char * const name); static void removeFile(const char * const name); - static inline char* longest_filename() { return longFilename[0] ? longFilename : filename; } + static char* longest_filename() { return longFilename[0] ? longFilename : filename; } #if ENABLED(LONG_FILENAME_HOST_SUPPORT) static void printLongPath(char * const path); // Used by M33 #endif @@ -163,18 +163,18 @@ class CardReader { static void endFilePrintNow(TERN_(SD_RESORT, const bool re_sort=false)); static void abortFilePrintNow(TERN_(SD_RESORT, const bool re_sort=false)); static void fileHasFinished(); - static inline void abortFilePrintSoon() { flag.abort_sd_printing = isFileOpen(); } - static inline void pauseSDPrint() { flag.sdprinting = false; } - static inline bool isPrinting() { return flag.sdprinting; } - static inline bool isPaused() { return isFileOpen() && !isPrinting(); } + static void abortFilePrintSoon() { flag.abort_sd_printing = isFileOpen(); } + static void pauseSDPrint() { flag.sdprinting = false; } + static bool isPrinting() { return flag.sdprinting; } + static bool isPaused() { return isFileOpen() && !isPrinting(); } #if HAS_PRINT_PROGRESS_PERMYRIAD - static inline uint16_t permyriadDone() { + static uint16_t permyriadDone() { if (flag.sdprintdone) return 10000; if (isFileOpen() && filesize) return sdpos / ((filesize + 9999) / 10000); return 0; } #endif - static inline uint8_t percentDone() { + static uint8_t percentDone() { if (flag.sdprintdone) return 100; if (isFileOpen() && filesize) return sdpos / ((filesize + 99) / 100); return 0; @@ -213,20 +213,20 @@ class CardReader { #endif // Current Working Dir - Set by cd, cdup, cdroot, and diveToFile(true, ...) - static inline char* getWorkDirName() { workDir.getDosName(filename); return filename; } - static inline SdFile& getWorkDir() { return workDir.isOpen() ? workDir : root; } + static char* getWorkDirName() { workDir.getDosName(filename); return filename; } + static SdFile& getWorkDir() { return workDir.isOpen() ? workDir : root; } // Print File stats - static inline uint32_t getFileSize() { return filesize; } - static inline uint32_t getIndex() { return sdpos; } - static inline bool isFileOpen() { return isMounted() && file.isOpen(); } - static inline bool eof() { return getIndex() >= getFileSize(); } + static uint32_t getFileSize() { return filesize; } + static uint32_t getIndex() { return sdpos; } + static bool isFileOpen() { return isMounted() && file.isOpen(); } + static bool eof() { return getIndex() >= getFileSize(); } // File data operations - static inline int16_t get() { int16_t out = (int16_t)file.read(); sdpos = file.curPosition(); return out; } - static inline int16_t read(void *buf, uint16_t nbyte) { return file.isOpen() ? file.read(buf, nbyte) : -1; } - static inline int16_t write(void *buf, uint16_t nbyte) { return file.isOpen() ? file.write(buf, nbyte) : -1; } - static inline void setIndex(const uint32_t index) { file.seekSet((sdpos = index)); } + static int16_t get() { int16_t out = (int16_t)file.read(); sdpos = file.curPosition(); return out; } + static int16_t read(void *buf, uint16_t nbyte) { return file.isOpen() ? file.read(buf, nbyte) : -1; } + static int16_t write(void *buf, uint16_t nbyte) { return file.isOpen() ? file.write(buf, nbyte) : -1; } + static void setIndex(const uint32_t index) { file.seekSet((sdpos = index)); } // TODO: rename to diskIODriver() static DiskIODriver* diskIODriver() { return driver; } From f3b8b0b5b94cbd96bb3cdb48625942b14e17babc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Dec 2021 18:29:05 -0600 Subject: [PATCH 212/273] =?UTF-8?q?=F0=9F=9A=9A=20Rename=20L6470=20G-code?= =?UTF-8?q?=20file?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/L6470/{M916-918.cpp => M916-M918.cpp} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename Marlin/src/gcode/feature/L6470/{M916-918.cpp => M916-M918.cpp} (100%) diff --git a/Marlin/src/gcode/feature/L6470/M916-918.cpp b/Marlin/src/gcode/feature/L6470/M916-M918.cpp similarity index 100% rename from Marlin/src/gcode/feature/L6470/M916-918.cpp rename to Marlin/src/gcode/feature/L6470/M916-M918.cpp From 6d1eaa0efaef69b383e7b0f9fe3a53468f17f245 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 29 Dec 2021 01:05:01 +0000 Subject: [PATCH 213/273] [cron] Bump distribution date (2021-12-29) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ca2fb62834c6c..8afd313616f3c 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 "2021-12-28" +//#define STRING_DISTRIBUTION_DATE "2021-12-29" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c2963ee8327cb..13154d0d19e78 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 "2021-12-28" + #define STRING_DISTRIBUTION_DATE "2021-12-29" #endif /** From 16a1a55ceaa6717eae7d075e2d6d685ce25896ed Mon Sep 17 00:00:00 2001 From: Lefteris Garyfalakis <46350667+lefterisgar@users.noreply.github.com> Date: Wed, 29 Dec 2021 05:22:01 +0200 Subject: [PATCH 214/273] =?UTF-8?q?=F0=9F=8E=A8=20E3V2=20corner=20leveling?= =?UTF-8?q?=20=3D>=20tramming=20(#23375)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 48 +++++++++++++-------------- Marlin/src/lcd/e3v2/enhanced/dwin.h | 2 +- Marlin/src/lcd/e3v2/enhanced/dwinui.h | 2 +- 3 files changed, 25 insertions(+), 27 deletions(-) diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 64a85b4b2311d..080b6f170aa50 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -216,7 +216,7 @@ static bool sdprint = false; // New menu system pointers MenuClass *PrepareMenu = nullptr; -MenuClass *LevBedMenu = nullptr; +MenuClass *TrammingMenu = nullptr; MenuClass *MoveMenu = nullptr; MenuClass *ControlMenu = nullptr; MenuClass *AdvancedSettings = nullptr; @@ -1703,8 +1703,8 @@ void HMI_SaveProcessID(const uint8_t id) { void DWIN_StartHoming() { HMI_flag.home_flag = true; HMI_SaveProcessID(Homing); - Title.ShowCaption(F("Axis Homing")); - DWIN_Draw_Popup(ICON_BLTouch, F("Axis Homing"), F("Please wait until done.")); + Title.ShowCaption(GET_TEXT_F(MSG_LEVEL_BED_HOMING)); + DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_LEVEL_BED_HOMING), F("Please wait until done.")); } void DWIN_CompletedHoming() { @@ -1719,7 +1719,7 @@ void DWIN_CompletedHoming() { void DWIN_MeshLevelingStart() { #if HAS_ONESTEP_LEVELING HMI_SaveProcessID(Leveling); - Title.ShowCaption(F("Bed Leveling")); + Title.ShowCaption(GET_TEXT_F(MSG_BED_LEVELING)); DWIN_Draw_Popup(ICON_AutoLeveling, GET_TEXT_F(MSG_BED_LEVELING), F("Please wait until done.")); #elif ENABLED(MESH_BED_LEVELING) Draw_ManualMesh_Menu(); @@ -2403,18 +2403,16 @@ void SetSpeed() { SetPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } void ApplyFlow() { planner.refresh_e_factor(0); } void SetFlow() { SetPIntOnClick(MIN_PRINT_FLOW, MAX_PRINT_FLOW, ApplyFlow); } -// Leveling Bed Corners -void LevBed(uint8_t point) { +// Bed Tramming +void Tram(uint8_t point) { char cmd[100] = ""; #if HAS_ONESTEP_LEVELING static bool inLev = false; if (inLev) return; char str_1[6] = "", str_2[6] = "", str_3[6] = ""; - #define fmt "X:%s, Y:%s, Z:%s" float xpos = 0, ypos = 0, zval = 0; float margin = PROBING_MARGIN; #else - #define fmt "M420S0\nG28O\nG90\nG0Z5F300\nG0X%iY%iF5000\nG0Z0F300" int16_t xpos = 0, ypos = 0; int16_t margin = 30; #endif @@ -2449,7 +2447,7 @@ void LevBed(uint8_t point) { planner.synchronize(); inLev = true; zval = probe.probe_at_point(xpos, ypos, PROBE_PT_STOW); - sprintf_P(cmd, PSTR(fmt), + sprintf_P(cmd, PSTR("X:%s, Y:%s, Z:%s"), dtostrf(xpos, 1, 1, str_1), dtostrf(ypos, 1, 1, str_2), dtostrf(zval, 1, 2, str_3) @@ -2458,16 +2456,16 @@ void LevBed(uint8_t point) { inLev = false; #else planner.synchronize(); - sprintf_P(cmd, PSTR(fmt), xpos, ypos); + sprintf_P(cmd, PSTR("M420S0\nG28O\nG90\nG0Z5F300\nG0X%iY%iF5000\nG0Z0F300"), xpos, ypos); queue.inject(cmd); #endif } -void LevBedFL() { LevBed(0); } -void LevBedFR() { LevBed(1); } -void LevBedBR() { LevBed(2); } -void LevBedBL() { LevBed(3); } -void LevBedC () { LevBed(4); } +void TramFL() { Tram(0); } +void TramFR() { Tram(1); } +void TramBR() { Tram(2); } +void TramBL() { Tram(3); } +void TramC () { Tram(4); } #if ENABLED(MESH_BED_LEVELING) @@ -3184,7 +3182,7 @@ void Draw_Prepare_Menu() { ADDMENUITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENT_MAN), onDrawSubMenu, Draw_FilamentMan_Menu); #endif ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_MOVE_AXIS), onDrawMoveSubMenu, Goto_Move_Menu); - ADDMENUITEM(ICON_LevBed, GET_TEXT_F(MSG_BED_LEVELING), onDrawSubMenu, Draw_LevBedCorners_Menu); + ADDMENUITEM(ICON_Tram, GET_TEXT_F(MSG_BED_TRAMMING), onDrawSubMenu, Draw_Tramming_Menu); ADDMENUITEM(ICON_CloseMotor, GET_TEXT_F(MSG_DISABLE_STEPPERS), onDrawDisableMotors, DisableMotors); #if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) ADDMENUITEM(ICON_Homing, GET_TEXT_F(MSG_HOMING), onDrawSubMenu, Draw_Homing_Menu); @@ -3218,20 +3216,20 @@ void Draw_Prepare_Menu() { CurrentMenu->draw(); } -void Draw_LevBedCorners_Menu() { +void Draw_Tramming_Menu() { DWINUI::ClearMenuArea(); checkkey = Menu; - if (!LevBedMenu) LevBedMenu = new MenuClass(); - if (CurrentMenu != LevBedMenu) { - CurrentMenu = LevBedMenu; + if (!TrammingMenu) TrammingMenu = new MenuClass(); + if (CurrentMenu != TrammingMenu) { + CurrentMenu = TrammingMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_BED_TRAMMING)); // TODO: Chinese, English "Bed Tramming" JPG DWINUI::MenuItemsPrepare(6); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FL), onDrawMenuItem, LevBedFL); - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FR), onDrawMenuItem, LevBedFR); - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BR), onDrawMenuItem, LevBedBR); - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BL), onDrawMenuItem, LevBedBL); - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_C ), onDrawMenuItem, LevBedC ); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FL), onDrawMenuItem, TramFL); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FR), onDrawMenuItem, TramFR); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BR), onDrawMenuItem, TramBR); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BL), onDrawMenuItem, TramBL); + ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_C ), onDrawMenuItem, TramC ); } CurrentMenu->draw(); } diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.h b/Marlin/src/lcd/e3v2/enhanced/dwin.h index 773c9c7bdfaf7..f377732b41391 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.h @@ -211,7 +211,7 @@ void Draw_Control_Menu(); void Draw_AdvancedSettings_Menu(); void Draw_Prepare_Menu(); void Draw_Move_Menu(); -void Draw_LevBedCorners_Menu(); +void Draw_Tramming_Menu(); #if HAS_HOME_OFFSET void Draw_HomeOffset_Menu(); #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.h b/Marlin/src/lcd/e3v2/enhanced/dwinui.h index c222b3aeb92a4..c92014e84ffc6 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.h @@ -52,7 +52,7 @@ #define ICON_HomeX ICON_MoveX #define ICON_HomeY ICON_MoveY #define ICON_HomeZ ICON_MoveZ -#define ICON_LevBed ICON_SetEndTemp +#define ICON_Tram ICON_SetEndTemp #define ICON_Lock ICON_Cool #define ICON_ManualMesh ICON_HotendTemp #define ICON_MeshNext ICON_Axis From 755c10d3030ed18762e05b1f86396237bca8dfbf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Dec 2021 03:41:28 -0600 Subject: [PATCH 215/273] =?UTF-8?q?=F0=9F=8E=A8=20Simplify=20some=20debug?= =?UTF-8?q?=20echos?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../src/lcd/extui/dgus/DGUSScreenHandler.cpp | 8 ++--- .../extui/dgus/fysetc/DGUSScreenHandler.cpp | 2 +- .../lcd/extui/dgus/fysetc/DGUSScreenHandler.h | 2 +- .../extui/dgus/hiprecy/DGUSScreenHandler.cpp | 2 +- .../extui/dgus/hiprecy/DGUSScreenHandler.h | 2 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 36 +++++++++---------- .../lcd/extui/dgus/mks/DGUSScreenHandler.h | 2 +- .../extui/dgus/origin/DGUSScreenHandler.cpp | 2 +- .../lcd/extui/dgus/origin/DGUSScreenHandler.h | 2 +- 9 files changed, 29 insertions(+), 29 deletions(-) diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 2b00fd16f8e24..70bcca1859601 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -508,9 +508,9 @@ void DGUSScreenHandler::HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ case VP_Z_STEP_PER_MM: axis = ExtUI::axis_t::Z; break; default: return; } - DEBUG_ECHOLNPAIR_F("value:", value); + DEBUG_ECHOLNPGM("value:", value); ExtUI::setAxisSteps_per_mm(value, axis); - DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisSteps_per_mm(axis)); + DEBUG_ECHOLNPGM("value_set:", ExtUI::getAxisSteps_per_mm(axis)); skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel return; } @@ -531,9 +531,9 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo #endif #endif } - DEBUG_ECHOLNPAIR_F("value:", value); + DEBUG_ECHOLNPGM("value:", value); ExtUI::setAxisSteps_per_mm(value, extruder); - DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisSteps_per_mm(extruder)); + DEBUG_ECHOLNPGM("value_set:", ExtUI::getAxisSteps_per_mm(extruder)); skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index 750acece1c06a..eba4b153f135c 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -268,7 +268,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { #endif } - DEBUG_ECHOLNPAIR_F("V3:", newvalue); + DEBUG_ECHOLNPGM("V3:", newvalue); *(float *)var.memadr = newvalue; skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h index d4fdf1d27e2ad..dfc1e9ea7d689 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h @@ -206,7 +206,7 @@ class DGUSScreenHandler { static void DGUSLCD_SendFloatAsIntValueToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { float f = *(float *)var.memadr; - DEBUG_ECHOLNPAIR_F(" >> ", f, 6); + DEBUG_ECHOLNPGM(" >> ", f, 6); f *= cpow(10, decimals); dgusdisplay.WriteVariable(var.VP, (int16_t)f); } diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index 79a3cb91038d9..88b3255b66e2b 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -268,7 +268,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { #endif } - DEBUG_ECHOLNPAIR_F("V3:", newvalue); + DEBUG_ECHOLNPGM("V3:", newvalue); *(float *)var.memadr = newvalue; skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h index d4fdf1d27e2ad..dfc1e9ea7d689 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h @@ -206,7 +206,7 @@ class DGUSScreenHandler { static void DGUSLCD_SendFloatAsIntValueToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { float f = *(float *)var.memadr; - DEBUG_ECHOLNPAIR_F(" >> ", f, 6); + DEBUG_ECHOLNPGM(" >> ", f, 6); f *= cpow(10, decimals); dgusdisplay.WriteVariable(var.VP, (int16_t)f); } diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 0e2a971fd1b8a..8054181353ec8 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -93,7 +93,7 @@ void DGUSScreenHandler::DGUSLCD_SendFanToDisplay(DGUS_VP_Variable &var) { void DGUSScreenHandler::DGUSLCD_SendBabyStepToDisplay_MKS(DGUS_VP_Variable &var) { float value = current_position.z; - DEBUG_ECHOLNPAIR_F(" >> ", value, 6); + DEBUG_ECHOLNPGM(" >> ", value, 6); value *= cpow(10, 2); dgusdisplay.WriteVariable(VP_SD_Print_Baby, (uint16_t)value); } @@ -399,7 +399,7 @@ void DGUSScreenHandler::GetOffsetValue(DGUS_VP_Variable &var, void *val_ptr) { #if HAS_BED_PROBE int32_t value = swap32(*(int32_t *)val_ptr); float Offset = value / 100.0f; - DEBUG_ECHOLNPAIR_F("\nget int6 offset >> ", value, 6); + DEBUG_ECHOLNPGM("\nget int6 offset >> ", value, 6); #endif switch (var.VP) { @@ -909,7 +909,7 @@ void DGUSScreenHandler::HandleChangeLevelPoint_MKS(DGUS_VP_Variable &var, void * DEBUG_ECHOLNPGM("HandleChangeLevelPoint_MKS"); const int16_t value_raw = swap16(*(int16_t*)val_ptr); - DEBUG_ECHOLNPAIR_F("value_raw:", value_raw); + DEBUG_ECHOLNPGM("value_raw:", value_raw); *(int16_t*)var.memadr = value_raw; @@ -924,7 +924,7 @@ void DGUSScreenHandler::HandleStepPerMMChanged_MKS(DGUS_VP_Variable &var, void * const float value = (float)value_raw; DEBUG_ECHOLNPGM("value_raw:", value_raw); - DEBUG_ECHOLNPAIR_F("value:", value); + DEBUG_ECHOLNPGM("value:", value); ExtUI::axis_t axis; switch (var.VP) { @@ -934,7 +934,7 @@ void DGUSScreenHandler::HandleStepPerMMChanged_MKS(DGUS_VP_Variable &var, void * case VP_Z_STEP_PER_MM: axis = ExtUI::axis_t::Z; break; } ExtUI::setAxisSteps_per_mm(value, axis); - DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisSteps_per_mm(axis)); + DEBUG_ECHOLNPGM("value_set:", ExtUI::getAxisSteps_per_mm(axis)); settings.save(); skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } @@ -946,7 +946,7 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged_MKS(DGUS_VP_Variable &var const float value = (float)value_raw; DEBUG_ECHOLNPGM("value_raw:", value_raw); - DEBUG_ECHOLNPAIR_F("value:", value); + DEBUG_ECHOLNPGM("value:", value); ExtUI::extruder_t extruder; switch (var.VP) { @@ -959,7 +959,7 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged_MKS(DGUS_VP_Variable &var #endif } ExtUI::setAxisSteps_per_mm(value, extruder); - DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisSteps_per_mm(extruder)); + DEBUG_ECHOLNPGM("value_set:", ExtUI::getAxisSteps_per_mm(extruder)); settings.save(); skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } @@ -971,7 +971,7 @@ void DGUSScreenHandler::HandleMaxSpeedChange_MKS(DGUS_VP_Variable &var, void *va const float value = (float)value_raw; DEBUG_ECHOLNPGM("value_raw:", value_raw); - DEBUG_ECHOLNPAIR_F("value:", value); + DEBUG_ECHOLNPGM("value:", value); ExtUI::axis_t axis; switch (var.VP) { @@ -981,7 +981,7 @@ void DGUSScreenHandler::HandleMaxSpeedChange_MKS(DGUS_VP_Variable &var, void *va default: return; } ExtUI::setAxisMaxFeedrate_mm_s(value, axis); - DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisMaxFeedrate_mm_s(axis)); + DEBUG_ECHOLNPGM("value_set:", ExtUI::getAxisMaxFeedrate_mm_s(axis)); settings.save(); skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } @@ -993,7 +993,7 @@ void DGUSScreenHandler::HandleExtruderMaxSpeedChange_MKS(DGUS_VP_Variable &var, const float value = (float)value_raw; DEBUG_ECHOLNPGM("value_raw:", value_raw); - DEBUG_ECHOLNPAIR_F("value:", value); + DEBUG_ECHOLNPGM("value:", value); ExtUI::extruder_t extruder; switch (var.VP) { @@ -1006,7 +1006,7 @@ void DGUSScreenHandler::HandleExtruderMaxSpeedChange_MKS(DGUS_VP_Variable &var, case VP_E1_MAX_SPEED: extruder = ExtUI::extruder_t::E1; break; } ExtUI::setAxisMaxFeedrate_mm_s(value, extruder); - DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisMaxFeedrate_mm_s(extruder)); + DEBUG_ECHOLNPGM("value_set:", ExtUI::getAxisMaxFeedrate_mm_s(extruder)); settings.save(); skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } @@ -1018,7 +1018,7 @@ void DGUSScreenHandler::HandleMaxAccChange_MKS(DGUS_VP_Variable &var, void *val_ const float value = (float)value_raw; DEBUG_ECHOLNPGM("value_raw:", value_raw); - DEBUG_ECHOLNPAIR_F("value:", value); + DEBUG_ECHOLNPGM("value:", value); ExtUI::axis_t axis; switch (var.VP) { @@ -1028,7 +1028,7 @@ void DGUSScreenHandler::HandleMaxAccChange_MKS(DGUS_VP_Variable &var, void *val_ case VP_Z_ACC_MAX_SPEED: axis = ExtUI::axis_t::Z; break; } ExtUI::setAxisMaxAcceleration_mm_s2(value, axis); - DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisMaxAcceleration_mm_s2(axis)); + DEBUG_ECHOLNPGM("value_set:", ExtUI::getAxisMaxAcceleration_mm_s2(axis)); settings.save(); skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } @@ -1049,9 +1049,9 @@ void DGUSScreenHandler::HandleExtruderAccChange_MKS(DGUS_VP_Variable &var, void case VP_E1_ACC_MAX_SPEED: extruder = ExtUI::extruder_t::E1; settings.load(); break; #endif } - DEBUG_ECHOLNPAIR_F("value:", value); + DEBUG_ECHOLNPGM("value:", value); ExtUI::setAxisMaxAcceleration_mm_s2(value, extruder); - DEBUG_ECHOLNPAIR_F("value_set:", ExtUI::getAxisMaxAcceleration_mm_s2(extruder)); + DEBUG_ECHOLNPGM("value_set:", ExtUI::getAxisMaxAcceleration_mm_s2(extruder)); settings.save(); skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } @@ -1115,7 +1115,7 @@ void DGUSScreenHandler::HandleAccChange_MKS(DGUS_VP_Variable &var, void *val_ptr #endif } - DEBUG_ECHOLNPAIR_F("V3:", newvalue); + DEBUG_ECHOLNPGM("V3:", newvalue); *(float *)var.memadr = newvalue; settings.save(); @@ -1175,7 +1175,7 @@ void DGUSScreenHandler::GetManualFilament(DGUS_VP_Variable &var, void *val_ptr) float value = (float)value_len; - DEBUG_ECHOLNPAIR_F("Get Filament len value:", value); + DEBUG_ECHOLNPGM("Get Filament len value:", value); distanceFilament = value; skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel @@ -1186,7 +1186,7 @@ void DGUSScreenHandler::GetManualFilamentSpeed(DGUS_VP_Variable &var, void *val_ uint16_t value_len = swap16(*(uint16_t*)val_ptr); - DEBUG_ECHOLNPAIR_F("filamentSpeed_mm_s value:", value_len); + DEBUG_ECHOLNPGM("filamentSpeed_mm_s value:", value_len); filamentSpeed_mm_s = value_len; diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index 2e6c8af9852bc..ee423b7bb9439 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -273,7 +273,7 @@ class DGUSScreenHandler { static void DGUSLCD_SendFloatAsIntValueToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { float f = *(float *)var.memadr; - DEBUG_ECHOLNPAIR_F(" >> ", f, 6); + DEBUG_ECHOLNPGM(" >> ", f, 6); f *= cpow(10, decimals); dgusdisplay.WriteVariable(var.VP, (int16_t)f); } diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index b77c92b7eb952..fb08fbf849192 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -268,7 +268,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { #endif } - DEBUG_ECHOLNPAIR_F("V3:", newvalue); + DEBUG_ECHOLNPGM("V3:", newvalue); *(float *)var.memadr = newvalue; skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h index d4fdf1d27e2ad..dfc1e9ea7d689 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h @@ -206,7 +206,7 @@ class DGUSScreenHandler { static void DGUSLCD_SendFloatAsIntValueToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { float f = *(float *)var.memadr; - DEBUG_ECHOLNPAIR_F(" >> ", f, 6); + DEBUG_ECHOLNPGM(" >> ", f, 6); f *= cpow(10, decimals); dgusdisplay.WriteVariable(var.VP, (int16_t)f); } From 88a6e5b691d61eb93d573e4e79aea3bf5e0b4501 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Dec 2021 04:17:41 -0600 Subject: [PATCH 216/273] =?UTF-8?q?=F0=9F=A9=BA=20Assert=20FAN=5FSOFT=5FPW?= =?UTF-8?q?M=20where=20required=20(#23383)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 8 ++++++-- Marlin/src/pins/mega/pins_MEGACONTROLLER.h | 2 +- Marlin/src/pins/stm32f1/pins_BEAST.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h | 2 +- Marlin/src/pins/stm32f1/pins_CHITU3D.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_V45x.h | 2 +- .../src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h | 7 ++++--- Marlin/src/pins/stm32f1/pins_FLY_MINI.h | 10 ++++++---- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 18 ++++++++++++------ Marlin/src/pins/stm32f1/pins_STM3R_MINI.h | 2 +- Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h | 4 +++- Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h | 6 ++++-- Marlin/src/pins/stm32f4/pins_INDEX_REV03.h | 2 +- Marlin/src/pins/stm32f4/pins_RUMBA32_common.h | 2 +- buildroot/tests/STM32F103RET6_creality | 2 +- buildroot/tests/STM32F103RE_btt_USB | 2 +- buildroot/tests/rumba32 | 5 +++-- 19 files changed, 50 insertions(+), 34 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 50191dd201e97..3261149668437 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2008,8 +2008,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif -#if HAS_FAN0 && CONTROLLER_FAN_PIN == FAN_PIN - #error "You cannot set CONTROLLER_FAN_PIN equal to FAN_PIN." +#if HAS_FAN0 + #if CONTROLLER_FAN_PIN == FAN_PIN + #error "You cannot set CONTROLLER_FAN_PIN equal to FAN_PIN." + #elif ENABLED(FAN_SOFT_PWM_REQUIRED) && DISABLED(FAN_SOFT_PWM) + #error "FAN_SOFT_PWM is required. Enable it to continue." + #endif #endif #if ENABLED(USE_CONTROLLER_FAN) diff --git a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h index 69c60b29ec547..0af37bb217ed3 100644 --- a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h +++ b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h @@ -121,7 +121,7 @@ #define CONTROLLER_FAN_PIN FAN2_PIN #endif -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED // // Misc. Functions diff --git a/Marlin/src/pins/stm32f1/pins_BEAST.h b/Marlin/src/pins/stm32f1/pins_BEAST.h index 2ace47822e163..d494b29c1448c 100644 --- a/Marlin/src/pins/stm32f1/pins_BEAST.h +++ b/Marlin/src/pins/stm32f1/pins_BEAST.h @@ -93,7 +93,7 @@ #define FAN_PIN PB10 #endif -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED // // Temperature Sensors diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h index 570d102c47583..7b8abb130060b 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -113,7 +113,7 @@ #define HEATER_BED_PIN PC9 // HOT BED #define FAN_PIN PC6 // FAN -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED #define CONTROLLER_FAN_PIN PC7 diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D.h b/Marlin/src/pins/stm32f1/pins_CHITU3D.h index 2d33fb9f2cc21..7d30d6efad88f 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D.h @@ -87,7 +87,7 @@ #define FAN_PIN PG14 // MAIN BOARD FAN #endif -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED // // Temperature Sensors diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index bf2a55fc7b995..cb7e784751a48 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -143,9 +143,7 @@ #ifndef FAN_PIN #define FAN_PIN PA0 // FAN #endif -#if PIN_EXISTS(FAN) - #define FAN_SOFT_PWM -#endif +#define FAN_SOFT_PWM_REQUIRED // // SD Card diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index 5251c8547b05e..4941949f81161 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -144,7 +144,7 @@ #define HEATER_BED_PIN PA1 // HOT BED #define FAN_PIN PA2 // FAN -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED // // SD Card diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h index 023fca21ce981..85d279872d55e 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h @@ -97,7 +97,7 @@ // Heaters / Fans // -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED // // SD Card diff --git a/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h b/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h index fea5b00b50d8b..0682bfd73620f 100644 --- a/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h @@ -38,10 +38,9 @@ //#define DISABLE_DEBUG #define DISABLE_JTAG //#define ENABLE_SPI3 -#define FLASH_EEPROM_EMULATION -#define FAN_SOFT_PWM -#if ENABLED(FLASH_EEPROM_EMULATION) +#if EITHER(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) #define MARLIN_EEPROM_SIZE (EEPROM_PAGE_SIZE) @@ -118,6 +117,8 @@ #endif #endif +#define FAN_SOFT_PWM_REQUIRED + // // Misc. Functions // diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index bfddf051f692c..5468d0b4bd7c6 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -30,10 +30,12 @@ // // Flash EEPROM Emulation // -#define FLASH_EEPROM_EMULATION -#define EEPROM_PAGE_SIZE 0x800 // 2KB -#define EEPROM_START_ADDRESS (0x8000000 + 256 * 1024 - 2 * EEPROM_PAGE_SIZE) // 256K firmware space -#define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE +#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + #define EEPROM_PAGE_SIZE 0x800 // 2KB + #define EEPROM_START_ADDRESS (0x8000000 + 256 * 1024 - 2 * EEPROM_PAGE_SIZE) // 256K firmware space + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE +#endif // // Servos diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index 15c6955a83a81..ca5ae45b3b75a 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -90,13 +90,19 @@ #define FAN_PIN PA15 // pin 77 (4cm Fan) #ifdef MAPLE_STM32F1 - #define FAN_SOFT_PWM // Required to avoid issues with heating or STLink - #define FAN_MIN_PWM 35 // Fan will not start in 1-30 range - #define FAN_MAX_PWM 255 + #define FAN_SOFT_PWM_REQUIRED + #if ENABLED(FAN_SOFT_PWM) && FAN_MIN_PWM < 35 // Required to avoid issues with heating or STLink + #error "FAN_MIN_PWM must be 35 or higher." // Fan will not start in 1-30 range + #endif +#elif ENABLED(FAST_PWM_FAN) + #if FAST_PWM_FAN_FREQUENCY != 31400 // Default 1000 is noisy, max 65K (uint16) + #error "FAST_PWM_FAN_FREQUENCY must be set to 31400." + #endif + #if FAN_MIN_PWM < 5 + #error "FAN_MIN_PWM must be 5 or higher." + #endif #else - #define FAST_PWM_FAN // STM32 Variant allow TIMER2 Hardware PWM - #define FAN_MIN_PWM 5 - #define FAN_MAX_PWM 255 + #error "FAST_PWM_FAN required to allow TIMER2 Hardware PWM." #endif //#define BEEPER_PIN PD13 // pin 60 (Servo PWM output 5V/GND on Board V0G+) made for BL-Touch sensor diff --git a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h index 7171de919d03e..e189fc3f97b96 100644 --- a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h @@ -91,7 +91,7 @@ #endif #define FAN1_PIN PD13 -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED // // Temperature Sensors diff --git a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h index bf38955127e4e..6c7e7cbbfa480 100644 --- a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h @@ -45,7 +45,9 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION +#endif #if ENABLED(FLASH_EEPROM_EMULATION) // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) #define EEPROM_START_ADDRESS (0x8000000UL + (512 * 1024) - 2 * EEPROM_PAGE_SIZE) diff --git a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h index 4cf9768fbe805..6d5928e86d58a 100644 --- a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h +++ b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h @@ -29,8 +29,10 @@ #define BOARD_INFO_NAME "Artillery Ruby" -#define FLASH_EEPROM_EMULATION -//#define I2C_EEPROM +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION + //#define I2C_EEPROM +#endif //#define E2END 0xFFF // 4KB #define HAL_TIMER_RATE F_CPU diff --git a/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h b/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h index 8560a04375c00..a9828c5bdaef6 100644 --- a/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h +++ b/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h @@ -119,7 +119,7 @@ #define FAN2_PIN PE4 #define FAN3_PIN PE5 -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED // Neopixel Rings #define NEOPIXEL_PIN PC7 diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index cf7c9ed8a6810..873a4d4ad3828 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -35,7 +35,7 @@ // Use soft PWM for fans - PWM is not working properly when paired with STM32 Arduino Core v1.7.0 // This can be removed when Core version is updated and PWM behaviour is fixed. -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED // // Configure Timers diff --git a/buildroot/tests/STM32F103RET6_creality b/buildroot/tests/STM32F103RET6_creality index ca7573cf16c3b..8eda5f801dd47 100755 --- a/buildroot/tests/STM32F103RET6_creality +++ b/buildroot/tests/STM32F103RET6_creality @@ -30,7 +30,7 @@ exec_test $1 $2 "Ender 3 v2 with MarlinUI" "$3" restore_configs opt_set MOTHERBOARD BOARD_CREALITY_V452 SERIAL_PORT 1 opt_disable NOZZLE_TO_PROBE_OFFSET -opt_enable NOZZLE_AS_PROBE Z_SAFE_HOMING Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN \ +opt_enable NOZZLE_AS_PROBE Z_SAFE_HOMING Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN FAN_SOFT_PWM \ PROBE_ACTIVATION_SWITCH PROBE_TARE PROBE_TARE_ONLY_WHILE_INACTIVE exec_test $1 $2 "Creality V4.5.2 PROBE_ACTIVATION_SWITCH, Probe Tare" "$3" diff --git a/buildroot/tests/STM32F103RE_btt_USB b/buildroot/tests/STM32F103RE_btt_USB index c63a90e43681a..7b264ea283129 100755 --- a/buildroot/tests/STM32F103RE_btt_USB +++ b/buildroot/tests/STM32F103RE_btt_USB @@ -15,7 +15,7 @@ exec_test $1 $2 "BigTreeTech SKR E3 DIP v1.0 - Basic Configuration" "$3" restore_configs opt_set MOTHERBOARD BOARD_BTT_SKR_CR6 SERIAL_PORT -1 SERIAL_PORT_2 2 TEMP_SENSOR_BED 1 -opt_enable CR10_STOCKDISPLAY \ +opt_enable CR10_STOCKDISPLAY FAN_SOFT_PWM \ NOZZLE_AS_PROBE Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN Z_SAFE_HOMING \ PROBE_ACTIVATION_SWITCH PROBE_TARE PROBE_TARE_ONLY_WHILE_INACTIVE \ PROBING_HEATERS_OFF PREHEAT_BEFORE_PROBING diff --git a/buildroot/tests/rumba32 b/buildroot/tests/rumba32 index f26af33610c6c..833769d0b9ba7 100755 --- a/buildroot/tests/rumba32 +++ b/buildroot/tests/rumba32 @@ -11,7 +11,7 @@ restore_configs opt_set MOTHERBOARD BOARD_RUMBA32_V1_0 SERIAL_PORT -1 \ TEMP_SENSOR_BED 1 X_DRIVER_TYPE TMC2130 opt_disable PIDTEMP -opt_enable PIDTEMPBED +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" @@ -19,12 +19,13 @@ exec_test $1 $2 "RUMBA32 V1.0 with TMC2130, PID Bed, and bed thermal protection restore_configs opt_set MOTHERBOARD BOARD_RUMBA32_V1_1 SERIAL_PORT -1 \ TEMP_SENSOR_BED 1 X_DRIVER_TYPE TMC2130 Y_DRIVER_TYPE TMC2208 -opt_enable PIDTEMPBED EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +opt_enable PIDTEMPBED FAN_SOFT_PWM EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER exec_test $1 $2 "RUMBA32 V1.1 with TMC2130, TMC2208, PID Bed, EEPROM settings, and graphic LCD controller" "$3" # Build examples restore_configs opt_set MOTHERBOARD BOARD_RUMBA32_MKS SERIAL_PORT -1 X_DRIVER_TYPE TMC2130 Y_DRIVER_TYPE TMC2208 +opt_enable FAN_SOFT_PWM exec_test $1 $2 "RUMBA32 MKS Default Config with Mixed TMC Drivers" "$3" # cleanup From 9edddd18ad96bf4b91b09179c99b57601fd7bf0d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 30 Dec 2021 01:05:16 +0000 Subject: [PATCH 217/273] [cron] Bump distribution date (2021-12-30) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 8afd313616f3c..e8278bfa11f36 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 "2021-12-29" +//#define STRING_DISTRIBUTION_DATE "2021-12-30" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 13154d0d19e78..42d0c3174b286 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 "2021-12-29" + #define STRING_DISTRIBUTION_DATE "2021-12-30" #endif /** From 6e8c67151148bc02fe52accb2e059015ff1b95e3 Mon Sep 17 00:00:00 2001 From: GHGiampy <83699429+GHGiampy@users.noreply.github.com> Date: Thu, 30 Dec 2021 05:37:07 +0100 Subject: [PATCH 218/273] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20Enhanced=20UI=20ma?= =?UTF-8?q?x=20E=20speed=20(#23387)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 080b6f170aa50..4e730d04e7278 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -3626,7 +3626,7 @@ void Draw_MaxSpeed_Menu() { ADDMENUITEM_P(ICON_MaxSpeedY, GET_TEXT_F(MSG_MAXSPEED_Y), onDrawMaxSpeedY, SetMaxSpeedY, &planner.settings.max_feedrate_mm_s[Y_AXIS]); ADDMENUITEM_P(ICON_MaxSpeedZ, GET_TEXT_F(MSG_MAXSPEED_Z), onDrawMaxSpeedZ, SetMaxSpeedZ, &planner.settings.max_feedrate_mm_s[Z_AXIS]); #if HAS_HOTEND - ADDMENUITEM_P(ICON_MaxSpeedE, GET_TEXT_F(MSG_MAXSPEED_E), onDrawMaxSpeedE, SetMaxSpeedE, &planner.settings.max_feedrate_mm_s[Z_AXIS]); + ADDMENUITEM_P(ICON_MaxSpeedE, GET_TEXT_F(MSG_MAXSPEED_E), onDrawMaxSpeedE, SetMaxSpeedE, &planner.settings.max_feedrate_mm_s[E_AXIS]); #endif } CurrentMenu->draw(); From 67521bdd01a5b26fbe5e82bc57b642c6ea3dcdd9 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Thu, 30 Dec 2021 20:35:22 +1300 Subject: [PATCH 219/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20RRW=20Keypad=20&?= =?UTF-8?q?=20Zonestar=20buttons=20(#23388)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/buttons.h | 64 +++++++++++++++++++++------------------- 1 file changed, 33 insertions(+), 31 deletions(-) diff --git a/Marlin/src/lcd/buttons.h b/Marlin/src/lcd/buttons.h index 6d028e9bc65ac..429fb971ec837 100644 --- a/Marlin/src/lcd/buttons.h +++ b/Marlin/src/lcd/buttons.h @@ -45,36 +45,6 @@ #define ENCODER_PHASE_3 1 #endif -#if IS_RRW_KEYPAD - #define BTN_OFFSET 0 // Bit offset into buttons for shift register values - - #define BLEN_KEYPAD_F3 0 - #define BLEN_KEYPAD_F2 1 - #define BLEN_KEYPAD_F1 2 - #define BLEN_KEYPAD_DOWN 3 - #define BLEN_KEYPAD_RIGHT 4 - #define BLEN_KEYPAD_MIDDLE 5 - #define BLEN_KEYPAD_UP 6 - #define BLEN_KEYPAD_LEFT 7 - - #define EN_KEYPAD_F1 _BV(BTN_OFFSET + BLEN_KEYPAD_F1) - #define EN_KEYPAD_F2 _BV(BTN_OFFSET + BLEN_KEYPAD_F2) - #define EN_KEYPAD_F3 _BV(BTN_OFFSET + BLEN_KEYPAD_F3) - #define EN_KEYPAD_DOWN _BV(BTN_OFFSET + BLEN_KEYPAD_DOWN) - #define EN_KEYPAD_RIGHT _BV(BTN_OFFSET + BLEN_KEYPAD_RIGHT) - #define EN_KEYPAD_MIDDLE _BV(BTN_OFFSET + BLEN_KEYPAD_MIDDLE) - #define EN_KEYPAD_UP _BV(BTN_OFFSET + BLEN_KEYPAD_UP) - #define EN_KEYPAD_LEFT _BV(BTN_OFFSET + BLEN_KEYPAD_LEFT) - - #define RRK(B) (keypad_buttons & (B)) - - #ifdef EN_C - #define BUTTON_CLICK() ((buttons & EN_C) || RRK(EN_KEYPAD_MIDDLE)) - #else - #define BUTTON_CLICK() RRK(EN_KEYPAD_MIDDLE) - #endif -#endif - #if EITHER(HAS_DIGITAL_BUTTONS, HAS_DWIN_E3V2) // Wheel spin pins where BA is 00, 10, 11, 01 (1 bit always changes) #define BLEN_A 0 @@ -141,7 +111,39 @@ #define B_ST _BV(BL_ST) #ifndef BUTTON_CLICK - #define BUTTON_CLICK() (buttons & (B_MI|B_ST)) + #if EN_C + #define BUTTON_CLICK() (buttons & (B_MI|B_ST)) + #endif + #endif +#endif + +#if IS_RRW_KEYPAD + #define BTN_OFFSET 0 // Bit offset into buttons for shift register values + + #define BLEN_KEYPAD_F3 0 + #define BLEN_KEYPAD_F2 1 + #define BLEN_KEYPAD_F1 2 + #define BLEN_KEYPAD_DOWN 3 + #define BLEN_KEYPAD_RIGHT 4 + #define BLEN_KEYPAD_MIDDLE 5 + #define BLEN_KEYPAD_UP 6 + #define BLEN_KEYPAD_LEFT 7 + + #define EN_KEYPAD_F1 _BV(BTN_OFFSET + BLEN_KEYPAD_F1) + #define EN_KEYPAD_F2 _BV(BTN_OFFSET + BLEN_KEYPAD_F2) + #define EN_KEYPAD_F3 _BV(BTN_OFFSET + BLEN_KEYPAD_F3) + #define EN_KEYPAD_DOWN _BV(BTN_OFFSET + BLEN_KEYPAD_DOWN) + #define EN_KEYPAD_RIGHT _BV(BTN_OFFSET + BLEN_KEYPAD_RIGHT) + #define EN_KEYPAD_MIDDLE _BV(BTN_OFFSET + BLEN_KEYPAD_MIDDLE) + #define EN_KEYPAD_UP _BV(BTN_OFFSET + BLEN_KEYPAD_UP) + #define EN_KEYPAD_LEFT _BV(BTN_OFFSET + BLEN_KEYPAD_LEFT) + + #define RRK(B) (keypad_buttons & (B)) + + #ifdef EN_C + #define BUTTON_CLICK() ((buttons & EN_C) || RRK(EN_KEYPAD_MIDDLE)) + #else + #define BUTTON_CLICK() RRK(EN_KEYPAD_MIDDLE) #endif #endif From c1410020abd71ace9a5cf84eedc637d2c41983c5 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 31 Dec 2021 01:07:37 +0000 Subject: [PATCH 220/273] [cron] Bump distribution date (2021-12-31) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e8278bfa11f36..97775ef280566 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 "2021-12-30" +//#define STRING_DISTRIBUTION_DATE "2021-12-31" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 42d0c3174b286..9f865bf5b5f56 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 "2021-12-30" + #define STRING_DISTRIBUTION_DATE "2021-12-31" #endif /** From ff46d7cae274375eba82a278ca70fe0da016f778 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 31 Dec 2021 01:43:25 -0600 Subject: [PATCH 221/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20"no=20T=20param"?= =?UTF-8?q?=20handling?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/L6470/M906.cpp | 2 +- Marlin/src/gcode/feature/trinamic/M569.cpp | 2 +- Marlin/src/gcode/feature/trinamic/M906.cpp | 2 +- Marlin/src/gcode/feature/trinamic/M911-M914.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 1 + 5 files changed, 5 insertions(+), 4 deletions(-) diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index 67d11493abf54..ae4a46dce60e9 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -285,7 +285,7 @@ void GcodeSuite::M906() { #if E_STEPPERS case E_AXIS: { - const int8_t eindex = get_target_e_stepper_from_command(); + const int8_t eindex = get_target_e_stepper_from_command(-2); #if AXIS_IS_L64XX(E0) if (eindex < 0 || eindex == 0) L6470_SET_KVAL_HOLD(E0); #endif diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index 3f4b0c6372a33..7bfedf8c7210f 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -134,7 +134,7 @@ static void say_stealth_status() { */ void GcodeSuite::M569() { if (parser.seen('S')) - set_stealth_status(parser.value_bool(), get_target_e_stepper_from_command()); + set_stealth_status(parser.value_bool(), get_target_e_stepper_from_command(-2)); else say_stealth_status(); } diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index 300b8beb097a6..788389ed61b7c 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -112,7 +112,7 @@ void GcodeSuite::M906() { #if E_STEPPERS case E_AXIS: { - const int8_t eindex = get_target_e_stepper_from_command(); + const int8_t eindex = get_target_e_stepper_from_command(-2); #if AXIS_IS_TMC(E0) if (eindex < 0 || eindex == 0) TMC_SET_CURRENT(E0); #endif diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 32a2d25e77dcf..37dd9479aba3d 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -291,7 +291,7 @@ break; #if E_STEPPERS case E_AXIS: { - const int8_t eindex = get_target_e_stepper_from_command(); + const int8_t eindex = get_target_e_stepper_from_command(-2); TERN_(E0_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 0) TMC_SET_PWMTHRS_E(0)); TERN_(E1_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 1) TMC_SET_PWMTHRS_E(1)); TERN_(E2_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 2) TMC_SET_PWMTHRS_E(2)); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index d3d8f335dfa99..2f031b3b74f63 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -148,6 +148,7 @@ int8_t GcodeSuite::get_target_extruder_from_command() { int8_t GcodeSuite::get_target_e_stepper_from_command(const int8_t dval/*=-1*/) { const int8_t e = parser.intval('T', dval); if (WITHIN(e, 0, E_STEPPERS - 1)) return e; + if (dval == -2) return dval; SERIAL_ECHO_START(); SERIAL_CHAR('M'); SERIAL_ECHO(parser.codenum); From ead693b1a4fe1c5e74b42e4ac6afd5a47bbbde29 Mon Sep 17 00:00:00 2001 From: Robby Candra Date: Fri, 31 Dec 2021 15:22:49 +0700 Subject: [PATCH 222/273] =?UTF-8?q?=F0=9F=94=A7=20DWIN=5FMARLINUI=20sanity?= =?UTF-8?q?=20checks=20(#23399)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 3261149668437..4cd16d44842cc 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -824,7 +824,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "LCD_PROGRESS_BAR requires SDSUPPORT or LCD_SET_PROGRESS_MANUALLY." #elif NONE(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) #error "LCD_PROGRESS_BAR only applies to HD44780 character LCD and TFTGLCD_PANEL_(SPI|I2C)." - #elif HAS_MARLINUI_U8GLIB + #elif HAS_MARLINUI_U8GLIB || IS_DWIN_MARLINUI #error "LCD_PROGRESS_BAR does not apply to graphical displays." #elif ENABLED(FILAMENT_LCD_DISPLAY) #error "LCD_PROGRESS_BAR and FILAMENT_LCD_DISPLAY are not fully compatible. Comment out this line to use both." @@ -3695,7 +3695,7 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #error "COOLANT_FLOOD requires COOLANT_FLOOD_PIN to be defined." #endif -#if NONE(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI) && ENABLED(PRINT_PROGRESS_SHOW_DECIMALS) +#if NONE(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI, IS_DWIN_MARLINUI) && ENABLED(PRINT_PROGRESS_SHOW_DECIMALS) #error "PRINT_PROGRESS_SHOW_DECIMALS currently requires a Graphical LCD." #endif From b07887687ed96645b3e67ae2586c8198575a3e5d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 31 Dec 2021 07:42:07 -0600 Subject: [PATCH 223/273] =?UTF-8?q?=F0=9F=9A=91=EF=B8=8F=20Fix=20thermal?= =?UTF-8?q?=20conditionals,=20structure?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_post.h | 8 +++---- Marlin/src/module/temperature.cpp | 34 ++++++++++++++---------------- Marlin/src/module/temperature.h | 10 ++++----- 3 files changed, 25 insertions(+), 27 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index a5c9d20eda9ea..e1e82c40f2c64 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2549,13 +2549,13 @@ #endif // Thermal protection -#if BOTH(HAS_HEATED_BED, THERMAL_PROTECTION_BED) - #define HAS_THERMALLY_PROTECTED_BED 1 +#if !HAS_HEATED_BED + #undef THERMAL_PROTECTION_BED #endif #if ENABLED(THERMAL_PROTECTION_HOTENDS) && WATCH_TEMP_PERIOD > 0 #define WATCH_HOTENDS 1 #endif -#if HAS_THERMALLY_PROTECTED_BED && WATCH_BED_TEMP_PERIOD > 0 +#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 @@ -2567,7 +2567,7 @@ #if (ENABLED(THERMAL_PROTECTION_HOTENDS) || !EXTRUDERS) \ && (ENABLED(THERMAL_PROTECTION_BED) || !HAS_HEATED_BED) \ && (ENABLED(THERMAL_PROTECTION_CHAMBER) || !HAS_HEATED_CHAMBER) \ - && (ENABLED(THERMAL_PROTECTION_COOLER) || !HAS_COOLER) + && (ENABLED(THERMAL_PROTECTION_COOLER) || !HAS_COOLER) #define THERMALLY_SAFE 1 #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index dccdc55034fd0..c5c4b3524bb08 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1444,7 +1444,7 @@ void Temperature::manage_heater() { TERN_(HEATER_IDLE_HANDLER, heater_idle[IDLE_INDEX_BED].update(ms)); - #if HAS_THERMALLY_PROTECTED_BED + #if ENABLED(THERMAL_PROTECTION_BED) tr_state_machine[RUNAWAY_IND_BED].run(temp_bed.celsius, temp_bed.target, H_BED, THERMAL_PROTECTION_BED_PERIOD, THERMAL_PROTECTION_BED_HYSTERESIS); #endif @@ -2570,20 +2570,14 @@ void Temperature::init() { ); */ - #if HEATER_IDLE_HANDLER - // If the heater idle timeout expires, restart - if (heater_idle[idle_index].timed_out) { - state = TRInactive; - running_temp = 0; - } - else - #endif - { - // If the target temperature changes, restart - if (running_temp != target) { - running_temp = target; - state = target > 0 ? TRFirstHeating : TRInactive; - } + // If the heater idle timeout expires, restart + if (TERN0(HEATER_IDLE_HANDLER, heater_idle[idle_index].timed_out)) { + state = TRInactive; + running_temp = 0; + } + else if (running_temp != target) { // If the target temperature changes, restart + running_temp = target; + state = target > 0 ? TRFirstHeating : TRInactive; } switch (state) { @@ -2596,7 +2590,7 @@ void Temperature::init() { state = TRStable; // While the temperature is stable watch for a bad temperature - case TRStable: + case TRStable: { #if ENABLED(ADAPTIVE_FAN_SLOWING) if (adaptive_fan_slowing && heater_id >= 0) { @@ -2614,13 +2608,17 @@ void Temperature::init() { } #endif + const millis_t now = millis(); + if (current >= running_temp - hysteresis_degc) { - timer = millis() + SEC_TO_MS(period_seconds); + timer = now + SEC_TO_MS(period_seconds); break; } - else if (PENDING(millis(), timer)) break; + else if (PENDING(now, timer)) break; state = TRRunaway; + } // fall through + case TRRunaway: TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); _temp_error(heater_id, FPSTR(str_t_thermal_runaway), GET_TEXT_F(MSG_THERMAL_RUNAWAY)); diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 1ca0f3e88cd53..56616682045ba 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -1009,7 +1009,7 @@ class Temperature { static void min_temp_error(const heater_id_t e); static void max_temp_error(const heater_id_t e); - #define HAS_THERMAL_PROTECTION ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER, HAS_THERMALLY_PROTECTED_BED, THERMAL_PROTECTION_COOLER) + #define HAS_THERMAL_PROTECTION ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER, THERMAL_PROTECTION_BED, THERMAL_PROTECTION_COOLER) #if HAS_THERMAL_PROTECTION @@ -1021,7 +1021,7 @@ class Temperature { REPEAT(HOTENDS, _RUNAWAY_IND_E) #undef _RUNAWAY_IND_E #endif - OPTARG(HAS_THERMALLY_PROTECTED_BED, RUNAWAY_IND_BED) + OPTARG(THERMAL_PROTECTION_BED, RUNAWAY_IND_BED) OPTARG(THERMAL_PROTECTION_CHAMBER, RUNAWAY_IND_CHAMBER) OPTARG(THERMAL_PROTECTION_COOLER, RUNAWAY_IND_COOLER) , NR_HEATER_RUNAWAY @@ -1029,9 +1029,9 @@ class Temperature { // Convert the given heater_id_t to runaway state array index static RunawayIndex runaway_index_for_id(const int8_t heater_id) { - TERN_(HAS_THERMALLY_PROTECTED_CHAMBER, if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER); - TERN_(HAS_THERMALLY_PROTECTED_CHAMBER, if (heater_id == H_COOLER) return RUNAWAY_IND_COOLER); - TERN_(HAS_THERMALLY_PROTECTED_BED, if (heater_id == H_BED) return RUNAWAY_IND_BED); + TERN_(THERMAL_PROTECTION_CHAMBER, if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER); + TERN_(THERMAL_PROTECTION_COOLER, if (heater_id == H_COOLER) return RUNAWAY_IND_COOLER); + TERN_(THERMAL_PROTECTION_BED, if (heater_id == H_BED) return RUNAWAY_IND_BED); return (RunawayIndex)_MAX(heater_id, 0); } From 61828492559f7a4f8d832f75cb262d64f813bdbe Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Fri, 31 Dec 2021 12:32:28 -0800 Subject: [PATCH 224/273] Do not warn about CONFIGURATION_EMBEDDING if it wasn't enabled (#23408) Warnings.cpp was warning about `CONFIGURATION_EMBEDDING` on AVR boards even if it wasn't enabled. Check the status of the feature before auto-disabling and warning about it. --- Marlin/src/inc/Conditionals_adv.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 9864b8715c754..8c6e79f36ab14 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -1006,7 +1006,7 @@ #endif // AVR are (usually) too limited in resources to store the configuration into the binary -#if !defined(FORCE_CONFIG_EMBED) && (defined(__AVR__) || DISABLED(SDSUPPORT) || EITHER(SDCARD_READONLY, DISABLE_M503)) +#if ENABLED(CONFIGURATION_EMBEDDING) && !defined(FORCE_CONFIG_EMBED) && (defined(__AVR__) || DISABLED(SDSUPPORT) || EITHER(SDCARD_READONLY, DISABLE_M503)) #undef CONFIGURATION_EMBEDDING #define CANNOT_EMBED_CONFIGURATION defined(__AVR__) #endif From 4de84031d84c9b92a7ce5c8df48b15682e51acdb Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 1 Jan 2022 01:08:17 +0000 Subject: [PATCH 225/273] [cron] Bump distribution date (2022-01-01) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 97775ef280566..33244880e3a6d 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 "2021-12-31" +//#define STRING_DISTRIBUTION_DATE "2022-01-01" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9f865bf5b5f56..3aa887a524bc5 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 "2021-12-31" + #define STRING_DISTRIBUTION_DATE "2022-01-01" #endif /** From 63f71d85f2af5c9a352a4fca9b3c1acb1a5f4746 Mon Sep 17 00:00:00 2001 From: John Lagonikas <39417467+zeleps@users.noreply.github.com> Date: Sun, 2 Jan 2022 02:18:07 +0200 Subject: [PATCH 226/273] =?UTF-8?q?=E2=9C=A8=20Temperature=20variance=20mo?= =?UTF-8?q?nitor=20(#23373)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 4 ++ Marlin/src/core/language.h | 1 + Marlin/src/inc/Conditionals_post.h | 3 ++ Marlin/src/lcd/language/language_el.h | 1 + Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/module/temperature.cpp | 55 +++++++++++++++++++++++---- Marlin/src/module/temperature.h | 8 +++- 7 files changed, 64 insertions(+), 9 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 2410d8b9033f2..76ab869bf7849 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -349,6 +349,10 @@ #define WATCH_COOLER_TEMP_INCREASE 3 // Degrees Celsius #endif +#if ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_BED, THERMAL_PROTECTION_CHAMBER, THERMAL_PROTECTION_COOLER) + #define THERMAL_PROTECTION_VARIANCE_MONITOR // Detect a sensor malfunction preventing temperature updates +#endif + #if ENABLED(PIDTEMP) // Add an experimental additional term to the heater power, proportional to the extrusion speed. // A well-chosen Kc value should add just enough power to melt the increased material volume. diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 0a6870af26bf3..707296b3574be 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -240,6 +240,7 @@ #define STR_REDUNDANCY "Heater switched off. Temperature difference between temp sensors is too high !" #define STR_T_HEATING_FAILED "Heating failed" #define STR_T_THERMAL_RUNAWAY "Thermal Runaway" +#define STR_T_MALFUNCTION "Thermal Malfunction" #define STR_T_MAXTEMP "MAXTEMP triggered" #define STR_T_MINTEMP "MINTEMP triggered" #define STR_ERR_PROBING_FAILED "Probing Failed" diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index e1e82c40f2c64..9ed25a611473e 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2564,6 +2564,9 @@ #if BOTH(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) + #undef THERMAL_PROTECTION_VARIANCE_MONITOR +#endif #if (ENABLED(THERMAL_PROTECTION_HOTENDS) || !EXTRUDERS) \ && (ENABLED(THERMAL_PROTECTION_BED) || !HAS_HEATED_BED) \ && (ENABLED(THERMAL_PROTECTION_CHAMBER) || !HAS_HEATED_CHAMBER) \ diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index 567706180cb15..265e02c0ef0aa 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -202,6 +202,7 @@ namespace Language_el { LSTR MSG_HEATING_FAILED_LCD = _UxGT("Αποτυχία θέρμανσης"); LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("ΠΛΕΟΝΑΖΟΥΣΑ ΘΕΡΜΟΤΗΤΑ"); LSTR MSG_THERMAL_RUNAWAY = _UxGT("ΘΕΡΜΙΚΗ ΔΙΑΦΥΓΗ"); + LSTR MSG_TEMP_MALFUNCTION = _UxGT("ΘΕΡΜΙΚΗ ΔΥΣΛΕΙΤΟΥΡΓΙΑ"); LSTR MSG_ERR_MAXTEMP = _UxGT("ΠΕΡΙΤΤΗ ΘΕΡΜΟΚΡΑΣΙΑ"); LSTR MSG_ERR_MINTEMP = _UxGT("ΑΝΕΠΑΡΚΗΣ ΘΕΡΜΟΚΡΑΣΙΑ"); LSTR MSG_HALTED = _UxGT("Εκτυπωτής διεκόπη"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index c8660cd1c8c52..f1beb62e07029 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -533,6 +533,7 @@ namespace Language_en { LSTR MSG_HEATING_FAILED_LCD = _UxGT("Heating Failed"); LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: REDUNDANT TEMP"); LSTR MSG_THERMAL_RUNAWAY = _UxGT("THERMAL RUNAWAY"); + LSTR MSG_TEMP_MALFUNCTION = _UxGT("TEMP MALFUNCTION"); LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("BED THERMAL RUNAWAY"); LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("CHAMBER T. RUNAWAY"); LSTR MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Cooler Runaway"); diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index c5c4b3524bb08..f7d53b6da7c37 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -196,6 +196,7 @@ Temperature thermalManager; PGMSTR(str_t_thermal_runaway, STR_T_THERMAL_RUNAWAY); +PGMSTR(str_t_temp_malfunction, STR_T_MALFUNCTION); PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); /** @@ -2570,14 +2571,30 @@ void Temperature::init() { ); */ - // If the heater idle timeout expires, restart - if (TERN0(HEATER_IDLE_HANDLER, heater_idle[idle_index].timed_out)) { - state = TRInactive; - running_temp = 0; - } - else if (running_temp != target) { // If the target temperature changes, restart - running_temp = target; - state = target > 0 ? TRFirstHeating : TRInactive; + #if ENABLED(THERMAL_PROTECTION_VARIANCE_MONITOR) + if (state == TRMalfunction) { // temperature invariance may continue, regardless of heater state + variance += ABS(current - last_temp); // no need for detection window now, a single change in variance is enough + last_temp = current; + if (!NEAR_ZERO(variance)) { + variance_timer = millis() + SEC_TO_MS(period_seconds); + variance = 0.0; + state = TRStable; // resume from where we detected the problem + } + } + #endif + + if (TERN1(THERMAL_PROTECTION_VARIANCE_MONITOR, state != TRMalfunction)) { + // If the heater idle timeout expires, restart + if (TERN0(HEATER_IDLE_HANDLER, heater_idle[idle_index].timed_out)) { + state = TRInactive; + running_temp = 0; + TERN_(THERMAL_PROTECTION_VARIANCE_MONITOR, variance_timer = 0); + } + else if (running_temp != target) { // If the target temperature changes, restart + running_temp = target; + state = target > 0 ? TRFirstHeating : TRInactive; + TERN_(THERMAL_PROTECTION_VARIANCE_MONITOR, variance_timer = 0); + } } switch (state) { @@ -2610,6 +2627,22 @@ void Temperature::init() { const millis_t now = millis(); + #if ENABLED(THERMAL_PROTECTION_VARIANCE_MONITOR) + if (PENDING(now, variance_timer)) { + variance += ABS(current - last_temp); + last_temp = current; + } + else { + if (NEAR_ZERO(variance) && variance_timer) { // valid variance monitoring window + state = TRMalfunction; + break; + } + variance_timer = now + SEC_TO_MS(period_seconds); + variance = 0.0; + last_temp = current; + } + #endif + if (current >= running_temp - hysteresis_degc) { timer = now + SEC_TO_MS(period_seconds); break; @@ -2622,6 +2655,12 @@ void Temperature::init() { case TRRunaway: TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); _temp_error(heater_id, FPSTR(str_t_thermal_runaway), GET_TEXT_F(MSG_THERMAL_RUNAWAY)); + + #if ENABLED(THERMAL_PROTECTION_VARIANCE_MONITOR) + case TRMalfunction: + TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); + _temp_error(heater_id, FPSTR(str_t_temp_malfunction), GET_TEXT_F(MSG_TEMP_MALFUNCTION)); + #endif } } diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 56616682045ba..e3515f0db870e 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -1035,12 +1035,18 @@ class Temperature { return (RunawayIndex)_MAX(heater_id, 0); } - enum TRState : char { TRInactive, TRFirstHeating, TRStable, TRRunaway }; + enum TRState : char { TRInactive, TRFirstHeating, TRStable, TRRunaway + OPTARG(THERMAL_PROTECTION_VARIANCE_MONITOR, TRMalfunction) + }; typedef struct { millis_t timer = 0; TRState state = TRInactive; float running_temp; + #if ENABLED(THERMAL_PROTECTION_VARIANCE_MONITOR) + millis_t variance_timer = 0; + celsius_float_t last_temp = 0.0, variance = 0.0; + #endif void run(const_celsius_float_t current, const_celsius_float_t target, const heater_id_t heater_id, const uint16_t period_seconds, const celsius_t hysteresis_degc); } tr_state_machine_t; From 08aacb822a7f49199939a5c66639adfc356b55fe Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 2 Jan 2022 01:09:36 +0000 Subject: [PATCH 227/273] [cron] Bump distribution date (2022-01-02) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 33244880e3a6d..ae674efded9df 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2022-01-01" +//#define STRING_DISTRIBUTION_DATE "2022-01-02" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3aa887a524bc5..6707e7ec506ed 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2022-01-01" + #define STRING_DISTRIBUTION_DATE "2022-01-02" #endif /** From 09ccaa5051df5b0580d99d0284fe657c474ccf38 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Jan 2022 20:01:24 -0600 Subject: [PATCH 228/273] =?UTF-8?q?=F0=9F=94=A8=20Add=20.vscode/extensions?= =?UTF-8?q?.json?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .gitignore | 7 ++----- .vscode/extensions.json | 8 ++++++++ 2 files changed, 10 insertions(+), 5 deletions(-) create mode 100644 .vscode/extensions.json diff --git a/.gitignore b/.gitignore index 72fd117bd2348..191dd65ed9f87 100755 --- a/.gitignore +++ b/.gitignore @@ -141,11 +141,8 @@ __vm/ vc-fileutils.settings # Visual Studio Code -.vscode -.vscode/.browse.c_cpp.db* -.vscode/c_cpp_properties.json -.vscode/launch.json -.vscode/*.db +.vscode/* +!.vscode/extensions.json #Simulation imgui.ini diff --git a/.vscode/extensions.json b/.vscode/extensions.json new file mode 100644 index 0000000000000..7226831cb1829 --- /dev/null +++ b/.vscode/extensions.json @@ -0,0 +1,8 @@ +{ + // See http://go.microsoft.com/fwlink/?LinkId=827846 + // for the documentation about the extensions.json format + "recommendations": [ + "marlinfirmware.auto-build", + "platformio.platformio-ide" + ] +} From 6fbfeb68010e63c76b545e2c27aeb48ee73be68b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Jan 2022 22:54:27 -0600 Subject: [PATCH 229/273] =?UTF-8?q?=E2=9C=A8=20M919=20:=20Chopper=20Timing?= =?UTF-8?q?=20(#23400)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 3 + Marlin/src/feature/tmc_util.h | 114 +++++--- Marlin/src/gcode/feature/trinamic/M906.cpp | 24 +- .../src/gcode/feature/trinamic/M911-M914.cpp | 38 ++- Marlin/src/gcode/feature/trinamic/M919.cpp | 266 ++++++++++++++++++ Marlin/src/gcode/gcode.cpp | 1 + Marlin/src/gcode/gcode.h | 2 + Marlin/src/inc/Conditionals_post.h | 16 +- ini/features.ini | 2 +- platformio.ini | 1 + 10 files changed, 387 insertions(+), 80 deletions(-) create mode 100644 Marlin/src/gcode/feature/trinamic/M919.cpp diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 76ab869bf7849..16c5587f9c6e8 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2979,6 +2979,9 @@ //#define CHOPPER_TIMING_Z2 CHOPPER_TIMING_Z //#define CHOPPER_TIMING_Z3 CHOPPER_TIMING_Z //#define CHOPPER_TIMING_Z4 CHOPPER_TIMING_Z + //#define CHOPPER_TIMING_I CHOPPER_TIMING + //#define CHOPPER_TIMING_J CHOPPER_TIMING + //#define CHOPPER_TIMING_K CHOPPER_TIMING //#define CHOPPER_TIMING_E CHOPPER_TIMING // For Extruders (override below) //#define CHOPPER_TIMING_E1 CHOPPER_TIMING_E //#define CHOPPER_TIMING_E2 CHOPPER_TIMING_E diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 2da425170f8f4..44cde9c7633ae 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -64,13 +64,13 @@ class TMCStorage { uint8_t otpw_count = 0, error_count = 0; bool flag_otpw = false; - inline bool getOTPW() { return flag_otpw; } - inline void clear_otpw() { flag_otpw = 0; } + bool getOTPW() { return flag_otpw; } + void clear_otpw() { flag_otpw = 0; } #endif - inline uint16_t getMilliamps() { return val_mA; } + uint16_t getMilliamps() { return val_mA; } - inline void printLabel() { + void printLabel() { SERIAL_CHAR(AXIS_LETTER); if (DRIVER_ID > '0') SERIAL_CHAR(DRIVER_ID); } @@ -97,25 +97,31 @@ class TMCMarlin : public TMC, public TMCStorage { TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t axis_chain_index) : TMC(CS, RS, pinMOSI, pinMISO, pinSCK, axis_chain_index) {} - inline uint16_t rms_current() { return TMC::rms_current(); } - inline void rms_current(uint16_t mA) { + uint16_t rms_current() { return TMC::rms_current(); } + void rms_current(uint16_t mA) { this->val_mA = mA; TMC::rms_current(mA); } - inline void rms_current(const uint16_t mA, const float mult) { + void rms_current(const uint16_t mA, const float mult) { this->val_mA = mA; TMC::rms_current(mA, mult); } - inline uint16_t get_microstep_counter() { return TMC::MSCNT(); } + uint16_t get_microstep_counter() { return TMC::MSCNT(); } #if HAS_STEALTHCHOP - inline bool get_stealthChop() { return this->en_pwm_mode(); } - inline bool get_stored_stealthChop() { return this->stored.stealthChop_enabled; } - inline void refresh_stepping_mode() { this->en_pwm_mode(this->stored.stealthChop_enabled); } - inline void set_stealthChop(const bool stch) { this->stored.stealthChop_enabled = stch; refresh_stepping_mode(); } - inline bool toggle_stepping_mode() { set_stealthChop(!this->stored.stealthChop_enabled); return get_stealthChop(); } + bool get_stealthChop() { return this->en_pwm_mode(); } + bool get_stored_stealthChop() { return this->stored.stealthChop_enabled; } + void refresh_stepping_mode() { this->en_pwm_mode(this->stored.stealthChop_enabled); } + void set_stealthChop(const bool stch) { this->stored.stealthChop_enabled = stch; refresh_stepping_mode(); } + bool toggle_stepping_mode() { set_stealthChop(!this->stored.stealthChop_enabled); return get_stealthChop(); } #endif + void set_chopper_times(const chopper_timing_t &ct) { + TMC::toff(ct.toff); + TMC::hysteresis_end(ct.hend); + TMC::hysteresis_start(ct.hstrt); + } + #if ENABLED(HYBRID_THRESHOLD) uint32_t get_pwm_thrs() { return _tmc_thrs(this->microsteps(), this->TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); @@ -127,7 +133,7 @@ class TMCMarlin : public TMC, public TMCStorage { #endif #if USE_SENSORLESS - inline int16_t homing_threshold() { return TMC::sgt(); } + int16_t homing_threshold() { return TMC::sgt(); } void homing_threshold(int16_t sgt_val) { sgt_val = (int16_t)constrain(sgt_val, sgt_min, sgt_max); TMC::sgt(sgt_val); @@ -139,13 +145,13 @@ class TMCMarlin : public TMC, public TMCStorage { #endif #if HAS_LCD_MENU - inline void refresh_stepper_current() { rms_current(this->val_mA); } + void refresh_stepper_current() { rms_current(this->val_mA); } #if ENABLED(HYBRID_THRESHOLD) - inline void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } + void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } #endif #if USE_SENSORLESS - inline void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } + void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } #endif #endif @@ -167,24 +173,30 @@ class TMCMarlin : public TMC220 {} uint16_t rms_current() { return TMC2208Stepper::rms_current(); } - inline void rms_current(const uint16_t mA) { + void rms_current(const uint16_t mA) { this->val_mA = mA; TMC2208Stepper::rms_current(mA); } - inline void rms_current(const uint16_t mA, const float mult) { + void rms_current(const uint16_t mA, const float mult) { this->val_mA = mA; TMC2208Stepper::rms_current(mA, mult); } - inline uint16_t get_microstep_counter() { return TMC2208Stepper::MSCNT(); } + uint16_t get_microstep_counter() { return TMC2208Stepper::MSCNT(); } #if HAS_STEALTHCHOP - inline bool get_stealthChop() { return !this->en_spreadCycle(); } - inline bool get_stored_stealthChop() { return this->stored.stealthChop_enabled; } - inline void refresh_stepping_mode() { this->en_spreadCycle(!this->stored.stealthChop_enabled); } - inline void set_stealthChop(const bool stch) { this->stored.stealthChop_enabled = stch; refresh_stepping_mode(); } - inline bool toggle_stepping_mode() { set_stealthChop(!this->stored.stealthChop_enabled); return get_stealthChop(); } + bool get_stealthChop() { return !this->en_spreadCycle(); } + bool get_stored_stealthChop() { return this->stored.stealthChop_enabled; } + void refresh_stepping_mode() { this->en_spreadCycle(!this->stored.stealthChop_enabled); } + void set_stealthChop(const bool stch) { this->stored.stealthChop_enabled = stch; refresh_stepping_mode(); } + bool toggle_stepping_mode() { set_stealthChop(!this->stored.stealthChop_enabled); return get_stealthChop(); } #endif + void set_chopper_times(const chopper_timing_t &ct) { + TMC2208Stepper::toff(ct.toff); + TMC2208Stepper::hysteresis_end(ct.hend); + TMC2208Stepper::hysteresis_start(ct.hstrt); + } + #if ENABLED(HYBRID_THRESHOLD) uint32_t get_pwm_thrs() { return _tmc_thrs(this->microsteps(), this->TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); @@ -196,10 +208,10 @@ class TMCMarlin : public TMC220 #endif #if HAS_LCD_MENU - inline void refresh_stepper_current() { rms_current(this->val_mA); } + void refresh_stepper_current() { rms_current(this->val_mA); } #if ENABLED(HYBRID_THRESHOLD) - inline void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } + void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } #endif #endif }; @@ -215,24 +227,30 @@ class TMCMarlin : public TMC220 {} uint8_t get_address() { return slave_address; } uint16_t rms_current() { return TMC2209Stepper::rms_current(); } - inline void rms_current(const uint16_t mA) { + void rms_current(const uint16_t mA) { this->val_mA = mA; TMC2209Stepper::rms_current(mA); } - inline void rms_current(const uint16_t mA, const float mult) { + void rms_current(const uint16_t mA, const float mult) { this->val_mA = mA; TMC2209Stepper::rms_current(mA, mult); } - inline uint16_t get_microstep_counter() { return TMC2209Stepper::MSCNT(); } + uint16_t get_microstep_counter() { return TMC2209Stepper::MSCNT(); } #if HAS_STEALTHCHOP - inline bool get_stealthChop() { return !this->en_spreadCycle(); } - inline bool get_stored_stealthChop() { return this->stored.stealthChop_enabled; } - inline void refresh_stepping_mode() { this->en_spreadCycle(!this->stored.stealthChop_enabled); } - inline void set_stealthChop(const bool stch) { this->stored.stealthChop_enabled = stch; refresh_stepping_mode(); } - inline bool toggle_stepping_mode() { set_stealthChop(!this->stored.stealthChop_enabled); return get_stealthChop(); } + bool get_stealthChop() { return !this->en_spreadCycle(); } + bool get_stored_stealthChop() { return this->stored.stealthChop_enabled; } + void refresh_stepping_mode() { this->en_spreadCycle(!this->stored.stealthChop_enabled); } + void set_stealthChop(const bool stch) { this->stored.stealthChop_enabled = stch; refresh_stepping_mode(); } + bool toggle_stepping_mode() { set_stealthChop(!this->stored.stealthChop_enabled); return get_stealthChop(); } #endif + void set_chopper_times(const chopper_timing_t &ct) { + TMC2209Stepper::toff(ct.toff); + TMC2209Stepper::hysteresis_end(ct.hend); + TMC2209Stepper::hysteresis_start(ct.hstrt); + } + #if ENABLED(HYBRID_THRESHOLD) uint32_t get_pwm_thrs() { return _tmc_thrs(this->microsteps(), this->TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); @@ -243,7 +261,7 @@ class TMCMarlin : public TMC220 } #endif #if USE_SENSORLESS - inline int16_t homing_threshold() { return TMC2209Stepper::SGTHRS(); } + int16_t homing_threshold() { return TMC2209Stepper::SGTHRS(); } void homing_threshold(int16_t sgt_val) { sgt_val = (int16_t)constrain(sgt_val, sgt_min, sgt_max); TMC2209Stepper::SGTHRS(sgt_val); @@ -252,13 +270,13 @@ class TMCMarlin : public TMC220 #endif #if HAS_LCD_MENU - inline void refresh_stepper_current() { rms_current(this->val_mA); } + void refresh_stepper_current() { rms_current(this->val_mA); } #if ENABLED(HYBRID_THRESHOLD) - inline void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } + void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } #endif #if USE_SENSORLESS - inline void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } + void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } #endif #endif @@ -275,15 +293,21 @@ class TMCMarlin : public TMC266 TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t) : TMC2660Stepper(CS, RS, pinMOSI, pinMISO, pinSCK) {} - inline uint16_t rms_current() { return TMC2660Stepper::rms_current(); } - inline void rms_current(const uint16_t mA) { + uint16_t rms_current() { return TMC2660Stepper::rms_current(); } + void rms_current(const uint16_t mA) { this->val_mA = mA; TMC2660Stepper::rms_current(mA); } - inline uint16_t get_microstep_counter() { return TMC2660Stepper::mstep(); } + uint16_t get_microstep_counter() { return TMC2660Stepper::mstep(); } + + void set_chopper_times(const chopper_timing_t &ct) { + TMC2660Stepper::toff(ct.toff); + TMC2660Stepper::hysteresis_end(ct.hend); + TMC2660Stepper::hysteresis_start(ct.hstrt); + } #if USE_SENSORLESS - inline int16_t homing_threshold() { return TMC2660Stepper::sgt(); } + int16_t homing_threshold() { return TMC2660Stepper::sgt(); } void homing_threshold(int16_t sgt_val) { sgt_val = (int16_t)constrain(sgt_val, sgt_min, sgt_max); TMC2660Stepper::sgt(sgt_val); @@ -292,10 +316,10 @@ class TMCMarlin : public TMC266 #endif #if HAS_LCD_MENU - inline void refresh_stepper_current() { rms_current(this->val_mA); } + void refresh_stepper_current() { rms_current(this->val_mA); } #if USE_SENSORLESS - inline void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } + void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } #endif #endif diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index 788389ed61b7c..92d2210645cd5 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -63,16 +63,18 @@ void GcodeSuite::M906() { LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(axis_codes[i])) { report = false; switch (i) { - case X_AXIS: - #if AXIS_IS_TMC(X) - if (index < 0 || index == 0) TMC_SET_CURRENT(X); - #endif - #if AXIS_IS_TMC(X2) - if (index < 0 || index == 1) TMC_SET_CURRENT(X2); - #endif - break; + #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) + case X_AXIS: + #if AXIS_IS_TMC(X) + if (index < 0 || index == 0) TMC_SET_CURRENT(X); + #endif + #if AXIS_IS_TMC(X2) + if (index < 0 || index == 1) TMC_SET_CURRENT(X2); + #endif + break; + #endif - #if HAS_Y_AXIS + #if AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) case Y_AXIS: #if AXIS_IS_TMC(Y) if (index < 0 || index == 0) TMC_SET_CURRENT(Y); @@ -83,7 +85,7 @@ void GcodeSuite::M906() { break; #endif - #if HAS_Z_AXIS + #if AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) case Z_AXIS: #if AXIS_IS_TMC(Z) if (index < 0 || index == 0) TMC_SET_CURRENT(Z); @@ -110,7 +112,7 @@ void GcodeSuite::M906() { case K_AXIS: TMC_SET_CURRENT(K); break; #endif - #if E_STEPPERS + #if AXIS_IS_TMC(E0) || AXIS_IS_TMC(E1) || AXIS_IS_TMC(E2) || AXIS_IS_TMC(E3) || AXIS_IS_TMC(E4) || AXIS_IS_TMC(E5) || AXIS_IS_TMC(E6) || AXIS_IS_TMC(E7) case E_AXIS: { const int8_t eindex = get_target_e_stepper_from_command(-2); #if AXIS_IS_TMC(E0) diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 37dd9479aba3d..6aeb9c3d9dfec 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -264,14 +264,28 @@ LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(axis_codes[i])) { report = false; switch (i) { - case X_AXIS: - TERN_(X_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_PWMTHRS(X,X)); - TERN_(X2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_PWMTHRS(X,X2)); - break; - case Y_AXIS: - TERN_(Y_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_PWMTHRS(Y,Y)); - TERN_(Y2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_PWMTHRS(Y,Y2)); - break; + #if X_HAS_STEALTHCHOP || X2_HAS_STEALTHCHOP + case X_AXIS: + TERN_(X_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_PWMTHRS(X,X)); + TERN_(X2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_PWMTHRS(X,X2)); + break; + #endif + + #if Y_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP + case Y_AXIS: + TERN_(Y_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_PWMTHRS(Y,Y)); + TERN_(Y2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_PWMTHRS(Y,Y2)); + break; + #endif + + #if Z_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP || Z3_HAS_STEALTHCHOP || Z4_HAS_STEALTHCHOP + case Z_AXIS: + TERN_(Z_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_PWMTHRS(Z,Z)); + TERN_(Z2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_PWMTHRS(Z,Z2)); + TERN_(Z3_HAS_STEALTHCHOP, if (index < 0 || index == 2) TMC_SET_PWMTHRS(Z,Z3)); + TERN_(Z4_HAS_STEALTHCHOP, if (index < 0 || index == 3) TMC_SET_PWMTHRS(Z,Z4)); + break; + #endif #if I_HAS_STEALTHCHOP case I_AXIS: TMC_SET_PWMTHRS(I,I); break; @@ -283,13 +297,7 @@ case K_AXIS: TMC_SET_PWMTHRS(K,K); break; #endif - case Z_AXIS: - TERN_(Z_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_PWMTHRS(Z,Z)); - TERN_(Z2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_PWMTHRS(Z,Z2)); - TERN_(Z3_HAS_STEALTHCHOP, if (index < 0 || index == 2) TMC_SET_PWMTHRS(Z,Z3)); - TERN_(Z4_HAS_STEALTHCHOP, if (index < 0 || index == 3) TMC_SET_PWMTHRS(Z,Z4)); - break; - #if E_STEPPERS + #if E0_HAS_STEALTHCHOP || E1_HAS_STEALTHCHOP || E2_HAS_STEALTHCHOP || E3_HAS_STEALTHCHOP || E4_HAS_STEALTHCHOP || E5_HAS_STEALTHCHOP || E6_HAS_STEALTHCHOP || E7_HAS_STEALTHCHOP case E_AXIS: { const int8_t eindex = get_target_e_stepper_from_command(-2); TERN_(E0_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 0) TMC_SET_PWMTHRS_E(0)); diff --git a/Marlin/src/gcode/feature/trinamic/M919.cpp b/Marlin/src/gcode/feature/trinamic/M919.cpp new file mode 100644 index 0000000000000..4dce28f0ae7de --- /dev/null +++ b/Marlin/src/gcode/feature/trinamic/M919.cpp @@ -0,0 +1,266 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfig.h" + +#if HAS_TRINAMIC_CONFIG + +#if AXIS_COLLISION('I') + #error "M919 parameter collision with axis name." +#endif + +#include "../../gcode.h" +#include "../../../feature/tmc_util.h" +#include "../../../module/stepper/indirection.h" + +#define DEBUG_OUT ENABLED(MARLIN_DEV_MODE) +#include "../../../core/debug_out.h" + +template +static void tmc_print_chopper_time(TMC &st) { + st.printLabel(); + SERIAL_ECHOLNPGM(" chopper .toff: ", st.toff(), + " .hend: ", st.hysteresis_end(), + " .hstrt: ", st.hysteresis_start()); +} + +/** + * M919: Set TMC stepper driver chopper times + * + * Parameters: + * XYZ...E - Selected axes + * I[index] - Axis sub-index (Omit for all XYZ steppers, 1 for X2, Y2, Z2; 2 for Z3; 3 for Z4) + * T[index] - Extruder index (Zero-based. Omit for all extruders.) + * O - time-off [ 1..15] + * P - hysteresis_end [-3..12] + * S - hysteresis_start [ 1...8] + * + * With no parameters report chopper times for all axes + */ +void GcodeSuite::M919() { + bool err = false; + + int8_t toff = int8_t(parser.intval('O', -127)); + if (toff != -127) { + if (WITHIN(toff, 1, 15)) + DEBUG_ECHOLNPGM(".toff: ", toff); + else { + SERIAL_ECHOLNPGM("?O out of range (1..15)"); + err = true; + } + } + + int8_t hend = int8_t(parser.intval('P', -127)); + if (hend != -127) { + if (WITHIN(hend, -3, 12)) + DEBUG_ECHOLNPGM(".hend: ", hend); + else { + SERIAL_ECHOLNPGM("?P out of range (-3..12)"); + err = true; + } + } + + int8_t hstrt = int8_t(parser.intval('S', -127)); + if (hstrt != -127) { + if (WITHIN(hstrt, 1, 8)) + DEBUG_ECHOLNPGM(".hstrt: ", hstrt); + else { + SERIAL_ECHOLNPGM("?S out of range (1..8)"); + err = true; + } + } + + if (err) return; + + #if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) + const int8_t index = parser.byteval('I'); + #else + constexpr int8_t index = -1; + #endif + + auto make_chopper_timing = [](chopper_timing_t bct, const int8_t toff, const int8_t hend, const int8_t hstrt) { + chopper_timing_t uct = bct; + if (toff != -127) uct.toff = toff; + if (hend != -127) uct.hend = hend; + if (hstrt != -127) uct.hstrt = hstrt; + return uct; + }; + + #define TMC_SET_CHOPPER_TIME(Q) stepper##Q.set_chopper_times(make_chopper_timing(CHOPPER_TIMING_##Q, toff, hend, hstrt)) + + #if AXIS_IS_TMC(E0) || AXIS_IS_TMC(E1) || AXIS_IS_TMC(E2) || AXIS_IS_TMC(E3) || AXIS_IS_TMC(E4) || AXIS_IS_TMC(E5) || AXIS_IS_TMC(E6) || AXIS_IS_TMC(E7) + #define HAS_E_CHOPPER 1 + int8_t eindex = -1; + #endif + bool report = true; + LOOP_LOGICAL_AXES(i) if (parser.seen_test(axis_codes[i])) { + report = false; + + // Get the chopper timing for the specified axis and index + switch (i) { + default: // A specified axis isn't Trinamic + SERIAL_ECHOLNPGM("?Axis ", AS_CHAR(axis_codes[i]), " has no TMC drivers."); + break; + + #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) + case X_AXIS: + #if AXIS_IS_TMC(X) + if (index <= 0) TMC_SET_CHOPPER_TIME(X); + #endif + #if AXIS_IS_TMC(X2) + if (index < 0 || index == 1) TMC_SET_CHOPPER_TIME(X2); + #endif + break; + #endif + + #if AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) + case Y_AXIS: + #if AXIS_IS_TMC(Y) + if (index <= 0) TMC_SET_CHOPPER_TIME(Y); + #endif + #if AXIS_IS_TMC(Y2) + if (index < 0 || index == 1) TMC_SET_CHOPPER_TIME(Y2); + #endif + break; + #endif + + #if AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) + case Z_AXIS: + #if AXIS_IS_TMC(Z) + if (index <= 0) TMC_SET_CHOPPER_TIME(Z); + #endif + #if AXIS_IS_TMC(Z2) + if (index < 0 || index == 1) TMC_SET_CHOPPER_TIME(Z2); + #endif + #if AXIS_IS_TMC(Z3) + if (index < 0 || index == 2) TMC_SET_CHOPPER_TIME(Z3); + #endif + #if AXIS_IS_TMC(Z4) + if (index < 0 || index == 3) TMC_SET_CHOPPER_TIME(Z4); + #endif + break; + #endif + + #if AXIS_IS_TMC(I) + case I_AXIS: TMC_SET_CHOPPER_TIME(I); break; + #endif + #if AXIS_IS_TMC(J) + case J_AXIS: TMC_SET_CHOPPER_TIME(J); break; + #endif + #if AXIS_IS_TMC(K) + case K_AXIS: TMC_SET_CHOPPER_TIME(K); break; + #endif + + #if HAS_E_CHOPPER + case E_AXIS: { + #if AXIS_IS_TMC(E0) + if (eindex <= 0) TMC_SET_CHOPPER_TIME(E0); + #endif + #if AXIS_IS_TMC(E1) + if (eindex < 0 || eindex == 1) TMC_SET_CHOPPER_TIME(E1); + #endif + #if AXIS_IS_TMC(E2) + if (eindex < 0 || eindex == 2) TMC_SET_CHOPPER_TIME(E2); + #endif + #if AXIS_IS_TMC(E3) + if (eindex < 0 || eindex == 3) TMC_SET_CHOPPER_TIME(E3); + #endif + #if AXIS_IS_TMC(E4) + if (eindex < 0 || eindex == 4) TMC_SET_CHOPPER_TIME(E4); + #endif + #if AXIS_IS_TMC(E5) + if (eindex < 0 || eindex == 5) TMC_SET_CHOPPER_TIME(E5); + #endif + #if AXIS_IS_TMC(E6) + if (eindex < 0 || eindex == 6) TMC_SET_CHOPPER_TIME(E6); + #endif + #if AXIS_IS_TMC(E7) + if (eindex < 0 || eindex == 7) TMC_SET_CHOPPER_TIME(E7); + #endif + } break; + #endif + } + } + + if (report) { + #define TMC_SAY_CHOPPER_TIME(Q) tmc_print_chopper_time(stepper##Q) + #if AXIS_IS_TMC(X) + TMC_SAY_CHOPPER_TIME(X); + #endif + #if AXIS_IS_TMC(X2) + TMC_SAY_CHOPPER_TIME(X2); + #endif + #if AXIS_IS_TMC(Y) + TMC_SAY_CHOPPER_TIME(Y); + #endif + #if AXIS_IS_TMC(Y2) + TMC_SAY_CHOPPER_TIME(Y2); + #endif + #if AXIS_IS_TMC(Z) + TMC_SAY_CHOPPER_TIME(Z); + #endif + #if AXIS_IS_TMC(Z2) + TMC_SAY_CHOPPER_TIME(Z2); + #endif + #if AXIS_IS_TMC(Z3) + TMC_SAY_CHOPPER_TIME(Z3); + #endif + #if AXIS_IS_TMC(Z4) + TMC_SAY_CHOPPER_TIME(Z4); + #endif + #if AXIS_IS_TMC(I) + TMC_SAY_CHOPPER_TIME(I); + #endif + #if AXIS_IS_TMC(J) + TMC_SAY_CHOPPER_TIME(J); + #endif + #if AXIS_IS_TMC(K) + TMC_SAY_CHOPPER_TIME(K); + #endif + #if AXIS_IS_TMC(E0) + TMC_SAY_CHOPPER_TIME(E0); + #endif + #if AXIS_IS_TMC(E1) + TMC_SAY_CHOPPER_TIME(E1); + #endif + #if AXIS_IS_TMC(E2) + TMC_SAY_CHOPPER_TIME(E2); + #endif + #if AXIS_IS_TMC(E3) + TMC_SAY_CHOPPER_TIME(E3); + #endif + #if AXIS_IS_TMC(E4) + TMC_SAY_CHOPPER_TIME(E4); + #endif + #if AXIS_IS_TMC(E5) + TMC_SAY_CHOPPER_TIME(E5); + #endif + #if AXIS_IS_TMC(E6) + TMC_SAY_CHOPPER_TIME(E6); + #endif + #if AXIS_IS_TMC(E7) + TMC_SAY_CHOPPER_TIME(E7); + #endif + } +} + +#endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 2f031b3b74f63..c365f8a67b426 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -971,6 +971,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #if USE_SENSORLESS case 914: M914(); break; // M914: Set StallGuard sensitivity. #endif + case 919: M919(); break; // M919: Set stepper Chopper Times #endif #if HAS_L64XX diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 92c1459a326c9..78dd0bc680078 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -296,6 +296,7 @@ * M916 - L6470 tuning: Increase KVAL_HOLD until thermal warning. (Requires at least one _DRIVER_TYPE L6470) * M917 - L6470 tuning: Find minimum current thresholds. (Requires at least one _DRIVER_TYPE L6470) * M918 - L6470 tuning: Increase speed until max or error. (Requires at least one _DRIVER_TYPE L6470) + * M919 - Get or Set motor Chopper Times (time_off, hysteresis_end, hysteresis_start) using axis codes XYZE, etc. If no parameters are given, report. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660) * M951 - Set Magnetic Parking Extruder parameters. (Requires MAGNETIC_PARKING_EXTRUDER) * M3426 - Read MCP3426 ADC over I2C. (Requires HAS_MCP3426_ADC) * M7219 - Control Max7219 Matrix LEDs. (Requires MAX7219_GCODE) @@ -1140,6 +1141,7 @@ class GcodeSuite { static void M914(); static void M914_report(const bool forReplay=true); #endif + static void M919(); #endif #if HAS_L64XX diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 9ed25a611473e..477309ad81947 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2395,28 +2395,28 @@ // ADC Temp Sensors (Thermistor or Thermocouple with amplifier ADC interface) // #define HAS_ADC_TEST(P) (PIN_EXISTS(TEMP_##P) && TEMP_SENSOR_##P != 0 && NONE(TEMP_SENSOR_##P##_IS_MAX_TC, TEMP_SENSOR_##P##_IS_DUMMY)) -#if HAS_ADC_TEST(0) +#if HOTENDS > 0 && HAS_ADC_TEST(0) #define HAS_TEMP_ADC_0 1 #endif -#if HAS_ADC_TEST(1) +#if HOTENDS > 1 && HAS_ADC_TEST(1) #define HAS_TEMP_ADC_1 1 #endif -#if HAS_ADC_TEST(2) +#if HOTENDS > 2 && HAS_ADC_TEST(2) #define HAS_TEMP_ADC_2 1 #endif -#if HAS_ADC_TEST(3) +#if HOTENDS > 3 && HAS_ADC_TEST(3) #define HAS_TEMP_ADC_3 1 #endif -#if HAS_ADC_TEST(4) +#if HOTENDS > 4 && HAS_ADC_TEST(4) #define HAS_TEMP_ADC_4 1 #endif -#if HAS_ADC_TEST(5) +#if HOTENDS > 5 && HAS_ADC_TEST(5) #define HAS_TEMP_ADC_5 1 #endif -#if HAS_ADC_TEST(6) +#if HOTENDS > 6 && HAS_ADC_TEST(6) #define HAS_TEMP_ADC_6 1 #endif -#if HAS_ADC_TEST(7) +#if HOTENDS > 7 && HAS_ADC_TEST(7) #define HAS_TEMP_ADC_7 1 #endif #if HAS_ADC_TEST(BED) diff --git a/ini/features.ini b/ini/features.ini index 5f69fcca25d50..eb3be400b109b 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -18,7 +18,7 @@ POSTMORTEM_DEBUGGING = src_filter=+ + + + + + src_filter=+ + + + + + HAS_STEALTHCHOP = src_filter=+ SR_LCD_3W_NL = SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip HAS_MOTOR_CURRENT_I2C = SlowSoftI2CMaster diff --git a/platformio.ini b/platformio.ini index 74ac012f19761..e1db73a4bd120 100644 --- a/platformio.ini +++ b/platformio.ini @@ -204,6 +204,7 @@ default_src_filter = + - - + - - - + - - - - From cb96f9d6c0f61e7a1d17b8b1983173035379491c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Johannes=20H=C3=B6rmann?= Date: Sun, 2 Jan 2022 06:46:55 +0100 Subject: [PATCH 230/273] =?UTF-8?q?=F0=9F=94=A8=20Upload=20to=20Optiboot?= =?UTF-8?q?=20at=20115200=20(#23403)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/avr.ini | 45 ++++++++++----------------------------------- ini/teensy.ini | 18 ++++++++++++++++++ 2 files changed, 28 insertions(+), 35 deletions(-) diff --git a/ini/avr.ini b/ini/avr.ini index e4d64de712a1e..92dd8f0cdb424 100644 --- a/ini/avr.ini +++ b/ini/avr.ini @@ -106,14 +106,6 @@ extends = common_avr8 board = sanguino_atmega1284p board_upload.maximum_size = 126976 -# -# Melzi and clones (ATmega1284p) -# -[env:melzi] -platform = atmelavr -extends = env:sanguino1284p -upload_speed = 57600 - # # Sanguinololu (ATmega1284p stock bootloader with tuned flags) # @@ -123,15 +115,21 @@ build_flags = ${common.build_flags} -fno-tree-scev-cprop -fno-split-wide-types - [env:sanguino1284p_optimized] platform = atmelavr -extends = env:melzi +extends = env:sanguino1284p build_flags = ${tuned_1284p.build_flags} # -# Melzi and clones (alias for sanguino1284p_optimized) +# Melzi and clones (ATmega1284p) # +[env:melzi] +platform = atmelavr +extends = env:sanguino1284p +upload_speed = 57600 + [env:melzi_optimized] -platform = atmelavr -extends = env:sanguino1284p_optimized +platform = atmelavr +extends = env:sanguino1284p_optimized +upload_speed = 57600 # # Melzi and clones (Optiboot bootloader) @@ -150,26 +148,3 @@ board_upload.maximum_size = 130048 platform = atmelavr extends = env:melzi_optiboot build_flags = ${tuned_1284p.build_flags} - -# -# AT90USB1286 boards using CDC bootloader -# - BRAINWAVE -# - BRAINWAVE_PRO -# - SAV_MKI -# - TEENSYLU -# -[env:at90usb1286_cdc] -platform = teensy -extends = common_avr8 -board = marlin_at90usb1286 -lib_ignore = ${env:common_avr8.lib_ignore}, Teensy_ADC, NativeEthernet - -# -# AT90USB1286 boards using DFU bootloader -# - Printrboard -# - Printrboard Rev.F -# - ? 5DPRINT ? -# -[env:at90usb1286_dfu] -platform = teensy -extends = env:at90usb1286_cdc diff --git a/ini/teensy.ini b/ini/teensy.ini index ef1ad766bcbb9..f3e5fd026092e 100644 --- a/ini/teensy.ini +++ b/ini/teensy.ini @@ -9,6 +9,24 @@ # # ################################# +# +# AT90USB1286 boards using CDC bootloader +# e.g., BRAINWAVE, BRAINWAVE_PRO, SAV_MKI, TEENSYLU +# +[env:at90usb1286_cdc] +platform = teensy +extends = common_avr8 +board = marlin_at90usb1286 +lib_ignore = ${env:common_avr8.lib_ignore}, Teensy_ADC, NativeEthernet + +# +# AT90USB1286 boards using DFU bootloader +# e.g., Printrboard, Printrboard Rev.F, 5DPRINT +# +[env:at90usb1286_dfu] +platform = teensy +extends = env:at90usb1286_cdc + # # Teensy++ 2.0 # From e37fe8566787cc006f70babb39e84226020d5e70 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sun, 2 Jan 2022 00:19:10 -0800 Subject: [PATCH 231/273] =?UTF-8?q?=F0=9F=94=A7=20Update=20deprecated=20au?= =?UTF-8?q?to=5Fbuild.py=20(#23427)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/vscode/auto_build.py | 235 +++++++++++++-------------- 1 file changed, 110 insertions(+), 125 deletions(-) diff --git a/buildroot/share/vscode/auto_build.py b/buildroot/share/vscode/auto_build.py index ac8432729f0a0..5bd769478e0ec 100644 --- a/buildroot/share/vscode/auto_build.py +++ b/buildroot/share/vscode/auto_build.py @@ -72,7 +72,7 @@ from __future__ import print_function from __future__ import division -import sys,os +import sys,os,re pwd = os.getcwd() # make sure we're executing from the correct directory level pwd = pwd.replace('\\', '/') @@ -123,7 +123,7 @@ # ########################################################################################## -def get_answer(board_name, cpu_label_txt, cpu_a_txt, cpu_b_txt): +def get_answer(board_name, question_txt, options, default_value=1): if python_ver == 2: import Tkinter as tk @@ -151,10 +151,10 @@ def disable_event(): root_get_answer.protocol("WM_DELETE_WINDOW", disable_event) root_get_answer.resizable(False, False) - root_get_answer.radio_state = 1 # declare variables used by TK and enable + root_get_answer.radio_state = default_value # declare variables used by TK and enable global get_answer_val - get_answer_val = 2 # return get_answer_val, set default to match radio_state default + get_answer_val = default_value # return get_answer_val, set default to match radio_state default radio_state = tk.IntVar() radio_state.set(get_answer_val) @@ -162,35 +162,27 @@ def disable_event(): l1 = tk.Label(text=board_name, fg="light green", bg="dark green", font="default 14 bold").grid(row=0, columnspan=2, sticky='EW', ipadx=2, ipady=2) - l2 = tk.Label(text=cpu_label_txt).grid(row=1, pady=4, columnspan=2, sticky='EW') - - b4 = tk.Radiobutton( - text=cpu_a_txt, - fg="black", - bg="lightgray", - relief=tk.SUNKEN, - selectcolor="green", - variable=radio_state, - value=1, - indicatoron=0, - command=CPU_exit_3 - ).grid(row=2, pady=1, ipady=2, ipadx=10, columnspan=2) - - b5 = tk.Radiobutton( - text=cpu_b_txt, - fg="black", - bg="lightgray", - relief=tk.SUNKEN, - selectcolor="green", - variable=radio_state, - value=2, - indicatoron=0, - command=CPU_exit_3 - ).grid(row=3, pady=1, ipady=2, ipadx=10, columnspan=2) # use same variable but inverted so they will track - - b6 = tk.Button(text="Cancel", fg="red", command=kill_session).grid(row=4, column=0, padx=4, pady=4, ipadx=2, ipady=2) - - b7 = tk.Button(text="Continue", fg="green", command=got_answer).grid(row=4, column=1, padx=4, pady=4, ipadx=2, ipady=2) + l2 = tk.Label(text=question_txt).grid(row=1, pady=4, columnspan=2, sticky='EW') + + buttons = [] + + for index, val in enumerate(options): + buttons.append( + tk.Radiobutton( + text=val, + fg="black", + bg="lightgray", + relief=tk.SUNKEN, + selectcolor="green", + variable=radio_state, + value=index + 1, + indicatoron=0, + command=CPU_exit_3 + ).grid(row=index + 2, pady=1, ipady=2, ipadx=10, columnspan=2)) + + b6 = tk.Button(text="Cancel", fg="red", command=kill_session).grid(row=(2 + len(options)), column=0, padx=4, pady=4, ipadx=2, ipady=2) + + b7 = tk.Button(text="Continue", fg="green", command=got_answer).grid(row=(2 + len(options)), column=1, padx=4, pady=4, ipadx=2, ipady=2) def got_answer_(): root_get_answer.destroy() @@ -485,6 +477,11 @@ def get_env_from_line(line, start_position): return env, next_position +def invalid_board(): + print('ERROR - invalid board') + print(board_name) + raise SystemExit(0) # quit if unable to find board + # scan pins.h for board name and return the environment(s) found def get_starting_env(board_name_full, version): # get environment starting point @@ -496,48 +493,26 @@ def get_starting_env(board_name_full, version): with open(path, 'r') as myfile: pins_h = myfile.read() - env_A = '' - env_B = '' - env_C = '' - board_name = board_name_full[6:] # only use the part after "BOARD_" since we're searching the pins.h file pins_h = pins_h.split('\n') - environment = '' - board_line = '' - cpu_A = '' - cpu_B = '' - i = 0 list_start_found = False - for lines in pins_h: - i = i + 1 # i is always one ahead of the index into pins_h - if 0 < lines.find("Unknown MOTHERBOARD value set in Configuration.h"): - break # no more - if 0 < lines.find('1280'): + possible_envs = None + for i, line in enumerate(pins_h): + if 0 < line.find("Unknown MOTHERBOARD value set in Configuration.h"): + invalid_board(); + if list_start_found == False and 0 < line.find('1280'): list_start_found = True - if list_start_found == False: # skip lines until find start of CPU list + elif list_start_found == False: # skip lines until find start of CPU list continue - board = lines.find(board_name) - comment_start = lines.find('// ') - cpu_A_loc = comment_start - cpu_B_loc = 0 - if board > 0: # need to look at the next line for environment info - cpu_line = pins_h[i] - comment_start = cpu_line.find('// ') - env_A, next_position = get_env_from_line(cpu_line, comment_start) # get name of environment & start of search for next - env_B, next_position = get_env_from_line(cpu_line, next_position) # get next environment, if it exists - env_C, next_position = get_env_from_line(cpu_line, next_position) # get next environment, if it exists - break - return env_A, env_B, env_C - -# Scan input string for CPUs that users may need to select from -# return: CPU name -def get_CPU_name(environment): - CPU_list = ('1280', '2560', '644', '1284', 'LPC1768', 'DUE') - CPU_name = '' - for CPU in CPU_list: - if 0 < environment.find(CPU): - return CPU + # Use a regex to find the board. Make sure it is surrounded by separators so the full boardname + # will be matched, even if multiple exist in a single MB macro. This avoids problems with boards + # such as MALYAN_M200 and MALYAN_M200_V2 where one board is a substring of the other. + if re.search(r'MB.*[\(, ]' + board_name + r'[, \)]', line): + # need to look at the next line for environment info + possible_envs = re.findall(r'env:([^ ]+)', pins_h[i + 1]) + break + return possible_envs # get environment to be used for the build @@ -549,71 +524,81 @@ def no_environment(): print(board_name) raise SystemExit(0) # no environment so quit - def invalid_board(): - print('ERROR - invalid board') - print(board_name) - raise SystemExit(0) # quit if unable to find board + possible_envs = get_starting_env(board_name, ver_Marlin) - CPU_question = (('1280', '2560', '1280 or 2560 CPU?'), ('644', '1284', '644 or 1284 CPU?')) + if not possible_envs: + no_environment() - if 0 < board_name.find('MELZI'): - get_answer( - board_name, " Which flavor of Melzi? ", "Melzi (Optiboot bootloader)", "Melzi " - ) + # Proceed to ask questions based on the available environments to filter down to a smaller list. + # If more then one remains after this filtering the user will be prompted to choose between + # all remaining options. + + # Filter selection based on CPU choice + CPU_questions = [ + {'options':['1280', '2560'], 'text':'1280 or 2560 CPU?', 'default':2}, + {'options':['644', '1284'], 'text':'644 or 1284 CPU?', 'default':2}, + {'options':['STM32F103RC', 'STM32F103RE'], 'text':'MCU Type?', 'default':1}] + + for question in CPU_questions: + if any(question['options'][0] in env for env in possible_envs) and any(question['options'][1] in env for env in possible_envs): + get_answer(board_name, question['text'], [question['options'][0], question['options'][1]], question['default']) + possible_envs = [env for env in possible_envs if question['options'][get_answer_val - 1] in env] + + # Choose which STM32 framework to use, if both are available + if [env for env in possible_envs if '_maple' in env] and [env for env in possible_envs if '_maple' not in env]: + get_answer(board_name, 'Which STM32 Framework should be used?', ['ST STM32 (Preferred)', 'Maple (Deprecated)']) if 1 == get_answer_val: - target_env = 'melzi_optiboot' + possible_envs = [env for env in possible_envs if '_maple' not in env] else: - target_env = 'melzi' - else: - env_A, env_B, env_C = get_starting_env(board_name, ver_Marlin) + possible_envs = [env for env in possible_envs if '_maple' in env] - if env_A == '': - no_environment() - if env_B == '': - return env_A # only one environment so finished + # Both USB and non-USB STM32 options exist, filter based on these + if any('STM32F103R' in env for env in possible_envs) and any('_USB' in env for env in possible_envs) and any('_USB' not in env for env in possible_envs): + get_answer(board_name, 'USB Support?', ['USB', 'No USB']) + if 1 == get_answer_val: + possible_envs = [env for env in possible_envs if '_USB' in env] + else: + possible_envs = [env for env in possible_envs if '_USB' not in env] - CPU_A = get_CPU_name(env_A) - CPU_B = get_CPU_name(env_B) + if not possible_envs: + no_environment() + if len(possible_envs) == 1: + return possible_envs[0] # only one environment so finished - for item in CPU_question: - if CPU_A == item[0]: - get_answer(board_name, item[2], item[0], item[1]) - if 2 == get_answer_val: - target_env = env_B - else: - target_env = env_A - return target_env + target_env = None - if env_A == 'LPC1768': - if build_type == 'traceback' or (build_type == 'clean' and get_build_last() == 'LPC1768_debug_and_upload'): - target_env = 'LPC1768_debug_and_upload' - else: - target_env = 'LPC1768' - elif env_A == 'DUE': - target_env = 'DUE' - if build_type == 'traceback' or (build_type == 'clean' and get_build_last() == 'DUE_debug'): - target_env = 'DUE_debug' - elif env_B == 'DUE_USB': - get_answer(board_name, 'DUE Download Port?', '(Native) USB port', 'Programming port') - if 1 == get_answer_val: - target_env = 'DUE_USB' - else: - target_env = 'DUE' - elif env_A == 'STM32F103RC_btt' or env_A == 'STM32F103RE_btt': - if env_A == 'STM32F103RE_btt': - get_answer(board_name, 'MCU Type?', 'STM32F103RC', 'STM32F103RE') - if 1 == get_answer_val: - env_A = 'STM32F103RC_btt' - target_env = env_A - if env_A == 'STM32F103RC_btt': - get_answer(board_name, 'RCT6 Flash Size?', '512K', '256K') - if 1 == get_answer_val: - target_env += '_512K' - get_answer(board_name, 'USB Support?', 'USB', 'No USB') - if 1 == get_answer_val: - target_env += '_USB' + # A few environments require special behavior + if 'LPC1768' in possible_envs: + if build_type == 'traceback' or (build_type == 'clean' and get_build_last() == 'LPC1768_debug_and_upload'): + target_env = 'LPC1768_debug_and_upload' else: - invalid_board() + target_env = 'LPC1768' + elif 'DUE' in possible_envs: + target_env = 'DUE' + if build_type == 'traceback' or (build_type == 'clean' and get_build_last() == 'DUE_debug'): + target_env = 'DUE_debug' + elif 'DUE_USB' in possible_envs: + get_answer(board_name, 'DUE Download Port?', ['(Native) USB port', 'Programming port']) + if 1 == get_answer_val: + target_env = 'DUE_USB' + else: + target_env = 'DUE' + else: + options = possible_envs + # Perform some substitutions for environment names which follow a consistent + # naming pattern and are very commonly used. This is fragile code, and replacements + # should only be made here for stable environments unlikely to change often. + for i, option in enumerate(options): + if 'melzi' in option: + options[i] = 'Melzi' + elif 'sanguino1284p' in option: + options[i] = 'sanguino1284p' + if 'optiboot' in option: + options[i] = options[i] + ' (Optiboot Bootloader)' + if 'optimized' in option: + options[i] = options[i] + ' (Optimized for Size)' + get_answer(board_name, 'Which environment?', options) + target_env = possible_envs[get_answer_val - 1] if build_type == 'traceback' and target_env != 'LPC1768_debug_and_upload' and target_env != 'DUE_debug' and Marlin_ver == 2: print("ERROR - this board isn't setup for traceback") From d007c1b835847ab21d5f9668300d5131713c84dc Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Sun, 2 Jan 2022 02:23:55 -0600 Subject: [PATCH 232/273] =?UTF-8?q?=F0=9F=94=A7=20Normal=20FET=20layout=20?= =?UTF-8?q?with=20Spindle/Laser=20(#23409)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/mega/pins_HJC2560C_REV2.h | 2 +- Marlin/src/pins/pins.h | 2 +- Marlin/src/pins/ramps/pins_TT_OSCAR.h | 2 +- Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h | 2 +- Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h index dcf25da070ff9..73d4bac472732 100644 --- a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h +++ b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h @@ -112,7 +112,7 @@ // // M3/M4/M5 - Spindle/Laser Control // -#if EITHER(SPINDLE_FEATURE, LASER_FEATURE) +#if HAS_CUTTER #define SPINDLE_DIR_PIN 16 #define SPINDLE_LASER_ENA_PIN 17 // Pin should have a pullup! #define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 0f0f42508db04..1cb9462de4874 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -45,7 +45,7 @@ #define FET_ORDER_EFF 1 #elif MB(RAMPS_13_EEF, RAMPS_14_EEF, RAMPS_PLUS_EEF, RAMPS_14_RE_ARM_EEF, RAMPS_SMART_EEF, RAMPS_DUO_EEF, RAMPS4DUE_EEF) #define FET_ORDER_EEF 1 -#elif MB(RAMPS_13_SF, RAMPS_14_SF, RAMPS_PLUS_SF, RAMPS_14_RE_ARM_SF, RAMPS_SMART_SF, RAMPS_DUO_SF, RAMPS4DUE_SF) || EITHER(SPINDLE_FEATURE, LASER_FEATURE) +#elif MB(RAMPS_13_SF, RAMPS_14_SF, RAMPS_PLUS_SF, RAMPS_14_RE_ARM_SF, RAMPS_SMART_SF, RAMPS_DUO_SF, RAMPS4DUE_SF) #define FET_ORDER_SF 1 #elif HAS_MULTI_HOTEND && TEMP_SENSOR_BED #define FET_ORDER_EEB 1 diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 01769fbff0cda..a07892914e166 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -226,7 +226,7 @@ // // M3/M4/M5 - Spindle/Laser Control // -#if EITHER(SPINDLE_FEATURE, LASER_FEATURE) && !PIN_EXISTS(SPINDLE_LASER_ENA) +#if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !NUM_SERVOS // Prefer the servo connector #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 02f4a6e985b6a..ba9cc350a8f73 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -135,7 +135,7 @@ #define LCD_BACKLIGHT_PIN 17 // LCD backlight LED #endif -#if NONE(SPINDLE_FEATURE, LASER_FEATURE) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(IS_ULTRA_LCD, IS_NEWPANEL) // try to use IO Header +#if !HAS_CUTTER && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(IS_ULTRA_LCD, IS_NEWPANEL) // try to use IO Header #define CASE_LIGHT_PIN 4 // Hardware PWM - see if IO Header is available #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 079d6dcccc1b9..4f5ed6c1b4ebd 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 @@ -253,7 +253,7 @@ #define FAN_PIN PB7 // Fan0 #endif -#if EITHER(SPINDLE_FEATURE, LASER_FEATURE) +#if HAS_CUTTER #ifndef SPINDLE_LASER_PWM_PIN #define SPINDLE_LASER_PWM_PIN PB5 #endif From 91909163ee0eb19920309a4ad9042d9240201fa4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 Jan 2022 09:22:06 -0600 Subject: [PATCH 233/273] =?UTF-8?q?=F0=9F=9A=A8=20Fix=20M906=20warning?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/L6470/M906.cpp | 28 +++++++++++++------------ 1 file changed, 15 insertions(+), 13 deletions(-) diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index ae4a46dce60e9..f55405b798ad3 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -246,16 +246,18 @@ void GcodeSuite::M906() { } switch (i) { - case X_AXIS: - #if AXIS_IS_L64XX(X) - if (index < 0 || index == 0) L6470_SET_KVAL_HOLD(X); - #endif - #if AXIS_IS_L64XX(X2) - if (index < 0 || index == 1) L6470_SET_KVAL_HOLD(X2); - #endif - break; - - #if HAS_Y_AXIS + #if AXIS_IS_L64XX(X) || AXIS_IS_L64XX(X2) + case X_AXIS: + #if AXIS_IS_L64XX(X) + if (index < 0 || index == 0) L6470_SET_KVAL_HOLD(X); + #endif + #if AXIS_IS_L64XX(X2) + if (index < 0 || index == 1) L6470_SET_KVAL_HOLD(X2); + #endif + break; + #endif + + #if AXIS_IS_L64XX(Y) || AXIS_IS_L64XX(Y2) case Y_AXIS: #if AXIS_IS_L64XX(Y) if (index < 0 || index == 0) L6470_SET_KVAL_HOLD(Y); @@ -266,7 +268,7 @@ void GcodeSuite::M906() { break; #endif - #if HAS_Z_AXIS + #if AXIS_IS_L64XX(Z) || AXIS_IS_L64XX(Z2) || AXIS_IS_L64XX(Z3) || AXIS_IS_L64XX(Z4) case Z_AXIS: #if AXIS_IS_L64XX(Z) if (index < 0 || index == 0) L6470_SET_KVAL_HOLD(Z); @@ -277,13 +279,13 @@ void GcodeSuite::M906() { #if AXIS_IS_L64XX(Z3) if (index < 0 || index == 2) L6470_SET_KVAL_HOLD(Z3); #endif - #if AXIS_DRIVER_TYPE_Z4(L6470) + #if AXIS_IS_L64XX(Z4) if (index < 0 || index == 3) L6470_SET_KVAL_HOLD(Z4); #endif break; #endif - #if E_STEPPERS + #if AXIS_IS_L64XX(E0) || AXIS_IS_L64XX(E1) || AXIS_IS_L64XX(E2) || AXIS_IS_L64XX(E3) || AXIS_IS_L64XX(E4) || AXIS_IS_L64XX(E5) || AXIS_IS_L64XX(E6) || AXIS_IS_L64XX(E7) case E_AXIS: { const int8_t eindex = get_target_e_stepper_from_command(-2); #if AXIS_IS_L64XX(E0) From e65c12cf96a226019a7456099078ee5cb03f9a49 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 Jan 2022 09:22:36 -0600 Subject: [PATCH 234/273] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20App?= =?UTF-8?q?ly=20axis=20conditionals?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/language.h | 6 +- Marlin/src/core/types.h | 16 ++-- Marlin/src/gcode/calibrate/G28.cpp | 12 +-- Marlin/src/gcode/calibrate/G425.cpp | 28 +++---- .../src/gcode/feature/trinamic/M911-M914.cpp | 8 +- Marlin/src/inc/Conditionals_LCD.h | 22 +++++- Marlin/src/inc/Conditionals_adv.h | 6 -- Marlin/src/inc/Conditionals_post.h | 44 +++++------ Marlin/src/inc/SanityCheck.h | 74 +++++++++---------- Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp | 6 +- Marlin/src/lcd/extui/nextion/nextion_tft.cpp | 17 ++--- Marlin/src/lcd/menu/menu_backlash.cpp | 6 +- Marlin/src/lcd/menu/menu_motion.cpp | 24 +++--- Marlin/src/libs/L64XX/L64XX_Marlin.cpp | 6 +- Marlin/src/module/endstops.cpp | 6 +- Marlin/src/module/motion.cpp | 30 ++++---- Marlin/src/module/motion.h | 18 ++--- Marlin/src/module/planner.cpp | 32 ++++---- Marlin/src/module/settings.cpp | 6 +- Marlin/src/module/stepper.cpp | 16 ++-- Marlin/src/module/stepper/indirection.h | 12 +-- Marlin/src/module/stepper/trinamic.h | 6 +- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 2 +- Marlin/src/pins/pins_postprocess.h | 16 ++-- Marlin/src/pins/rambo/pins_EINSY_RETRO.h | 10 +-- Marlin/src/pins/sam/pins_RURAMPS4D_11.h | 4 - Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 9 +-- Marlin/src/pins/sensitive_pins.h | 6 +- Marlin/src/pins/stm32f7/pins_REMRAM_V1.h | 3 +- 29 files changed, 220 insertions(+), 231 deletions(-) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 707296b3574be..c1f2e7e31c4d0 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -369,7 +369,7 @@ #define LCD_STR_E STR_E // Extra Axis and Endstop Names -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #if AXIS4_NAME == 'A' #define AXIS4_STR "A" #define STR_I_MIN "a_min" @@ -403,7 +403,7 @@ #define AXIS4_STR "" #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #if AXIS5_NAME == 'A' #define AXIS5_STR "A" #define STR_J_MIN "a_min" @@ -437,7 +437,7 @@ #define AXIS5_STR "" #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #if AXIS6_NAME == 'A' #define AXIS6_STR "A" #define STR_K_MIN "a_min" diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index d589abfc1adb5..e5d95d81ec798 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -98,10 +98,10 @@ enum AxisEnum : uint8_t { // A, B, and C are for DELTA, SCARA, etc. , A_AXIS = X_AXIS - #if LINEAR_AXES >= 2 + #if HAS_Y_AXIS , B_AXIS = Y_AXIS #endif - #if LINEAR_AXES >= 3 + #if HAS_Z_AXIS , C_AXIS = Z_AXIS #endif @@ -408,13 +408,13 @@ struct XYZval { FI void set(const T (&arr)[DISTINCT_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); } #endif #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS FI void set(const T px, const T py, const T pz, const T pi) { x = px; y = py; z = pz; i = pi; } #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; } #endif @@ -549,13 +549,13 @@ struct XYZEval { FI void set(const XYZval pxyz, const T pe) { set(pxyz); e = pe; } FI void set(LOGICAL_AXIS_ARGS(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, u = i, v = j, w = k); } #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS FI void set(const T px, const T py, const T pz, const T pi) { x = px; y = py; z = pz; i = pi; } #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; } #endif diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 8743c0d8951ca..421220e4106ab 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -441,15 +441,9 @@ void GcodeSuite::G28() { } #endif - #if LINEAR_AXES >= 4 - if (doI) homeaxis(I_AXIS); - #endif - #if LINEAR_AXES >= 5 - if (doJ) homeaxis(J_AXIS); - #endif - #if LINEAR_AXES >= 6 - if (doK) homeaxis(K_AXIS); - #endif + TERN_(HAS_I_AXIS, if (doI) homeaxis(I_AXIS)); + TERN_(HAS_J_AXIS, if (doJ) homeaxis(J_AXIS)); + TERN_(HAS_K_AXIS, if (doK) homeaxis(K_AXIS)); sync_plan_position(); diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 31e0bb2587396..9d630ba1e24b4 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -73,16 +73,16 @@ #if BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT) #define HAS_X_CENTER 1 #endif -#if HAS_Y_AXIS && BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK) +#if ALL(HAS_Y_AXIS, CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK) #define HAS_Y_CENTER 1 #endif -#if LINEAR_AXES >= 4 && BOTH(CALIBRATION_MEASURE_IMIN, CALIBRATION_MEASURE_IMAX) +#if ALL(HAS_I_AXIS, CALIBRATION_MEASURE_IMIN, CALIBRATION_MEASURE_IMAX) #define HAS_I_CENTER 1 #endif -#if LINEAR_AXES >= 5 && BOTH(CALIBRATION_MEASURE_JMIN, CALIBRATION_MEASURE_JMAX) +#if ALL(HAS_J_AXIS, CALIBRATION_MEASURE_JMIN, CALIBRATION_MEASURE_JMAX) #define HAS_J_CENTER 1 #endif -#if LINEAR_AXES >= 6 && BOTH(CALIBRATION_MEASURE_KMIN, CALIBRATION_MEASURE_KMAX) +#if ALL(HAS_K_AXIS, CALIBRATION_MEASURE_KMIN, CALIBRATION_MEASURE_KMAX) #define HAS_K_CENTER 1 #endif @@ -246,7 +246,7 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t case RIGHT: dir = -1; case LEFT: axis = X_AXIS; break; #endif - #if LINEAR_AXES >= 2 && AXIS_CAN_CALIBRATE(Y) + #if HAS_Y_AXIS && AXIS_CAN_CALIBRATE(Y) case BACK: dir = -1; case FRONT: axis = Y_AXIS; break; #endif @@ -258,15 +258,15 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t return; } #endif - #if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I) + #if HAS_I_AXIS && AXIS_CAN_CALIBRATE(I) case IMINIMUM: dir = -1; case IMAXIMUM: axis = I_AXIS; break; #endif - #if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J) + #if HAS_J_AXIS && AXIS_CAN_CALIBRATE(J) case JMINIMUM: dir = -1; case JMAXIMUM: axis = J_AXIS; break; #endif - #if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K) + #if HAS_K_AXIS && AXIS_CAN_CALIBRATE(K) case KMINIMUM: dir = -1; case KMAXIMUM: axis = K_AXIS; break; #endif @@ -370,7 +370,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM(" Back: ", m.obj_side[BACK]); #endif #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS #if ENABLED(CALIBRATION_MEASURE_IMIN) SERIAL_ECHOLNPGM(" " STR_I_MIN ": ", m.obj_side[IMINIMUM]); #endif @@ -378,7 +378,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM(" " STR_I_MAX ": ", m.obj_side[IMAXIMUM]); #endif #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS #if ENABLED(CALIBRATION_MEASURE_JMIN) SERIAL_ECHOLNPGM(" " STR_J_MIN ": ", m.obj_side[JMINIMUM]); #endif @@ -386,7 +386,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM(" " STR_J_MAX ": ", m.obj_side[JMAXIMUM]); #endif #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS #if ENABLED(CALIBRATION_MEASURE_KMIN) SERIAL_ECHOLNPGM(" " STR_K_MIN ": ", m.obj_side[KMINIMUM]); #endif @@ -439,7 +439,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPGM(" Top: ", m.backlash[TOP]); #endif - #if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I) + #if HAS_I_AXIS && AXIS_CAN_CALIBRATE(I) #if ENABLED(CALIBRATION_MEASURE_IMIN) SERIAL_ECHOLNPGM(" " STR_I_MIN ": ", m.backlash[IMINIMUM]); #endif @@ -447,7 +447,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM(" " STR_I_MAX ": ", m.backlash[IMAXIMUM]); #endif #endif - #if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J) + #if HAS_J_AXIS && AXIS_CAN_CALIBRATE(J) #if ENABLED(CALIBRATION_MEASURE_JMIN) SERIAL_ECHOLNPGM(" " STR_J_MIN ": ", m.backlash[JMINIMUM]); #endif @@ -455,7 +455,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM(" " STR_J_MAX ": ", m.backlash[JMAXIMUM]); #endif #endif - #if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K) + #if HAS_K_AXIS && AXIS_CAN_CALIBRATE(K) #if ENABLED(CALIBRATION_MEASURE_KMIN) SERIAL_ECHOLNPGM(" " STR_K_MIN ": ", m.backlash[KMINIMUM]); #endif diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 6aeb9c3d9dfec..628ae40f4845d 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -38,19 +38,19 @@ #if M91x_USE(X) || M91x_USE(X2) #define M91x_SOME_X 1 #endif - #if LINEAR_AXES >= 2 && (M91x_USE(Y) || M91x_USE(Y2)) + #if HAS_Y_AXIS && (M91x_USE(Y) || M91x_USE(Y2)) #define M91x_SOME_Y 1 #endif #if HAS_Z_AXIS && (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4)) #define M91x_SOME_Z 1 #endif - #if LINEAR_AXES >= 4 && M91x_USE(I) + #if HAS_I_AXIS && M91x_USE(I) #define M91x_USE_I 1 #endif - #if LINEAR_AXES >= 5 && M91x_USE(J) + #if HAS_J_AXIS && M91x_USE(J) #define M91x_USE_J 1 #endif - #if LINEAR_AXES >= 6 && M91x_USE(K) + #if HAS_K_AXIS && M91x_USE(K) #define M91x_USE_K 1 #endif diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 803a182654986..53c1bb302a9c9 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -693,6 +693,15 @@ #define HAS_Y_AXIS 1 #if LINEAR_AXES >= XYZ #define HAS_Z_AXIS 1 + #if LINEAR_AXES >= 4 + #define HAS_I_AXIS 1 + #if LINEAR_AXES >= 5 + #define HAS_J_AXIS 1 + #if LINEAR_AXES >= 6 + #define HAS_K_AXIS 1 + #endif + #endif + #endif #endif #endif @@ -926,6 +935,11 @@ #elif X_HOME_DIR < 0 #define X_HOME_TO_MIN 1 #endif +#if X2_HOME_DIR > 0 + #define X2_HOME_TO_MAX 1 +#elif X2_HOME_DIR < 0 + #define X2_HOME_TO_MIN 1 +#endif #if Y_HOME_DIR > 0 #define Y_HOME_TO_MAX 1 #elif Y_HOME_DIR < 0 @@ -1215,13 +1229,13 @@ #if HAS_Z_AXIS && !defined(INVERT_Z_DIR) #define INVERT_Z_DIR false #endif -#if LINEAR_AXES >= 4 && !defined(INVERT_I_DIR) +#if HAS_I_AXIS && !defined(INVERT_I_DIR) #define INVERT_I_DIR false #endif -#if LINEAR_AXES >= 5 && !defined(INVERT_J_DIR) +#if HAS_J_AXIS && !defined(INVERT_J_DIR) #define INVERT_J_DIR false #endif -#if LINEAR_AXES >= 6 && !defined(INVERT_K_DIR) +#if HAS_K_AXIS && !defined(INVERT_K_DIR) #define INVERT_K_DIR false #endif #if HAS_EXTRUDERS && !defined(INVERT_E_DIR) @@ -1411,7 +1425,7 @@ #endif #endif -#if ANY(USE_XMIN_PLUG, USE_YMIN_PLUG, USE_ZMIN_PLUG, USE_XMAX_PLUG, USE_YMAX_PLUG, USE_ZMAX_PLUG) +#if X_HOME_DIR || (HAS_Y_AXIS && Y_HOME_DIR) || (HAS_Z_AXIS && Z_HOME_DIR) || (HAS_I_AXIS && I_HOME_DIR) || (HAS_J_AXIS && J_HOME_DIR) || (HAS_K_AXIS && K_HOME_DIR) #define HAS_ENDSTOPS 1 #define COORDINATE_OKAY(N,L,H) WITHIN(N,L,H) #else diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 8c6e79f36ab14..2db80f9955adc 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -823,12 +823,6 @@ #define POLL_JOG #endif -#if X2_HOME_DIR > 0 - #define X2_HOME_TO_MAX 1 -#elif X2_HOME_DIR < 0 - #define X2_HOME_TO_MIN 1 -#endif - #ifndef HOMING_BUMP_MM #define HOMING_BUMP_MM { 0, 0, 0 } #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 477309ad81947..08130d31b7a1d 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -97,13 +97,13 @@ #else #undef CONTROLLER_FAN_USE_Z_ONLY #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #define I_MAX_LENGTH (I_MAX_POS - (I_MIN_POS)) #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #define J_MAX_LENGTH (J_MAX_POS - (J_MIN_POS)) #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #define K_MAX_LENGTH (K_MAX_POS - (K_MIN_POS)) #endif @@ -114,13 +114,13 @@ #if HAS_Y_AXIS && !defined(Y_BED_SIZE) #define Y_BED_SIZE Y_MAX_LENGTH #endif -#if LINEAR_AXES >= 4 && !defined(I_BED_SIZE) +#if HAS_I_AXIS && !defined(I_BED_SIZE) #define I_BED_SIZE I_MAX_LENGTH #endif -#if LINEAR_AXES >= 5 && !defined(J_BED_SIZE) +#if HAS_J_AXIS && !defined(J_BED_SIZE) #define J_BED_SIZE J_MAX_LENGTH #endif -#if LINEAR_AXES >= 6 && !defined(K_BED_SIZE) +#if HAS_K_AXIS && !defined(K_BED_SIZE) #define K_BED_SIZE K_MAX_LENGTH #endif @@ -134,13 +134,13 @@ #if HAS_Y_AXIS #define _Y_HALF_BED ((Y_BED_SIZE) / 2) #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #define _I_HALF_IMAX ((I_BED_SIZE) / 2) #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #define _J_HALF_JMAX ((J_BED_SIZE) / 2) #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #define _K_HALF_KMAX ((K_BED_SIZE) / 2) #endif @@ -149,13 +149,13 @@ #define Y_CENTER TERN(BED_CENTER_AT_0_0, 0, _Y_HALF_BED) #define XY_CENTER { X_CENTER, Y_CENTER } #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #define I_CENTER TERN(BED_CENTER_AT_0_0, 0, _I_HALF_BED) #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #define J_CENTER TERN(BED_CENTER_AT_0_0, 0, _J_HALF_BED) #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #define K_CENTER TERN(BED_CENTER_AT_0_0, 0, _K_HALF_BED) #endif @@ -166,15 +166,15 @@ #define Y_MIN_BED (Y_CENTER - _Y_HALF_BED) #define Y_MAX_BED (Y_MIN_BED + Y_BED_SIZE) #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #define I_MINIM (I_CENTER - _I_HALF_BED_SIZE) #define I_MAXIM (I_MINIM + I_BED_SIZE) #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #define J_MINIM (J_CENTER - _J_HALF_BED_SIZE) #define J_MAXIM (J_MINIM + J_BED_SIZE) #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #define K_MINIM (K_CENTER - _K_HALF_BED_SIZE) #define K_MAXIM (K_MINIM + K_BED_SIZE) #endif @@ -253,21 +253,21 @@ #define Z_HOME_POS TERN(Z_HOME_TO_MIN, Z_MIN_POS, Z_MAX_POS) #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #ifdef MANUAL_I_HOME_POS #define I_HOME_POS MANUAL_I_HOME_POS #else #define I_HOME_POS TERN(I_HOME_TO_MIN, I_MIN_POS, I_MAX_POS) #endif #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #ifdef MANUAL_J_HOME_POS #define J_HOME_POS MANUAL_J_HOME_POS #else #define J_HOME_POS TERN(J_HOME_TO_MIN, J_MIN_POS, J_MAX_POS) #endif #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #ifdef MANUAL_K_HOME_POS #define K_HOME_POS MANUAL_K_HOME_POS #else @@ -745,7 +745,7 @@ #define LIB_INTERNAL_MAX31865 1 #endif -#endif //HAS_MAX_TC +#endif // HAS_MAX_TC /** * X_DUAL_ENDSTOPS endstop reassignment @@ -1620,7 +1620,7 @@ #endif #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #if PIN_EXISTS(I_ENABLE) || AXIS_IS_L64XX(I) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(I)) #define HAS_I_ENABLE 1 #endif @@ -1640,7 +1640,7 @@ #undef DISABLE_INACTIVE_I #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #if PIN_EXISTS(J_ENABLE) || AXIS_IS_L64XX(J) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(J)) #define HAS_J_ENABLE 1 #endif @@ -1660,7 +1660,7 @@ #undef DISABLE_INACTIVE_J #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #if PIN_EXISTS(K_ENABLE) || AXIS_IS_L64XX(K) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(K)) #define HAS_K_ENABLE 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 4cd16d44842cc..f884046a96d50 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1416,7 +1416,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Allow only extra axis codes that do not conflict with G-code parameter names */ -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #if AXIS4_NAME != 'A' && AXIS4_NAME != 'B' && AXIS4_NAME != 'C' && AXIS4_NAME != 'U' && AXIS4_NAME != 'V' && AXIS4_NAME != 'W' #error "AXIS4_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." #elif !defined(I_MIN_POS) || !defined(I_MAX_POS) @@ -1427,7 +1427,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "I_ENABLE_ON is required for your I driver with LINEAR_AXES >= 4." #endif #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #if AXIS5_NAME == AXIS4_NAME #error "AXIS5_NAME must be unique." #elif AXIS5_NAME != 'A' && AXIS5_NAME != 'B' && AXIS5_NAME != 'C' && AXIS5_NAME != 'U' && AXIS5_NAME != 'V' && AXIS5_NAME != 'W' @@ -1440,7 +1440,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "J_ENABLE_ON is required for your J driver with LINEAR_AXES >= 5." #endif #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #if AXIS6_NAME == AXIS5_NAME || AXIS6_NAME == AXIS4_NAME #error "AXIS6_NAME must be unique." #elif AXIS6_NAME != 'A' && AXIS6_NAME != 'B' && AXIS6_NAME != 'C' && AXIS6_NAME != 'U' && AXIS6_NAME != 'V' && AXIS6_NAME != 'W' @@ -2412,13 +2412,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if _AXIS_PLUG_UNUSED_TEST(Z) #error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG." #endif - #if LINEAR_AXES >= 4 && _AXIS_PLUG_UNUSED_TEST(I) + #if HAS_I_AXIS && _AXIS_PLUG_UNUSED_TEST(I) #error "You must enable USE_IMIN_PLUG or USE_IMAX_PLUG." #endif - #if LINEAR_AXES >= 5 && _AXIS_PLUG_UNUSED_TEST(J) + #if HAS_J_AXIS && _AXIS_PLUG_UNUSED_TEST(J) #error "You must enable USE_JMIN_PLUG or USE_JMAX_PLUG." #endif - #if LINEAR_AXES >= 6 && _AXIS_PLUG_UNUSED_TEST(K) + #if HAS_K_AXIS && _AXIS_PLUG_UNUSED_TEST(K) #error "You must enable USE_KMIN_PLUG or USE_KMAX_PLUG." #endif @@ -2432,17 +2432,17 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Enable USE_YMIN_PLUG when homing Y to MIN." #elif Y_HOME_TO_MAX && DISABLED(USE_YMAX_PLUG) #error "Enable USE_YMAX_PLUG when homing Y to MAX." - #elif LINEAR_AXES >= 4 && I_HOME_TO_MIN && DISABLED(USE_IMIN_PLUG) + #elif HAS_I_AXIS && I_HOME_TO_MIN && DISABLED(USE_IMIN_PLUG) #error "Enable USE_IMIN_PLUG when homing I to MIN." - #elif LINEAR_AXES >= 4 && I_HOME_TO_MAX && DISABLED(USE_IMAX_PLUG) + #elif HAS_I_AXIS && I_HOME_TO_MAX && DISABLED(USE_IMAX_PLUG) #error "Enable USE_IMAX_PLUG when homing I to MAX." - #elif LINEAR_AXES >= 5 && J_HOME_TO_MIN && DISABLED(USE_JMIN_PLUG) + #elif HAS_J_AXIS && J_HOME_TO_MIN && DISABLED(USE_JMIN_PLUG) #error "Enable USE_JMIN_PLUG when homing J to MIN." - #elif LINEAR_AXES >= 5 && J_HOME_TO_MAX && DISABLED(USE_JMAX_PLUG) + #elif HAS_J_AXIS && J_HOME_TO_MAX && DISABLED(USE_JMAX_PLUG) #error "Enable USE_JMAX_PLUG when homing J to MAX." - #elif LINEAR_AXES >= 6 && K_HOME_TO_MIN && DISABLED(USE_KMIN_PLUG) + #elif HAS_K_AXIS && K_HOME_TO_MIN && DISABLED(USE_KMIN_PLUG) #error "Enable USE_KMIN_PLUG when homing K to MIN." - #elif LINEAR_AXES >= 6 && K_HOME_TO_MAX && DISABLED(USE_KMAX_PLUG) + #elif HAS_K_AXIS && K_HOME_TO_MAX && DISABLED(USE_KMAX_PLUG) #error "Enable USE_KMAX_PLUG when homing K to MAX." #endif #endif @@ -2967,11 +2967,11 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "TMC2208 or TMC2209 on E6 requires E6_HARDWARE_SERIAL or E6_SERIAL_(RX|TX)_PIN." #elif INVALID_TMC_UART(E7) #error "TMC2208 or TMC2209 on E7 requires E7_HARDWARE_SERIAL or E7_SERIAL_(RX|TX)_PIN." -#elif LINEAR_AXES >= 4 && INVALID_TMC_UART(I) +#elif HAS_I_AXIS && INVALID_TMC_UART(I) #error "TMC2208 or TMC2209 on I requires I_HARDWARE_SERIAL or I_SERIAL_(RX|TX)_PIN." -#elif LINEAR_AXES >= 5 && INVALID_TMC_UART(J) +#elif HAS_J_AXIS && INVALID_TMC_UART(J) #error "TMC2208 or TMC2209 on J requires J_HARDWARE_SERIAL or J_SERIAL_(RX|TX)_PIN." -#elif LINEAR_AXES >= 6 && INVALID_TMC_UART(K) +#elif HAS_K_AXIS && INVALID_TMC_UART(K) #error "TMC2208 or TMC2209 on K requires K_HARDWARE_SERIAL or K_SERIAL_(RX|TX)_PIN." #endif #undef INVALID_TMC_UART @@ -3057,11 +3057,11 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS INVALID_TMC_MS(E6) #elif !TMC_MICROSTEP_IS_VALID(E7) INVALID_TMC_MS(E7) -#elif LINEAR_AXES >= 4 && !TMC_MICROSTEP_IS_VALID(I) +#elif HAS_I_AXIS && !TMC_MICROSTEP_IS_VALID(I) INVALID_TMC_MS(I) -#elif LINEAR_AXES >= 5 && !TMC_MICROSTEP_IS_VALID(J) +#elif HAS_J_AXIS && !TMC_MICROSTEP_IS_VALID(J) INVALID_TMC_MS(J) -#elif LINEAR_AXES >= 6 && !TMC_MICROSTEP_IS_VALID(K) +#elif HAS_K_AXIS && !TMC_MICROSTEP_IS_VALID(K) INVALID_TMC_MS(K) #endif #undef INVALID_TMC_MS @@ -3083,13 +3083,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #define X_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(X,TMC2209) #define Y_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Y,TMC2209) #define Z_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Z,TMC2209) - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS #define I_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(I,TMC2209) #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS #define J_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(J,TMC2209) #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS #define K_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(K,TMC2209) #endif @@ -3106,17 +3106,17 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) when homing to Z_MIN." #elif Z_SENSORLESS && Z_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_ZMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) when homing to Z_MAX." - #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_IMIN) + #elif ALL(HAS_I_AXIS, I_SENSORLESS, I_HOME_TO_MIN) && DISABLED(ENDSTOPPULLUP_IMIN) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_IMIN (or ENDSTOPPULLUPS) when homing to I_MIN." - #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_IMAX) + #elif ALL(HAS_I_AXIS, I_SENSORLESS, I_HOME_TO_MAX) && DISABLED(ENDSTOPPULLUP_IMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_IMAX (or ENDSTOPPULLUPS) when homing to I_MAX." - #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_JMIN) + #elif ALL(HAS_J_AXIS, J_SENSORLESS, J_HOME_TO_MIN) && DISABLED(ENDSTOPPULLUP_JMIN) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_JMIN (or ENDSTOPPULLUPS) when homing to J_MIN." - #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_JMAX) + #elif ALL(HAS_J_AXIS, J_SENSORLESS, J_HOME_TO_MAX) && DISABLED(ENDSTOPPULLUP_JMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_JMAX (or ENDSTOPPULLUPS) when homing to J_MAX." - #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_KMIN) + #elif ALL(HAS_K_AXIS, K_SENSORLESS, K_HOME_TO_MIN) && DISABLED(ENDSTOPPULLUP_KMIN) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMIN (or ENDSTOPPULLUPS) when homing to K_MIN." - #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_KMAX) + #elif ALL(HAS_K_AXIS, K_SENSORLESS, K_HOME_TO_MAX) && DISABLED(ENDSTOPPULLUP_KMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMAX (or ENDSTOPPULLUPS) when homing to K_MAX." #endif #endif @@ -3162,37 +3162,37 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #else #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to Z_MAX." #endif - #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MIN && I_MIN_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING + #elif ALL(HAS_I_AXIS, I_SENSORLESS, I_HOME_TO_MIN) && I_MIN_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING #if I_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_INVERTING = true when homing to I_MIN." #else #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to I_MIN." #endif - #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && I_MAX_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING + #elif ALL(HAS_I_AXIS, I_SENSORLESS, I_HOME_TO_MAX) && I_MAX_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING #if I_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_INVERTING = true when homing to I_MAX." #else #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to I_MAX." #endif - #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MIN && J_MIN_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING + #elif ALL(HAS_J_AXIS, J_SENSORLESS, J_HOME_TO_MIN) && J_MIN_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING #if J_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_INVERTING = true when homing to J_MIN." #else #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to J_MIN." #endif - #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && J_MAX_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING + #elif ALL(HAS_J_AXIS, J_SENSORLESS, J_HOME_TO_MAX) && J_MAX_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING #if J_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_INVERTING = true when homing to J_MAX." #else #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to J_MAX." #endif - #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MIN && K_MIN_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING + #elif ALL(HAS_K_AXIS, K_SENSORLESS, K_HOME_TO_MIN) && K_MIN_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING #if K_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_INVERTING = true when homing to K_MIN." #else #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to K_MIN." #endif - #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && K_MAX_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING + #elif ALL(HAS_K_AXIS, K_SENSORLESS, K_HOME_TO_MAX) && K_MAX_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING #if K_ENDSTOP_INVERTING #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_INVERTING = true when homing to K_MAX." #else @@ -3316,7 +3316,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * L64XX requirement */ -#if HAS_L64XX && LINEAR_AXES >= 4 +#if HAS_L64XX && HAS_I_AXIS #error "L64XX requires LINEAR_AXES 3. Homing with L64XX is not yet implemented for LINEAR_AXES > 3." #endif @@ -3791,17 +3791,17 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #if _BAD_DRIVER(Z) #error "Z_DRIVER_TYPE is not recognized." #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #if _BAD_DRIVER(I) #error "I_DRIVER_TYPE is not recognized." #endif #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #if _BAD_DRIVER(J) #error "J_DRIVER_TYPE is not recognized." #endif #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #if _BAD_DRIVER(K) #error "K_DRIVER_TYPE is not recognized." #endif diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp index 4305462162ca7..a14fa4d1dfb2d 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp @@ -45,7 +45,7 @@ #if PIN_EXISTS(MT_DET_2) bool mt_det2_sta; #endif - #if HAS_X_MIN || HAS_X_MAX + #if X_HOME_DIR bool endstopx1_sta; #else constexpr static bool endstopx1_sta = true; @@ -55,7 +55,7 @@ #else constexpr static bool endstopx2_sta = true; #endif - #if HAS_Y_MIN || HAS_Y_MAX + #if HAS_Y_AXIS && Y_HOME_DIR bool endstopy1_sta; #else constexpr static bool endstopy1_sta = true; @@ -65,7 +65,7 @@ #else constexpr static bool endstopy2_sta = true; #endif - #if HAS_Z_MIN || HAS_Z_MAX + #if HAS_Z_AXIS && Z_HOME_DIR bool endstopz1_sta; #else constexpr static bool endstopz1_sta = true; diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp index 2c1bde245c025..92349659eb3d9 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -430,25 +430,24 @@ void NextionTFT::PanelInfo(uint8_t req) { break; case 36: // Endstop Info - #if HAS_X_MIN + #if X_HOME_TO_MIN SEND_VALasTXT("x1", READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING ? "triggered" : "open"); - #endif - #if HAS_X_MAX + #elif X_HOME_TO_MAX SEND_VALasTXT("x2", READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING ? "triggered" : "open"); #endif - #if HAS_Y_MIN + #if Y_HOME_TO_MIN SEND_VALasTXT("y1", READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING ? "triggered" : "open"); + #elif Y_HOME_TO_MAX + SEND_VALasTXT("y2", READ(X_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING ? "triggered" : "open"); #endif - #if HAS_Z_MIN + #if Z_HOME_TO_MIN SEND_VALasTXT("z1", READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING ? "triggered" : "open"); - #endif - #if HAS_Z_MAX + #elif Z_HOME_TO_MAX SEND_VALasTXT("z2", READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING ? "triggered" : "open"); #endif #if HAS_Z2_MIN SEND_VALasTXT("z2", READ(Z2_MIN_PIN) != Z2_MIN_ENDSTOP_INVERTING ? "triggered" : "open"); - #endif - #if HAS_Z2_MAX + #elif HAS_Z2_MAX SEND_VALasTXT("z2", READ(Z2_MAX_PIN) != Z2_MAX_ENDSTOP_INVERTING ? "triggered" : "open"); #endif #if HAS_BED_PROBE diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index ad276e11c0485..28be1ca9cfbb0 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -51,13 +51,13 @@ void menu_backlash() { #if HAS_Z_AXIS && _CAN_CALI(C) EDIT_BACKLASH_DISTANCE(C); #endif - #if LINEAR_AXES >= 4 && _CAN_CALI(I) + #if HAS_I_AXIS && _CAN_CALI(I) EDIT_BACKLASH_DISTANCE(I); #endif - #if LINEAR_AXES >= 5 && _CAN_CALI(J) + #if HAS_J_AXIS && _CAN_CALI(J) EDIT_BACKLASH_DISTANCE(J); #endif - #if LINEAR_AXES >= 6 && _CAN_CALI(K) + #if HAS_K_AXIS && _CAN_CALI(K) EDIT_BACKLASH_DISTANCE(K); #endif diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 29a908ac334df..344b94e2e9ba1 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -97,13 +97,13 @@ void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); } #if HAS_Z_AXIS void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS void lcd_move_i() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_I), I_AXIS); } #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS void lcd_move_j() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_J), J_AXIS); } #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS void lcd_move_k() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_K), K_AXIS); } #endif @@ -254,13 +254,13 @@ void menu_move() { #if HAS_Z_AXIS SUBMENU(MSG_MOVE_Z, []{ _menu_move_distance(Z_AXIS, lcd_move_z); }); #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS SUBMENU(MSG_MOVE_I, []{ _menu_move_distance(I_AXIS, lcd_move_i); }); #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS SUBMENU(MSG_MOVE_J, []{ _menu_move_distance(J_AXIS, lcd_move_j); }); #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS SUBMENU(MSG_MOVE_K, []{ _menu_move_distance(K_AXIS, lcd_move_k); }); #endif } @@ -345,13 +345,13 @@ void menu_move() { #if HAS_Z_AXIS GCODES_ITEM_N(Z_AXIS, MSG_AUTO_HOME_A, PSTR("G28Z")); #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS GCODES_ITEM_N(I_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS4_STR)); #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS GCODES_ITEM_N(J_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS5_STR)); #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS GCODES_ITEM_N(K_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS6_STR)); #endif @@ -398,13 +398,13 @@ void menu_motion() { #if HAS_Z_AXIS GCODES_ITEM_N(Z_AXIS, MSG_AUTO_HOME_A, PSTR("G28Z")); #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS GCODES_ITEM_N(I_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS4_STR)); #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS GCODES_ITEM_N(J_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS5_STR)); #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS GCODES_ITEM_N(K_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS6_STR)); #endif #endif diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp index 6f80652ce5b4b..dea2e3fc2d4c2 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp @@ -497,7 +497,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in } break; #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS case AXIS4_NAME: { position_min = I_center - displacement; position_max = I_center + displacement; @@ -509,7 +509,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in } break; #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS case AXIS5_NAME: { position_min = J_center - displacement; position_max = J_center + displacement; @@ -521,7 +521,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in } break; #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS case AXIS6_NAME: { position_min = K_center - displacement; position_max = K_center + displacement; diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 7a2cefdd4cea3..50ee33b3c06a1 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -1059,7 +1059,7 @@ void Endstops::update() { } #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS if (stepper.axis_is_moving(I_AXIS)) { if (stepper.motor_direction(I_AXIS_HEAD)) { // -direction #if HAS_I_MIN || (I_SPI_SENSORLESS && I_HOME_TO_MIN) @@ -1074,7 +1074,7 @@ void Endstops::update() { } #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS if (stepper.axis_is_moving(J_AXIS)) { if (stepper.motor_direction(J_AXIS_HEAD)) { // -direction #if HAS_J_MIN || (J_SPI_SENSORLESS && J_HOME_TO_MIN) @@ -1089,7 +1089,7 @@ void Endstops::update() { } #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS if (stepper.axis_is_moving(K_AXIS)) { if (stepper.motor_direction(K_AXIS_HEAD)) { // -direction #if HAS_K_MIN || (K_SPI_SENSORLESS && K_HOME_TO_MIN) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 2248c52d85d91..a77f395fb4c2b 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -603,7 +603,7 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { } #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s/*=0.0*/) { do_blocking_move_to_xyz_i(current_position, ri, fr_mm_s); } @@ -615,7 +615,7 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { } #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s/*=0.0*/) { do_blocking_move_to_xyzi_j(current_position, rj, fr_mm_s); } @@ -627,7 +627,7 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { } #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s/*=0.0*/) { do_blocking_move_to_xyzij_k(current_position, rk, fr_mm_s); } @@ -839,7 +839,7 @@ void restore_feedrate_and_scaling() { #endif } #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS if (axis_was_homed(I_AXIS)) { #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_I) NOLESS(target.i, soft_endstop.min.i); @@ -849,7 +849,7 @@ void restore_feedrate_and_scaling() { #endif } #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS if (axis_was_homed(J_AXIS)) { #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_J) NOLESS(target.j, soft_endstop.min.j); @@ -859,7 +859,7 @@ void restore_feedrate_and_scaling() { #endif } #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS if (axis_was_homed(K_AXIS)) { #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_K) NOLESS(target.k, soft_endstop.min.k); @@ -1417,13 +1417,13 @@ void prepare_line_to_destination() { #if HAS_Z_AXIS case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = true; break; #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = true; break; #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = true; break; #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = true; break; #endif default: break; @@ -1494,13 +1494,13 @@ void prepare_line_to_destination() { #if HAS_Z_AXIS case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = false; break; #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = false; break; #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = false; break; #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = false; break; #endif default: break; @@ -1821,13 +1821,13 @@ void prepare_line_to_destination() { case X_AXIS: es = X_ENDSTOP; break; case Y_AXIS: es = Y_ENDSTOP; break; case Z_AXIS: es = Z_ENDSTOP; break; - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS case I_AXIS: es = I_ENDSTOP; break; #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS case J_AXIS: es = J_ENDSTOP; break; #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS case K_AXIS: es = K_ENDSTOP; break; #endif } diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 50df5675e6c88..9fe61aad33494 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -180,19 +180,19 @@ inline float home_bump_mm(const AxisEnum axis) { TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z); break; #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS case I_AXIS: TERN_(MIN_SOFTWARE_ENDSTOP_I, amin = min.i); TERN_(MIN_SOFTWARE_ENDSTOP_I, amax = max.i); break; #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS case J_AXIS: TERN_(MIN_SOFTWARE_ENDSTOP_J, amin = min.j); TERN_(MIN_SOFTWARE_ENDSTOP_J, amax = max.j); break; #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS case K_AXIS: TERN_(MIN_SOFTWARE_ENDSTOP_K, amin = min.k); TERN_(MIN_SOFTWARE_ENDSTOP_K, amax = max.k); @@ -333,15 +333,15 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s=0.0f); #if HAS_Z_AXIS void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s=0.0f); #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s=0.0f); #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s=0.0f); #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s=0.0f); #endif @@ -476,15 +476,15 @@ void home_if_needed(const bool keeplev=false); #define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS) #define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS) #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #define LOGICAL_I_POSITION(POS) NATIVE_TO_LOGICAL(POS, I_AXIS) #define RAW_I_POSITION(POS) LOGICAL_TO_NATIVE(POS, I_AXIS) #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #define LOGICAL_J_POSITION(POS) NATIVE_TO_LOGICAL(POS, J_AXIS) #define RAW_J_POSITION(POS) LOGICAL_TO_NATIVE(POS, J_AXIS) #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #define LOGICAL_K_POSITION(POS) NATIVE_TO_LOGICAL(POS, K_AXIS) #define RAW_K_POSITION(POS) LOGICAL_TO_NATIVE(POS, K_AXIS) #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 45ccdd1702ef8..4c86c06efe6fb 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1866,13 +1866,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move, " A:", target.a, " (", da, " steps)" " B:", target.b, " (", db, " steps)" " C:", target.c, " (", dc, " steps)" - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS " " AXIS4_STR ":", target.i, " (", di, " steps)" #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS " " AXIS5_STR ":", target.j, " (", dj, " steps)" #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS " " AXIS6_STR ":", target.k, " (", dk, " steps)" #endif #if HAS_EXTRUDERS @@ -1939,13 +1939,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (db + dc < 0) SBI(dm, B_AXIS); // Motor B direction if (CORESIGN(db - dc) < 0) SBI(dm, C_AXIS); // Motor C direction #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS if (di < 0) SBI(dm, I_AXIS); #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS if (dj < 0) SBI(dm, J_AXIS); #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS if (dk < 0) SBI(dm, K_AXIS); #endif #elif ENABLED(MARKFORGED_XY) @@ -2041,13 +2041,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move, steps_dist_mm.b = (db + dc) * mm_per_step[B_AXIS]; steps_dist_mm.c = CORESIGN(db - dc) * mm_per_step[C_AXIS]; #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS steps_dist_mm.i = di * mm_per_step[I_AXIS]; #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS steps_dist_mm.j = dj * mm_per_step[J_AXIS]; #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS steps_dist_mm.k = dk * mm_per_step[K_AXIS]; #endif #elif ENABLED(MARKFORGED_XY) @@ -2104,7 +2104,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, ) #elif ENABLED(FOAMCUTTER_XYUV) // Return the largest distance move from either X/Y or I/J plane - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS _MAX(sq(steps_dist_mm.x) + sq(steps_dist_mm.y), sq(steps_dist_mm.i) + sq(steps_dist_mm.j)) #else sq(steps_dist_mm.x) + sq(steps_dist_mm.y) @@ -2197,13 +2197,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move, ); #endif #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS if (block->steps.i) stepper.enable_axis(I_AXIS); #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS if (block->steps.j) stepper.enable_axis(J_AXIS); #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS if (block->steps.k) stepper.enable_axis(K_AXIS); #endif #endif @@ -2949,17 +2949,17 @@ bool Planner::buffer_segment(const abce_pos_t &abce SERIAL_ECHOPGM(" (", position.z, "->", target.z); SERIAL_CHAR(')'); #endif - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS SERIAL_ECHOPGM_P(SP_I_LBL, abce.i); SERIAL_ECHOPGM(" (", position.i, "->", target.i); SERIAL_CHAR(')'); #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS SERIAL_ECHOPGM_P(SP_J_LBL, abce.j); SERIAL_ECHOPGM(" (", position.j, "->", target.j); SERIAL_CHAR(')'); #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS SERIAL_ECHOPGM_P(SP_K_LBL, abce.k); SERIAL_ECHOPGM(" (", position.k, "->", target.k); SERIAL_CHAR(')'); diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 5fda608e38390..a1525754549f0 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -2712,13 +2712,13 @@ void MarlinSettings::reset() { #if HAS_Z_AXIS && !defined(DEFAULT_ZJERK) #define DEFAULT_ZJERK 0 #endif - #if LINEAR_AXES >= 4 && !defined(DEFAULT_IJERK) + #if HAS_I_AXIS && !defined(DEFAULT_IJERK) #define DEFAULT_IJERK 0 #endif - #if LINEAR_AXES >= 5 && !defined(DEFAULT_JJERK) + #if HAS_J_AXIS && !defined(DEFAULT_JJERK) #define DEFAULT_JJERK 0 #endif - #if LINEAR_AXES >= 6 && !defined(DEFAULT_KJERK) + #if HAS_K_AXIS && !defined(DEFAULT_KJERK) #define DEFAULT_KJERK 0 #endif planner.max_jerk.set( diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index c100051f98087..b61f36bbb45db 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -435,15 +435,15 @@ xyze_int8_t Stepper::count_direction{0}; #define Z_APPLY_STEP(v,Q) Z_STEP_WRITE(v) #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #define I_APPLY_DIR(v,Q) I_DIR_WRITE(v) #define I_APPLY_STEP(v,Q) I_STEP_WRITE(v) #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #define J_APPLY_DIR(v,Q) J_DIR_WRITE(v) #define J_APPLY_STEP(v,Q) J_STEP_WRITE(v) #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #define K_APPLY_DIR(v,Q) K_DIR_WRITE(v) #define K_APPLY_STEP(v,Q) K_STEP_WRITE(v) #endif @@ -1688,7 +1688,7 @@ void Stepper::pulse_phase_isr() { const bool is_page = IS_PAGE(current_block); #if ENABLED(DIRECT_STEPPING) - // TODO (DerAndere): Add support for LINEAR_AXES >= 4 + // TODO (DerAndere): Add support for HAS_I_AXIS if (is_page) { #if STEPPER_PAGE_FORMAT == SP_4x4D_128 @@ -1929,7 +1929,7 @@ uint32_t Stepper::block_phase_isr() { // If current block is finished, reset pointer and finalize state if (step_events_completed >= step_event_count) { #if ENABLED(DIRECT_STEPPING) - // TODO (DerAndere): Add support for LINEAR_AXES >= 4 + // TODO (DerAndere): Add support for HAS_I_AXIS #if STEPPER_PAGE_FORMAT == SP_4x4D_128 #define PAGE_SEGMENT_UPDATE_POS(AXIS) \ count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] - 128 * 7; @@ -3184,13 +3184,13 @@ void Stepper::report_positions() { } break; - #if LINEAR_AXES >= 4 + #if HAS_I_AXIS case I_AXIS: BABYSTEP_AXIS(I, 0, direction); break; #endif - #if LINEAR_AXES >= 5 + #if HAS_J_AXIS case J_AXIS: BABYSTEP_AXIS(J, 0, direction); break; #endif - #if LINEAR_AXES >= 6 + #if HAS_K_AXIS case K_AXIS: BABYSTEP_AXIS(K, 0, direction); break; #endif diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index 93b765d7a52e3..7aea677534033 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -206,7 +206,7 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #endif // I Stepper -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #ifndef I_ENABLE_INIT #define I_ENABLE_INIT() SET_OUTPUT(I_ENABLE_PIN) #define I_ENABLE_WRITE(STATE) WRITE(I_ENABLE_PIN,STATE) @@ -225,7 +225,7 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #endif // J Stepper -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #ifndef J_ENABLE_INIT #define J_ENABLE_INIT() SET_OUTPUT(J_ENABLE_PIN) #define J_ENABLE_WRITE(STATE) WRITE(J_ENABLE_PIN,STATE) @@ -244,7 +244,7 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #endif // K Stepper -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #ifndef K_ENABLE_INIT #define K_ENABLE_INIT() SET_OUTPUT(K_ENABLE_PIN) #define K_ENABLE_WRITE(STATE) WRITE(K_ENABLE_PIN,STATE) @@ -895,21 +895,21 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define Z_RESET() #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #define ENABLE_AXIS_I() if (SHOULD_ENABLE(i)) { ENABLE_STEPPER_I(); AFTER_CHANGE(i, true); } #define DISABLE_AXIS_I() if (SHOULD_DISABLE(i)) { DISABLE_STEPPER_I(); AFTER_CHANGE(i, false); set_axis_untrusted(I_AXIS); } #else #define ENABLE_AXIS_I() NOOP #define DISABLE_AXIS_I() NOOP #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #define ENABLE_AXIS_J() if (SHOULD_ENABLE(j)) { ENABLE_STEPPER_J(); AFTER_CHANGE(j, true); } #define DISABLE_AXIS_J() if (SHOULD_DISABLE(j)) { DISABLE_STEPPER_J(); AFTER_CHANGE(j, false); set_axis_untrusted(J_AXIS); } #else #define ENABLE_AXIS_J() NOOP #define DISABLE_AXIS_J() NOOP #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #define ENABLE_AXIS_K() if (SHOULD_ENABLE(k)) { ENABLE_STEPPER_K(); AFTER_CHANGE(k, true); } #define DISABLE_AXIS_K() if (SHOULD_DISABLE(k)) { DISABLE_STEPPER_K(); AFTER_CHANGE(k, false); set_axis_untrusted(K_AXIS); } #else diff --git a/Marlin/src/module/stepper/trinamic.h b/Marlin/src/module/stepper/trinamic.h index 9ed9bdf407a8b..dd3a64240f20c 100644 --- a/Marlin/src/module/stepper/trinamic.h +++ b/Marlin/src/module/stepper/trinamic.h @@ -83,13 +83,13 @@ #if HAS_Z_AXIS && !defined(CHOPPER_TIMING_Z) #define CHOPPER_TIMING_Z CHOPPER_TIMING #endif -#if LINEAR_AXES >= 4 && !defined(CHOPPER_TIMING_I) +#if HAS_I_AXIS && !defined(CHOPPER_TIMING_I) #define CHOPPER_TIMING_I CHOPPER_TIMING #endif -#if LINEAR_AXES >= 5 && !defined(CHOPPER_TIMING_J) +#if HAS_J_AXIS && !defined(CHOPPER_TIMING_J) #define CHOPPER_TIMING_J CHOPPER_TIMING #endif -#if LINEAR_AXES >= 6 && !defined(CHOPPER_TIMING_K) +#if HAS_K_AXIS && !defined(CHOPPER_TIMING_K) #define CHOPPER_TIMING_K CHOPPER_TIMING #endif #if HAS_EXTRUDERS && !defined(CHOPPER_TIMING_E) diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index 934b74cbb1602..bf214761d3b2c 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -228,7 +228,7 @@ #define PS_ON_PIN P2_12 // (12) -#if !defined(TEMP_0_CS_PIN) && DISABLED(USE_ZMAX_PLUG) +#if !defined(TEMP_0_CS_PIN) && !(HAS_Z_AXIS && Z_HOME_DIR) #define TEMP_0_CS_PIN P1_28 #endif diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index fe8c4c6c41aaf..aa1def0b40a93 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -477,7 +477,7 @@ #endif #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #ifdef I_STOP_PIN #if I_HOME_TO_MIN #define I_MIN_PIN I_STOP_PIN @@ -500,7 +500,7 @@ #undef I_MAX_PIN #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #ifdef J_STOP_PIN #if J_HOME_TO_MIN #define J_MIN_PIN J_STOP_PIN @@ -523,7 +523,7 @@ #undef J_MAX_PIN #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #ifdef K_STOP_PIN #if K_HOME_TO_MIN #define K_MIN_PIN K_STOP_PIN @@ -1027,12 +1027,12 @@ #endif // The I axis, if any, should be the next open extruder port -#if LINEAR_AXES >= 4 && !defined(I_DIAG_PIN) && !defined(I_STEP_PIN) && !PIN_EXISTS(I_CS_PIN) +#if HAS_I_AXIS && !defined(I_DIAG_PIN) && !defined(I_STEP_PIN) && !PIN_EXISTS(I_CS_PIN) #define J_E_INDEX INCREMENT(I_E_INDEX) #else #define J_E_INDEX I_E_INDEX #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #ifndef I_STEP_PIN #define I_STEP_PIN _EPIN(I_E_INDEX, STEP) #define I_DIR_PIN _EPIN(I_E_INDEX, DIR) @@ -1112,12 +1112,12 @@ #endif // The J axis, if any, should be the next open extruder port -#if LINEAR_AXES >= 5 && !defined(J_DIAG_PIN) && !defined(J_STEP_PIN) && !PIN_EXISTS(J_CS_PIN) +#if HAS_J_AXIS && !defined(J_DIAG_PIN) && !defined(J_STEP_PIN) && !PIN_EXISTS(J_CS_PIN) #define K_E_INDEX INCREMENT(J_E_INDEX) #else #define K_E_INDEX J_E_INDEX #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #ifndef J_STEP_PIN #define J_STEP_PIN _EPIN(J_E_INDEX, STEP) #define J_DIR_PIN _EPIN(J_E_INDEX, DIR) @@ -1197,7 +1197,7 @@ #endif // The K axis, if any, should be the next open extruder port -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #ifndef K_STEP_PIN #define K_STEP_PIN _EPIN(K_E_INDEX, STEP) #define K_DIR_PIN _EPIN(K_E_INDEX, DIR) diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index 45c09ae33e3b4..165475dae8fdf 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -55,7 +55,6 @@ #define X_MIN_PIN 12 // X- #define Y_MIN_PIN 11 // Y- - #define Z_MIN_PIN 10 // Z- #define X_MAX_PIN 81 // X+ #define Y_MAX_PIN 57 // Y+ @@ -78,15 +77,16 @@ #endif #if ENABLED(BLTOUCH) - #define Z_MIN_PIN 11 // Y-MIN - #define SERVO0_PIN 10 // Z-MIN - #else - #define Z_MIN_PIN 10 + #define Z_MIN_PIN 11 // Y- + #define SERVO0_PIN 10 // Z- #endif #endif #define Z_MAX_PIN 7 +#ifndef Z_MIN_PIN 7 + #define Z_MIN_PIN 10 // Z- +#endif // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index 65ecd37e62da3..4bdadd80828ea 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -117,10 +117,6 @@ //#define E3_MS2_PIN ? //#define E3_MS3_PIN ? -#if USES_Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 49 -#endif - #ifndef FIL_RUNOUT_PIN #define FIL_RUNOUT_PIN Y_MIN_PIN #endif diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 76a2d5a3985fd..5273cbcd0e939 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -53,13 +53,6 @@ #define Z_MIN_PIN 47 #define Z_MAX_PIN 43 -// -// Z Probe (when not Z_MIN_PIN) -// -#ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 49 -#endif - // // Steppers // @@ -105,7 +98,7 @@ #define E2_CS_PIN 61 #endif -#if USES_Z_MIN_PROBE_PIN +#ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN 49 #endif diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index 5f2bd0467e1cf..f9911cc863fa5 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -155,7 +155,7 @@ #endif -#if LINEAR_AXES >= 4 +#if HAS_I_AXIS #if PIN_EXISTS(I_MIN) #define _I_MIN I_MIN_PIN, @@ -201,7 +201,7 @@ #endif -#if LINEAR_AXES >= 5 +#if HAS_J_AXIS #if PIN_EXISTS(J_MIN) #define _J_MIN J_MIN_PIN, @@ -247,7 +247,7 @@ #endif -#if LINEAR_AXES >= 6 +#if HAS_K_AXIS #if PIN_EXISTS(K_MIN) #define _K_MIN K_MIN_PIN, diff --git a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h index 486c10e71164f..5bfc2551acfa9 100644 --- a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h +++ b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h @@ -44,14 +44,13 @@ #define X_MAX_PIN 59 #define Y_MIN_PIN 60 #define Y_MAX_PIN 61 - #define Z_MIN_PIN 62 #define Z_MAX_PIN 63 #else #define X_STOP_PIN 36 #define Y_STOP_PIN 39 - #define Z_MIN_PIN 62 #define Z_MAX_PIN 42 #endif +#define Z_MIN_PIN 62 // // Z Probe (when not Z_MIN_PIN) From 397c751d55340f9f8fcd0a3b328b89cb1a6c16bc Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 3 Jan 2022 01:06:21 +0000 Subject: [PATCH 235/273] [cron] Bump distribution date (2022-01-03) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ae674efded9df..1279caef59ac9 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2022-01-02" +//#define STRING_DISTRIBUTION_DATE "2022-01-03" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6707e7ec506ed..d01fd0f543991 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2022-01-02" + #define STRING_DISTRIBUTION_DATE "2022-01-03" #endif /** From 6fd48a98815cb9a0b549a94b5a80f6e0da369c53 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sun, 2 Jan 2022 19:17:19 -0800 Subject: [PATCH 236/273] =?UTF-8?q?=F0=9F=92=9A=20Fix=20Teensy=20CI=20test?= =?UTF-8?q?=20(#23433)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/tests/teensy31 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/tests/teensy31 b/buildroot/tests/teensy31 index 10dde2be99ad8..7465a67fdde1e 100755 --- a/buildroot/tests/teensy31 +++ b/buildroot/tests/teensy31 @@ -14,7 +14,7 @@ exec_test $1 $2 "Teensy3.1 with default config" "$3" # Zero endstops, as with a CNC # restore_configs -opt_set MOTHERBOARD BOARD_TEENSY31_32 +opt_set MOTHERBOARD BOARD_TEENSY31_32 X_HOME_DIR 0 Y_HOME_DIR 0 Z_HOME_DIR 0 opt_disable USE_XMIN_PLUG USE_YMIN_PLUG USE_ZMIN_PLUG exec_test $1 $2 "Teensy3.1 with Zero Endstops" "$3" From 554a2fc84a5cd67cc9b0be8b01551a9eca3925bf Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sun, 2 Jan 2022 21:27:22 -0800 Subject: [PATCH 237/273] =?UTF-8?q?=E2=AC=86=EF=B8=8F=20Assert=20newer=20G?= =?UTF-8?q?CC=20in=20PIO=20via=20atmelavr@~3.4=20(#23432)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/avr.ini | 15 +---------- ini/due.ini | 3 --- ini/esp32.ini | 3 --- ini/lpc176x.ini | 2 -- ini/native.ini | 5 ---- ini/stm32f0.ini | 3 --- ini/stm32f1-maple.ini | 30 ---------------------- ini/stm32f1.ini | 32 +---------------------- ini/stm32f4.ini | 47 ---------------------------------- ini/stm32f7.ini | 2 -- ini/stm32g0.ini | 24 +++++++++--------- ini/stm32h7.ini | 1 - ini/teensy.ini | 59 +++++++++++++++++++++++++------------------ 13 files changed, 49 insertions(+), 177 deletions(-) diff --git a/ini/avr.ini b/ini/avr.ini index 92dd8f0cdb424..b13596afe119e 100644 --- a/ini/avr.ini +++ b/ini/avr.ini @@ -13,6 +13,7 @@ # AVR (8-bit) Common Environment values # [common_avr8] +platform = atmelavr@~3.4 build_flags = ${common.build_flags} -Wl,--relax board_build.f_cpu = 16000000L src_filter = ${common.default_src_filter} + @@ -21,7 +22,6 @@ src_filter = ${common.default_src_filter} + # ATmega2560 # [env:mega2560] -platform = atmelavr extends = common_avr8 board = megaatmega2560 @@ -33,7 +33,6 @@ board = megaatmega2560 # BOARD_EINSTART_S # [env:mega2560ext] -platform = atmelavr extends = env:mega2560 board_build.variant = MARLIN_MEGA_EXTENDED extra_scripts = ${common.extra_scripts} @@ -43,7 +42,6 @@ extra_scripts = ${common.extra_scripts} # ATmega1280 # [env:mega1280] -platform = atmelavr extends = common_avr8 board = megaatmega1280 @@ -61,7 +59,6 @@ build_flags = ${common.build_flags} -fno-tree-scev-cprop -fno-split-wide # MightyBoard ATmega1280 # [env:MightyBoard1280] -platform = atmelavr extends = mega_extended_optimized board = megaatmega1280 @@ -69,7 +66,6 @@ board = megaatmega1280 # MightyBoard ATmega2560 # [env:MightyBoard2560] -platform = atmelavr extends = mega_extended_optimized board = megaatmega2560 @@ -77,7 +73,6 @@ board = megaatmega2560 # RAMBo # [env:rambo] -platform = atmelavr extends = common_avr8 board = reprap_rambo @@ -85,7 +80,6 @@ board = reprap_rambo # FYSETC F6 V1.3 / V1.4 # [env:FYSETC_F6] -platform = atmelavr extends = common_avr8 board = fysetc_f6_13 @@ -93,7 +87,6 @@ board = fysetc_f6_13 # Sanguinololu (ATmega644p) # [env:sanguino644p] -platform = atmelavr extends = common_avr8 board = sanguino_atmega644p @@ -101,7 +94,6 @@ board = sanguino_atmega644p # Sanguinololu (ATmega1284p) # [env:sanguino1284p] -platform = atmelavr extends = common_avr8 board = sanguino_atmega1284p board_upload.maximum_size = 126976 @@ -114,7 +106,6 @@ board_upload.maximum_size = 126976 build_flags = ${common.build_flags} -fno-tree-scev-cprop -fno-split-wide-types -Wl,--relax -mcall-prologues [env:sanguino1284p_optimized] -platform = atmelavr extends = env:sanguino1284p build_flags = ${tuned_1284p.build_flags} @@ -122,12 +113,10 @@ build_flags = ${tuned_1284p.build_flags} # Melzi and clones (ATmega1284p) # [env:melzi] -platform = atmelavr extends = env:sanguino1284p upload_speed = 57600 [env:melzi_optimized] -platform = atmelavr extends = env:sanguino1284p_optimized upload_speed = 57600 @@ -135,7 +124,6 @@ upload_speed = 57600 # Melzi and clones (Optiboot bootloader) # [env:melzi_optiboot] -platform = atmelavr extends = common_avr8 board = sanguino_atmega1284p upload_speed = 115200 @@ -145,6 +133,5 @@ board_upload.maximum_size = 130048 # Melzi and clones (Zonestar Melzi2 with tuned flags) # [env:melzi_optiboot_optimized] -platform = atmelavr extends = env:melzi_optiboot build_flags = ${tuned_1284p.build_flags} diff --git a/ini/due.ini b/ini/due.ini index 9123af8cdc882..28b68383074d4 100644 --- a/ini/due.ini +++ b/ini/due.ini @@ -21,7 +21,6 @@ board = due src_filter = ${common.default_src_filter} + + [env:DUE_USB] -platform = atmelsam extends = env:DUE board = dueUSB @@ -29,7 +28,6 @@ board = dueUSB # Archim SAM # [common_DUE_archim] -platform = atmelsam extends = env:DUE board = marlin_archim build_flags = ${common.build_flags} @@ -39,5 +37,4 @@ extra_scripts = ${common.extra_scripts} Marlin/src/HAL/DUE/upload_extra_script.py [env:DUE_archim] -platform = ${common_DUE_archim.platform} extends = common_DUE_archim diff --git a/ini/esp32.ini b/ini/esp32.ini index 0815486cc9935..4ac6b96f5c3db 100644 --- a/ini/esp32.ini +++ b/ini/esp32.ini @@ -24,12 +24,10 @@ monitor_speed = 250000 #board_build.flash_mode = qio [env:FYSETC_E4] -platform = espressif32@2.1.0 extends = env:esp32 board_build.partitions = default_16MB.csv [env:PANDA] -platform = espressif32@2.1.0 extends = env:esp32 build_flags = ${env:esp32.build_flags} -DUSE_ESP32_EXIO -DUSE_ESP32_TASK_WDT lib_deps = ${common.lib_deps} @@ -40,5 +38,4 @@ monitor_speed = 115200 [env:mks_tinybee] extends = env:esp32 -platform = espressif32@2.1.0 board_build.partitions = default_8MB.csv diff --git a/ini/lpc176x.ini b/ini/lpc176x.ini index 3c5f43764ba6d..95f5637a5dec9 100644 --- a/ini/lpc176x.ini +++ b/ini/lpc176x.ini @@ -34,11 +34,9 @@ build_flags = ${common.build_flags} -DU8G_HAL_LINKS -IMarlin/src/HAL/LPC17 # NXP LPC176x ARM Cortex-M3 # [env:LPC1768] -platform = ${common_LPC.platform} extends = common_LPC board = nxp_lpc1768 [env:LPC1769] -platform = ${common_LPC.platform} extends = common_LPC board = nxp_lpc1769 diff --git a/ini/native.ini b/ini/native.ini index fe5fe3a5d05ad..5355284992cb3 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -52,12 +52,10 @@ extends = simulator_common build_flags = ${simulator_common.build_flags} -ldl -lpthread -lSDL2 -lSDL2_net -lGL [env:simulator_linux_debug] -platform = ${simulator_linux.platform} extends = simulator_linux build_type = debug [env:simulator_linux_release] -platform = ${simulator_linux.platform} extends = simulator_linux build_type = release build_flags = ${simulator_linux.build_flags} ${simulator_linux.release_flags} @@ -92,13 +90,11 @@ build_flags = -lSDL2 [env:simulator_macos_debug] -platform = ${env:simulator_linux_release.platform} extends = env:simulator_linux_debug build_flags = ${env:simulator_linux_debug.build_flags} ${simulator_macos.build_flags} -ggdb -Og -D_THREAD_SAFE build_unflags = ${simulator_macos.build_unflags} [env:simulator_macos_release] -platform = ${env:simulator_linux_release.platform} extends = env:simulator_linux_release build_flags = ${env:simulator_linux_release.build_flags} ${simulator_macos.build_flags} build_unflags = ${simulator_macos.build_unflags} @@ -110,7 +106,6 @@ build_unflags = ${simulator_macos.build_unflags} # pacman -S --needed base-devel mingw-w64-x86_64-toolchain mingw64/mingw-w64-x86_64-glm mingw64/mingw-w64-x86_64-SDL2 mingw64/mingw-w64-x86_64-SDL2_net mingw-w64-x86_64-dlfcn # [env:simulator_windows] -platform = ${simulator_common.platform} extends = simulator_common src_build_flags = ${simulator_common.src_build_flags} -fpermissive build_flags = ${simulator_common.build_flags} ${simulator_common.debug_build_flags} -IC:\\msys64\\mingw64\\include\\SDL2 -fno-stack-protector -Wl,-subsystem,windows -ldl -lmingw32 -lSDL2main -lSDL2 -lSDL2_net -lopengl32 -lssp diff --git a/ini/stm32f0.ini b/ini/stm32f0.ini index 4559f115bd8e2..d6251344c365b 100644 --- a/ini/stm32f0.ini +++ b/ini/stm32f0.ini @@ -23,7 +23,6 @@ # Malyan M200 v2 (STM32F070RB) # [env:STM32F070RB_malyan] -platform = ${common_stm32.platform} extends = common_stm32 board = marlin_malyanM200v2 build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED @@ -34,7 +33,6 @@ build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED # Malyan M200 v2 (STM32F070CB) # [env:STM32F070CB_malyan] -platform = ${common_stm32.platform} extends = common_stm32 board = malyanm200_f070cb build_flags = ${common_stm32.build_flags} @@ -45,7 +43,6 @@ build_flags = ${common_stm32.build_flags} # Malyan M300 (STM32F070CB) # [env:malyan_M300] -platform = ${common_stm32.platform} extends = common_stm32 board = malyanm300_f070cb build_flags = ${common_stm32.build_flags} diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 969bb815dacdd..878ccd6f7ce68 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -42,7 +42,6 @@ extra_scripts = ${common.extra_scripts} # STM32F103RC # [common_STM32F103RC_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103RC monitor_speed = 115200 @@ -51,7 +50,6 @@ monitor_speed = 115200 # MEEB_3DP (STM32F103RCT6 with 512K) # [env:STM32F103RC_meeb] -platform = ${common_stm32f1.platform} extends = common_STM32F103RC_maple board = marlin_MEEB_3DP build_flags = ${common_stm32f1.build_flags} @@ -75,7 +73,6 @@ upload_protocol = dfu # FYSETC STM32F103RC # [env:STM32F103RC_fysetc_maple] -platform = ${common_stm32f1.platform} extends = common_STM32F103RC_maple extra_scripts = ${common_stm32f1.extra_scripts} buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py @@ -91,7 +88,6 @@ upload_protocol = serial # STM32F103RC_btt_USB_maple ......... RCT6 with 256K (USB mass storage) # [env:STM32F103RC_btt_maple] -platform = ${common_stm32f1.platform} extends = common_STM32F103RC_maple board_build.address = 0x08007000 board_build.ldscript = STM32F103RC_SKR_MINI_256K.ld @@ -102,7 +98,6 @@ build_flags = ${common_stm32f1.build_flags} monitor_speed = 115200 [env:STM32F103RC_btt_USB_maple] -platform = ${common_stm32f1.platform} extends = env:STM32F103RC_btt_maple build_flags = ${env:STM32F103RC_btt_maple.build_flags} -DUSE_USB_COMPOSITE lib_deps = ${env:STM32F103RC_btt_maple.lib_deps} @@ -112,7 +107,6 @@ lib_deps = ${env:STM32F103RC_btt_maple.lib_deps} # Generic STM32F103RE environment # [env:STM32F103RE_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103RE monitor_speed = 115200 @@ -121,7 +115,6 @@ monitor_speed = 115200 # Creality (STM32F103RET6) # [env:STM32F103RET6_creality_maple] -platform = ${common_stm32f1.platform} extends = env:STM32F103RE_maple build_flags = ${common_stm32f1.build_flags} -DTEMP_TIMER_CHAN=4 board_build.address = 0x08007000 @@ -139,7 +132,6 @@ upload_protocol = jlink # STM32F103RE_btt_USB_maple ......... RET6 (USB mass storage) # [env:STM32F103RE_btt_maple] -platform = ${common_stm32f1.platform} extends = env:STM32F103RE_maple board_build.address = 0x08007000 board_build.ldscript = STM32F103RE_SKR_MINI_512K.ld @@ -150,7 +142,6 @@ debug_tool = stlink upload_protocol = stlink [env:STM32F103RE_btt_USB_maple] -platform = ${common_stm32f1.platform} extends = env:STM32F103RE_btt_maple build_flags = ${env:STM32F103RE_btt_maple.build_flags} -DUSE_USB_COMPOSITE lib_deps = ${common_stm32f1.lib_deps} @@ -160,7 +151,6 @@ lib_deps = ${common_stm32f1.lib_deps} # Geeetech GTM32 (STM32F103VET6) # [env:STM32F103VE_GTM32] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103VE build_flags = ${common_stm32f1.build_flags} @@ -174,7 +164,6 @@ upload_protocol = serial # Longer 3D board in Alfawise U20 (STM32F103VET6) # [env:STM32F103VE_longer_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103VE board_build.address = 0x08010000 @@ -191,7 +180,6 @@ build_unflags = ${common_stm32f1.build_unflags} # MKS Robin Mini (STM32F103VET6) # [env:mks_robin_mini_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103VE extra_scripts = ${common_stm32f1.extra_scripts} @@ -203,7 +191,6 @@ build_flags = ${common_stm32f1.build_flags} # MKS Robin Nano (STM32F103VET6) # [env:mks_robin_nano35_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103VE extra_scripts = ${common_stm32f1.extra_scripts} @@ -217,7 +204,6 @@ upload_protocol = jlink # MKS Robin (STM32F103ZET6) # [env:mks_robin_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103ZE extra_scripts = ${common_stm32f1.extra_scripts} @@ -229,7 +215,6 @@ build_flags = ${common_stm32f1.build_flags} # MKS Robin Pro (STM32F103ZET6) # [env:mks_robin_pro_maple] -platform = ${common_stm32f1.platform} extends = env:mks_robin_maple extra_scripts = ${common_stm32f1.extra_scripts} buildroot/share/PlatformIO/scripts/mks_robin_pro.py @@ -238,7 +223,6 @@ extra_scripts = ${common_stm32f1.extra_scripts} # TRIGORILLA PRO (STM32F103ZET6) # [env:trigorilla_pro_maple] -platform = ${common_stm32f1.platform} extends = env:mks_robin_maple extra_scripts = ${common_stm32f1.extra_scripts} @@ -247,7 +231,6 @@ extra_scripts = ${common_stm32f1.extra_scripts} # MKS Robin E3 with TMC2209 # [env:mks_robin_e3_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103RC extra_scripts = ${common_stm32f1.extra_scripts} @@ -260,7 +243,6 @@ build_flags = ${common_stm32f1.build_flags} # - LVGL UI # [env:mks_robin_e3p_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103VE extra_scripts = ${common_stm32f1.extra_scripts} @@ -274,7 +256,6 @@ upload_protocol = jlink # MKS Robin Lite/Lite2 (STM32F103RCT6) # [env:mks_robin_lite_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103RC extra_scripts = ${common_stm32f1.extra_scripts} @@ -284,7 +265,6 @@ extra_scripts = ${common_stm32f1.extra_scripts} # MKS ROBIN LITE3 (STM32F103RCT6) # [env:mks_robin_lite3_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103RC extra_scripts = ${common_stm32f1.extra_scripts} @@ -294,7 +274,6 @@ extra_scripts = ${common_stm32f1.extra_scripts} # JGAurora A5S A1 (STM32F103ZET6) # [env:jgaurora_a5s_a1_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103ZE board_build.address = 0x0800A000 @@ -309,7 +288,6 @@ build_flags = ${common_stm32f1.build_flags} # Malyan M200 (STM32F103CB) # [env:STM32F103CB_malyan_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = marlin_malyanM200 build_flags = ${common_stm32f1.build_flags} @@ -322,7 +300,6 @@ lib_ignore = ${common_stm32f1.lib_ignore} # Chitu boards like Tronxy X5s (STM32F103ZET6) # [env:chitu_f103_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = marlin_CHITU_F103 extra_scripts = ${common_stm32f1.extra_scripts} @@ -338,7 +315,6 @@ build_unflags = ${common_stm32f1.build_unflags} # Use this target if G28 or G29 are always failing. # [env:chitu_v5_gpio_init_maple] -platform = ${common_stm32f1.platform} extends = env:chitu_f103_maple build_flags = ${env:chitu_f103_maple.build_flags} -DCHITU_V5_Z_MIN_BUGFIX @@ -346,7 +322,6 @@ build_flags = ${env:chitu_f103_maple.build_flags} -DCHITU_V5_Z_MIN_BUGFIX # FLYmaker FLY Mini (STM32F103RCT6) # [env:FLY_MINI_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103RC board_build.address = 0x08005000 @@ -364,7 +339,6 @@ build_flags = ${common_stm32f1.build_flags} # STM32F103VE_ZM3E4V2_USB_maple ......... VET6 with 512K # [ZONESTAR_ZM3E_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 platform_packages = tool-stm32duino board_build.address = 0x08005000 @@ -380,20 +354,17 @@ lib_deps = ${common_stm32f1.lib_deps} lib_ignore = Adafruit NeoPixel, SPI, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, TMCStepper [env:STM32F103RC_ZM3E2_USB_maple] -platform = ${ZONESTAR_ZM3E_maple.platform} extends = ZONESTAR_ZM3E_maple board = genericSTM32F103RC board_build.ldscript = ZONESTAR_ZM3E_256K.ld [env:STM32F103VC_ZM3E4_USB_maple] -platform = ${ZONESTAR_ZM3E_maple.platform} extends = ZONESTAR_ZM3E_maple board = genericSTM32F103VC board_build.ldscript = ZONESTAR_ZM3E_256K.ld build_flags = ${ZONESTAR_ZM3E_maple.build_flags} -DTONE_TIMER=1 -DTONE_CHANNEL=2 [env:STM32F103VE_ZM3E4V2_USB_maple] -platform = ${ZONESTAR_ZM3E_maple.platform} extends = ZONESTAR_ZM3E_maple board = genericSTM32F103VE board_build.ldscript = ZONESTAR_ZM3E_512K.ld @@ -404,7 +375,6 @@ board_upload.maximum_size = 499712 # ERYONE ERY32 Mini (STM32F103VET6) # [env:ERYONE_ERY32_MINI_maple] -platform = ${common_stm32f1.platform} extends = common_stm32f1 board = genericSTM32F103VE build_flags = ${common_stm32f1.build_flags} diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index a2cd1b0f58674..939f51ffbf691 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -30,7 +30,6 @@ monitor_speed = 115200 # STM32F103RE # [env:STM32F103RE] -platform = ${common_stm32.platform} extends = common_stm32 board = genericSTM32F103RE monitor_speed = 115200 @@ -39,7 +38,6 @@ monitor_speed = 115200 # STM32F103VE # [env:STM32F103VE] -platform = ${common_stm32.platform} extends = common_stm32 board = genericSTM32F103VE monitor_speed = 115200 @@ -48,7 +46,6 @@ monitor_speed = 115200 # STM32F103ZE # [env:STM32F103ZE] -platform = ${common_stm32.platform} extends = common_stm32 board = genericSTM32F103ZE monitor_speed = 115200 @@ -60,7 +57,6 @@ monitor_speed = 115200 # STM32F103RC_btt_USB ......... RCT6 with 256K (USB mass storage) # [env:STM32F103RC_btt] -platform = ${common_stm32.platform} extends = common_STM32F103RC_variant build_flags = ${common_STM32F103RC_variant.build_flags} -DTIMER_SERVO=TIM5 @@ -68,7 +64,6 @@ board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 [env:STM32F103RC_btt_USB] -platform = ${common_stm32.platform} extends = env:STM32F103RC_btt platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${env:STM32F103RC_btt.build_flags} @@ -83,7 +78,6 @@ build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC # Uses HAL STM32 to support Marlin UI for TFT screen with optional touch panel # [env:mks_robin] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103ZE board_build.variant = MARLIN_F103Zx @@ -98,7 +92,6 @@ build_unflags = ${stm32_variant.build_unflags} # MKS Robin E3/E3D (STM32F103RCT6) with TMC2209 # [env:mks_robin_e3] -platform = ${common_stm32.platform} extends = common_STM32F103RC_variant board_build.encrypt = Robin_e3.bin board_build.offset = 0x5000 @@ -114,7 +107,6 @@ debug_tool = stlink # Creality (STM32F103RET6) # [env:STM32F103RET6_creality] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103RE board_build.variant = MARLIN_F103Rx @@ -139,7 +131,6 @@ upload_protocol = jlink # STM32F103RE_btt_USB ......... RET6 (USB mass storage) # [env:STM32F103RE_btt] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103RE board_build.variant = MARLIN_F103Rx @@ -154,7 +145,6 @@ debug_tool = jlink upload_protocol = jlink [env:STM32F103RE_btt_USB] -platform = ${common_stm32.platform} extends = env:STM32F103RE_btt platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${env:STM32F103RE_btt.build_flags} @@ -167,7 +157,6 @@ build_unflags = ${stm32_variant.build_unflags} -DUSBD_USE_CDC # board Hispeedv1 # [env:flsun_hispeedv1] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103VE board_build.variant = MARLIN_F103Vx @@ -184,7 +173,6 @@ build_unflags = ${stm32_variant.build_unflags} # MKS Robin Nano V1.2 and V2 # [env:mks_robin_nano35] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103VE board_build.variant = MARLIN_F103Vx @@ -203,7 +191,6 @@ upload_protocol = jlink # Mingda MPX_ARM_MINI # [env:mingda_mpx_arm_mini] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103ZE board_build.variant = MARLIN_F103Zx @@ -217,7 +204,6 @@ build_unflags = ${stm32_variant.build_unflags} # Malyan M200 (STM32F103CB) # [env:STM32F103CB_malyan] -platform = ${common_stm32.platform} extends = common_stm32 board = malyanm200_f103cb build_flags = ${common_stm32.build_flags} @@ -229,7 +215,6 @@ src_filter = ${common.default_src_filter} + # FLYmaker FLY Mini (STM32F103RCT6) # [env:FLY_MINI] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103RC board_build.variant = MARLIN_F103Rx @@ -241,7 +226,6 @@ build_flags = ${stm32_variant.build_flags} -DSS_TIMER=4 # MKS Robin Mini (STM32F103VET6) # [env:mks_robin_mini] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103VE board_build.variant = MARLIN_F103Vx @@ -255,7 +239,6 @@ build_flags = ${stm32_variant.build_flags} # MKS Robin Lite/Lite2 (STM32F103RCT6) # [env:mks_robin_lite] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103RC board_build.variant = MARLIN_F103Rx @@ -267,7 +250,6 @@ board_upload.offset_address = 0x08005000 # MKS ROBIN LITE3 (STM32F103RCT6) # [env:mks_robin_lite3] -platform = ${common_stm32.platform} extends = env:mks_robin_lite board_build.encrypt = mksLite3.bin @@ -275,7 +257,6 @@ board_build.encrypt = mksLite3.bin # MKS Robin Pro (STM32F103ZET6) # [env:mks_robin_pro] -platform = ${common_stm32.platform} extends = env:mks_robin board_build.encrypt = Robin_pro.bin @@ -284,7 +265,6 @@ board_build.encrypt = Robin_pro.bin # - LVGL UI # [env:mks_robin_e3p] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103VE board_build.variant = MARLIN_F103Vx @@ -301,7 +281,6 @@ upload_protocol = jlink # JGAurora A5S A1 (STM32F103ZET6) # [env:jgaurora_a5s_a1] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103ZE board_build.variant = MARLIN_F103Zx @@ -317,7 +296,6 @@ extra_scripts = ${stm32_variant.extra_scripts} # FYSETC STM32F103RC # [env:STM32F103RC_fysetc] -platform = ${common_stm32.platform} extends = common_STM32F103RC_variant extra_scripts = ${common_STM32F103RC_variant.extra_scripts} buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py @@ -329,10 +307,9 @@ upload_protocol = serial # Longer 3D board in Alfawise U20 (STM32F103VET6) # [env:STM32F103VE_longer] -platform = ${common_stm32.platform} +extends = stm32_variant lib_deps = ${common.lib_deps} https://github.com/tpruvot/STM32_Servo_OpenDrain/archive/2.0.zip -extends = stm32_variant board = genericSTM32F103VE board_build.variant = MARLIN_F103VE_LONGER board_build.rename = project.bin @@ -348,7 +325,6 @@ debug_tool = stlink # TRIGORILLA PRO (STM32F103ZET6) # [env:trigorilla_pro] -platform = ${stm32_variant.platform} extends = stm32_variant board = genericSTM32F103ZE board_build.variant = MARLIN_F103Zx @@ -361,7 +337,6 @@ build_unflags = ${stm32_variant.build_unflags} # Chitu boards like Tronxy X5s (STM32F103ZET6) # [env:chitu_f103] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F103ZE board_build.variant = MARLIN_F103Zx @@ -377,7 +352,6 @@ extra_scripts = ${stm32_variant.extra_scripts} # Use this target if G28 or G29 are always failing. # [env:chitu_v5_gpio_init] -platform = ${common_stm32.platform} extends = env:chitu_f103 build_flags = ${env:chitu_f103.build_flags} -DCHITU_V5_Z_MIN_BUGFIX @@ -389,7 +363,6 @@ build_flags = ${env:chitu_f103.build_flags} -DCHITU_V5_Z_MIN_BUGFIX # STM32F103VE_ZM3E4V2_USB ......... VET6 with 512K # [ZONESTAR_ZM3E] -platform = ${common_stm32.platform} extends = stm32_variant platform_packages = ${stm_flash_drive.platform_packages} board_upload.offset_address = 0x08005000 @@ -401,20 +374,17 @@ build_flags = ${common_stm32.build_flags} build_unflags = ${stm32_variant.build_unflags} -DUSBD_USE_CDC [env:STM32F103RC_ZM3E2_USB] -platform = ${ZONESTAR_ZM3E.platform} extends = ZONESTAR_ZM3E board = genericSTM32F103RC board_build.variant = MARLIN_F103Rx [env:STM32F103VC_ZM3E4_USB] -platform = ${ZONESTAR_ZM3E.platform} extends = ZONESTAR_ZM3E board = genericSTM32F103VC board_build.variant = MARLIN_F103Vx build_flags = ${ZONESTAR_ZM3E.build_flags} -DTIMER_TONE=TIM1 [env:STM32F103VE_ZM3E4V2_USB] -platform = ${ZONESTAR_ZM3E.platform} extends = ZONESTAR_ZM3E board = genericSTM32F103VE board_build.variant = MARLIN_F103Vx diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index d7c80cf0e9107..1c3d9a8892624 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -23,7 +23,6 @@ # ARMED (STM32) # [env:ARMED] -platform = ${common_stm32.platform} extends = common_stm32 board = armed_v1 build_flags = ${common_stm32.build_flags} @@ -34,7 +33,6 @@ build_flags = ${common_stm32.build_flags} # 'STEVAL-3DP001V1' STM32F401VE board - https://www.st.com/en/evaluation-tools/steval-3dp001v1.html # [env:STM32F401VE_STEVAL] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_STEVAL_STM32F401VE build_flags = ${stm32_variant.build_flags} @@ -45,7 +43,6 @@ build_flags = ${stm32_variant.build_flags} # STM32F401RC # [env:FYSETC_CHEETAH_V20] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_FYSETC_CHEETAH_V20 board_build.offset = 0x8000 @@ -55,7 +52,6 @@ build_flags = ${stm32_variant.build_flags} -DSTM32F401xC # FLYF407ZG # [env:FLYF407ZG] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_STM32F407ZGT6 board_build.variant = MARLIN_FLY_F407ZG @@ -66,7 +62,6 @@ upload_protocol = dfu # FYSETC S6 (STM32F446RET6 ARM Cortex-M4) # [env:FYSETC_S6] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_fysetc_s6 board_build.offset = 0x10000 @@ -80,7 +75,6 @@ upload_command = dfu-util -a 0 -s 0x08010000:leave -D "$SOURCE" # FYSETC S6 new bootloader # [env:FYSETC_S6_8000] -platform = ${common_stm32.platform} extends = env:FYSETC_S6 board = marlin_fysetc_s6 board_build.offset = 0x8000 @@ -93,7 +87,6 @@ upload_command = dfu-util -a 0 -s 0x08008000:leave -D "$SOURCE" # Shield - https://github.com/jmz52/Hardware # [env:STM32F407VE_black] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_blackSTM32F407VET6 build_flags = ${stm32_variant.build_flags} @@ -103,7 +96,6 @@ build_flags = ${stm32_variant.build_flags} # STM32F407VET6 Index Mobo Rev 03 # [env:Index_Mobo_Rev03] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_index_mobo_rev03 build_flags = ${stm32_variant.build_flags} @@ -117,7 +109,6 @@ extra_scripts = ${stm32_variant.extra_scripts} # Comment out board_build.offset = 0x10000 if you don't plan to use OpenBLT/flashing directly to 0x08000000. # [env:Anet_ET4_OpenBLT] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_F4x7Vx @@ -137,7 +128,6 @@ upload_protocol = jlink # BigTreeTech SKR Pro (STM32F407ZGT6 ARM Cortex-M4) # [env:BIGTREE_SKR_PRO] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_BigTree_SKR_Pro board_build.offset = 0x8000 @@ -149,7 +139,6 @@ upload_protocol = stlink # BigTreeTech SKR Pro (STM32F407ZGT6 ARM Cortex-M4) with USB Flash Drive Support # [env:BIGTREE_SKR_PRO_usb_flash_drive] -platform = ${common_stm32.platform} extends = env:BIGTREE_SKR_PRO platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${stm_flash_drive.build_flags} -DSTM32F407_5ZX @@ -159,7 +148,6 @@ build_unflags = ${env:BIGTREE_SKR_PRO.build_unflags} -DUSBCON -DUSBD_USE_CDC # BigTreeTech E3 RRF (STM32F407VGT6 ARM Cortex-M4) # [env:BIGTREE_E3_RRF] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_BIGTREE_E3_RRF @@ -173,7 +161,6 @@ build_flags = ${stm32_variant.build_flags} # Bigtreetech GTR V1.0 (STM32F407IGT6 ARM Cortex-M4) # [env:BIGTREE_GTR_V1_0] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_BigTree_GTR_v1 board_build.offset = 0x8000 @@ -183,7 +170,6 @@ build_flags = ${stm32_variant.build_flags} -DSTM32F407IX # Bigtreetech GTR V1.0 (STM32F407IGT6 ARM Cortex-M4) with USB Flash Drive Support # [env:BIGTREE_GTR_V1_0_usb_flash_drive] -platform = ${common_stm32.platform} extends = env:BIGTREE_GTR_V1_0 platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${stm_flash_drive.build_flags} -DSTM32F407IX @@ -193,7 +179,6 @@ build_unflags = ${env:BIGTREE_GTR_V1_0.build_unflags} -DUSBCON -DUSBD_USE_CD # BigTreeTech BTT002 V1.0 (STM32F407VGT6 ARM Cortex-M4) # [env:BIGTREE_BTT002] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_BigTree_BTT002 board_build.offset = 0x8000 @@ -208,7 +193,6 @@ build_flags = ${stm32_variant.build_flags} # BigTreeTech BTT002 V1.x with 512k of flash (STM32F407VET6 ARM Cortex-M4) # [env:BIGTREE_BTT002_VET6] -platform = ${env:BIGTREE_BTT002.platform} extends = env:BIGTREE_BTT002 board = marlin_BigTree_BTT002_VET6 @@ -216,7 +200,6 @@ board = marlin_BigTree_BTT002_VET6 # BigTreeTech SKR V2.0 (STM32F407VGT6 ARM Cortex-M4) with USB Flash Drive Support # [env:BIGTREE_SKR_2] -platform = ${common_stm32.platform} extends = stm32_variant platform_packages = ${stm_flash_drive.platform_packages} board = marlin_STM32F407VGT6_CCM @@ -234,13 +217,11 @@ upload_protocol = stlink # BigTreeTech SKR V2.0 (STM32F407VGT6 ARM Cortex-M4) with USB Media Share Support # [env:BIGTREE_SKR_2_USB] -platform = ${common_stm32.platform} extends = env:BIGTREE_SKR_2 build_flags = ${env:BIGTREE_SKR_2.build_flags} -DUSBD_USE_CDC_MSC build_unflags = ${env:BIGTREE_SKR_2.build_unflags} -DUSBD_USE_CDC [env:BIGTREE_SKR_2_USB_debug] -platform = ${common_stm32.platform} extends = env:BIGTREE_SKR_2_USB build_flags = ${env:BIGTREE_SKR_2_USB.build_flags} -O0 build_unflags = ${env:BIGTREE_SKR_2_USB.build_unflags} -Os -NDEBUG @@ -249,7 +230,6 @@ build_unflags = ${env:BIGTREE_SKR_2_USB.build_unflags} -Os -NDEBUG # Bigtreetech SKR V2.0 F429 (STM32F429VGT6 ARM Cortex-M4) with USB Flash Drive Support # [env:BIGTREE_SKR_2_F429] -platform = ${common_stm32.platform} extends = stm32_variant platform_packages = ${stm_flash_drive.platform_packages} board = marlin_STM32F429VGT6 @@ -267,13 +247,11 @@ upload_protocol = stlink # BigTreeTech SKR V2.0 F429 (STM32F429VGT6 ARM Cortex-M4) with USB Media Share Support # [env:BIGTREE_SKR_2_F429_USB] -platform = ${common_stm32.platform} extends = env:BIGTREE_SKR_2_F429 build_flags = ${env:BIGTREE_SKR_2_F429.build_flags} -DUSBD_USE_CDC_MSC build_unflags = ${env:BIGTREE_SKR_2_F429.build_unflags} -DUSBD_USE_CDC [env:BIGTREE_SKR_2_F429_USB_debug] -platform = ${common_stm32.platform} extends = env:BIGTREE_SKR_2_F429_USB build_flags = ${env:BIGTREE_SKR_2_F429_USB.build_flags} -O0 build_unflags = ${env:BIGTREE_SKR_2_F429_USB.build_unflags} -Os -NDEBUG @@ -282,7 +260,6 @@ build_unflags = ${env:BIGTREE_SKR_2_F429_USB.build_unflags} -Os -NDEBUG # BigTreeTech Octopus V1.0/1.1 / Octopus Pro V1.0 (STM32F446ZET6 ARM Cortex-M4) # [env:BIGTREE_OCTOPUS_V1] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_BigTree_Octopus_v1 board_build.offset = 0x8000 @@ -293,7 +270,6 @@ build_flags = ${stm32_variant.build_flags} # BigTreeTech Octopus V1.0/1.1 / Octopus Pro V1.0 (STM32F446ZET6 ARM Cortex-M4) with USB Flash Drive Support # [env:BIGTREE_OCTOPUS_V1_USB] -platform = ${common_stm32.platform} extends = env:BIGTREE_OCTOPUS_V1 platform_packages = ${stm_flash_drive.platform_packages} build_unflags = -DUSBD_USE_CDC @@ -307,7 +283,6 @@ build_flags = ${stm_flash_drive.build_flags} # BigTreeTech Octopus Pro V1.0 (STM32F429ZGT6 ARM Cortex-M4) # [env:BIGTREE_OCTOPUS_PRO_V1_F429] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_BigTree_Octopus_Pro_v1_F429 board_build.offset = 0x8000 @@ -318,7 +293,6 @@ build_flags = ${stm32_variant.build_flags} # BigTreeTech Octopus Pro V1.0 (STM32F429ZGT6 ARM Cortex-M4) with USB Flash Drive Support # [env:BIGTREE_OCTOPUS_PRO_V1_F429_USB] -platform = ${common_stm32.platform} extends = env:BIGTREE_OCTOPUS_PRO_V1_F429 platform_packages = ${stm_flash_drive.platform_packages} build_unflags = -DUSBD_USE_CDC @@ -332,7 +306,6 @@ build_flags = ${stm_flash_drive.build_flags} # Lerdge base # [lerdge_common] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_STM32F407ZGT6 board_build.variant = MARLIN_LERDGE @@ -349,7 +322,6 @@ extra_scripts = ${common_stm32.extra_scripts} # Lerdge X (STM32F407VE) # [env:LERDGEX] -platform = ${lerdge_common.platform} extends = lerdge_common board_build.encrypt = Lerdge_X_firmware_force.bin @@ -357,7 +329,6 @@ board_build.encrypt = Lerdge_X_firmware_force.bin # Lerdge X with USB Flash Drive Support # [env:LERDGEX_usb_flash_drive] -platform = ${env:LERDGEX.platform} extends = env:LERDGEX platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} @@ -366,7 +337,6 @@ build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # Lerdge S (STM32F407ZG) # [env:LERDGES] -platform = ${lerdge_common.platform} extends = lerdge_common board_build.encrypt = Lerdge_firmware_force.bin @@ -374,7 +344,6 @@ board_build.encrypt = Lerdge_firmware_force.bin # Lerdge S with USB Flash Drive Support # [env:LERDGES_usb_flash_drive] -platform = ${env:LERDGES.platform} extends = env:LERDGES platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} @@ -383,7 +352,6 @@ build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # Lerdge K (STM32F407ZG) # [env:LERDGEK] -platform = ${lerdge_common.platform} extends = lerdge_common board_build.encrypt = Lerdge_K_firmware_force.bin build_flags = ${lerdge_common.build_flags} -DLERDGEK @@ -392,7 +360,6 @@ build_flags = ${lerdge_common.build_flags} -DLERDGEK # Lerdge K with USB Flash Drive Support # [env:LERDGEK_usb_flash_drive] -platform = ${env:LERDGEK.platform} extends = env:LERDGEK platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} @@ -401,7 +368,6 @@ build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # RUMBA32 # [env:rumba32] -platform = ${common_stm32.platform} extends = stm32_variant board = rumba32_f446ve board_build.variant = MARLIN_F446VE @@ -418,7 +384,6 @@ upload_protocol = dfu # MKS Robin Pro V2 # [env:mks_robin_pro2] -platform = ${common_stm32.platform} extends = stm32_variant platform_packages = ${stm_flash_drive.platform_packages} board = genericSTM32F407VET6 @@ -440,7 +405,6 @@ build_flags = -DPIN_WIRE_SCL=PB6 -DPIN_WIRE_SDA=PB7 # MKS Robin Nano V3 # [env:mks_robin_nano_v3] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_F4x7Vx @@ -457,7 +421,6 @@ upload_protocol = jlink # Currently, using a STM32duino fork, until USB Host get merged # [env:mks_robin_nano_v3_usb_flash_drive] -platform = ${common_stm32.platform} extends = env:mks_robin_nano_v3 platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} @@ -471,7 +434,6 @@ build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} # Currently, using a STM32duino fork, until USB Host and USB Device MSC get merged # [env:mks_robin_nano_v3_usb_flash_drive_msc] -platform = ${common_stm32.platform} extends = env:mks_robin_nano_v3_usb_flash_drive build_flags = ${env:mks_robin_nano_v3_usb_flash_drive.build_flags} -DUSBD_USE_CDC_MSC @@ -482,7 +444,6 @@ build_unflags = -DUSBD_USE_CDC # 5 TMC2209 uart mode on board # [env:mks_eagle] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_F4x7Vx @@ -500,7 +461,6 @@ upload_protocol = jlink # Currently, using a STM32duino fork, until USB Host get merged # [env:mks_eagle_usb_flash_drive] -platform = ${common_stm32.platform} extends = env:mks_eagle platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} @@ -514,7 +474,6 @@ build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} # Currently, using a STM32duino fork, until USB Host and USB Device MSC get merged # [env:mks_eagle_usb_flash_drive_msc] -platform = ${common_stm32.platform} extends = env:mks_eagle_usb_flash_drive build_flags = ${env:mks_eagle_usb_flash_drive.build_flags} -DUSBD_USE_CDC_MSC @@ -530,7 +489,6 @@ build_flags = -DPIN_WIRE_SCL=PB8 -DPIN_WIRE_SDA=PB9 # MKS Monster8 # [env:mks_monster8] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_F4x7Vx @@ -548,7 +506,6 @@ upload_protocol = jlink # Currently, using a STM32duino fork, until USB Host get merged # [env:mks_monster8_usb_flash_drive] -platform = ${common_stm32.platform} extends = env:mks_monster8 platform_packages = ${stm_flash_drive.platform_packages} build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1_CAN.build_flags} @@ -562,7 +519,6 @@ build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1_CAN.build_flag # Currently, using a STM32duino fork, until USB Host and USB Device MSC get merged # [env:mks_monster8_usb_flash_drive_msc] -platform = ${common_stm32.platform} extends = env:mks_monster8_usb_flash_drive build_flags = ${env:mks_monster8_usb_flash_drive.build_flags} -DUSBD_USE_CDC_MSC @@ -572,7 +528,6 @@ build_unflags = -DUSBD_USE_CDC # TH3D EZBoard v2.0 (STM32F405RGT6 ARM Cortex-M4) # [env:TH3D_EZBoard_V2] -platform = ${common_stm32.platform} extends = stm32_variant board = genericSTM32F405RG board_build.variant = MARLIN_TH3D_EZBOARD_V2 @@ -588,7 +543,6 @@ upload_protocol = stlink # - MKS Robin Nano-S V1.3 (STM32F407VET6) 4 TMC2225 + 1 Pololu Plug # [env:mks_robin_nano_v1_3_f4] -platform = ${common_stm32.platform} extends = stm32_variant board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_F4x7Vx @@ -610,7 +564,6 @@ upload_protocol = jlink # Artillery Ruby # [env:Artillery_Ruby] -platform = ${common_stm32.platform} extends = common_stm32 board = marlin_Artillery_Ruby build_flags = ${common_stm32.build_flags} diff --git a/ini/stm32f7.ini b/ini/stm32f7.ini index 200740589b1af..62755c846d478 100644 --- a/ini/stm32f7.ini +++ b/ini/stm32f7.ini @@ -25,7 +25,6 @@ # being readily available based on STM32F7 MCUs # [env:NUCLEO_F767ZI] -platform = ${common_stm32.platform} extends = common_stm32 board = nucleo_f767zi build_flags = ${common_stm32.build_flags} -DTIMER_SERIAL=TIM9 @@ -34,6 +33,5 @@ build_flags = ${common_stm32.build_flags} -DTIMER_SERIAL=TIM9 # REMRAM_V1 # [env:REMRAM_V1] -platform = ${common_stm32.platform} extends = common_stm32 board = remram_v1 diff --git a/ini/stm32g0.ini b/ini/stm32g0.ini index 99f167a4df329..171945ffe2f0a 100644 --- a/ini/stm32g0.ini +++ b/ini/stm32g0.ini @@ -23,17 +23,17 @@ # BigTree SKR mini E3 V3.0 (STM32G0B1RET6 ARM Cortex-M0+) # [env:STM32G0B1RE_btt] -platform = ststm32@~14.1.0 -platform_packages = framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32/archive/main.zip -extends = stm32_variant -board = marlin_STM32G0B1RE +extends = stm32_variant +platform = ststm32@~14.1.0 +platform_packages = framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32/archive/main.zip +board = marlin_STM32G0B1RE board_build.offset = 0x2000 board_upload.offset_address = 0x08002000 -build_flags = ${stm32_variant.build_flags} - -DADC_RESOLUTION=12 - -DPIN_SERIAL4_RX=PC_11 -DPIN_SERIAL4_TX=PC_10 - -DSERIAL_RX_BUFFER_SIZE=1024 -DSERIAL_TX_BUFFER_SIZE=1024 - -DTIMER_SERVO=TIM3 -DTIMER_TONE=TIM4 - -DSTEP_TIMER_IRQ_PRIO=0 -upload_protocol = stlink -debug_tool = stlink +build_flags = ${stm32_variant.build_flags} + -DADC_RESOLUTION=12 + -DPIN_SERIAL4_RX=PC_11 -DPIN_SERIAL4_TX=PC_10 + -DSERIAL_RX_BUFFER_SIZE=1024 -DSERIAL_TX_BUFFER_SIZE=1024 + -DTIMER_SERVO=TIM3 -DTIMER_TONE=TIM4 + -DSTEP_TIMER_IRQ_PRIO=0 +upload_protocol = stlink +debug_tool = stlink diff --git a/ini/stm32h7.ini b/ini/stm32h7.ini index 16d1067e52c92..b0cb10866c55e 100644 --- a/ini/stm32h7.ini +++ b/ini/stm32h7.ini @@ -23,7 +23,6 @@ # BigTreeTech SKR SE BX (STM32H743IIT6 ARM Cortex-M7) # [env:BTT_SKR_SE_BX] -platform = ${common_stm32.platform} extends = stm32_variant platform_packages = framework-arduinoststm32@https://github.com/thisiskeithb/Arduino_Core_STM32/archive/biqu-bx-workaround.zip board = marlin_BTT_SKR_SE_BX diff --git a/ini/teensy.ini b/ini/teensy.ini index f3e5fd026092e..ab0617b5b7b5a 100644 --- a/ini/teensy.ini +++ b/ini/teensy.ini @@ -9,61 +9,72 @@ # # ################################# +# +# Teensy AVR +# +[teensy_avr] +platform = teensy +platform_packages = toolchain-atmelavr@~1.70300.0 +extends = common_avr8 +lib_ignore = ${env:common_avr8.lib_ignore}, NativeEthernet + # # AT90USB1286 boards using CDC bootloader # e.g., BRAINWAVE, BRAINWAVE_PRO, SAV_MKI, TEENSYLU # [env:at90usb1286_cdc] -platform = teensy -extends = common_avr8 +extends = teensy_avr board = marlin_at90usb1286 -lib_ignore = ${env:common_avr8.lib_ignore}, Teensy_ADC, NativeEthernet +lib_ignore = ${teensy_avr.lib_ignore}, Teensy_ADC # # AT90USB1286 boards using DFU bootloader # e.g., Printrboard, Printrboard Rev.F, 5DPRINT # [env:at90usb1286_dfu] -platform = teensy -extends = env:at90usb1286_cdc +extends = env:at90usb1286_cdc # # Teensy++ 2.0 # [env:teensy20] -platform = teensy -extends = common_avr8 -board = teensy2pp -lib_ignore = ${env:common_avr8.lib_ignore}, NativeEthernet +extends = teensy_avr +board = teensy2pp + +# +# Teensy 3.x - 4.x +# +[teensy_arm] +platform = teensy@~4.12.0 +src_filter = ${common.default_src_filter} +lib_ignore = NativeEthernet # # Teensy 3.1 / 3.2 (ARM Cortex-M4) # [env:teensy31] -platform = teensy@~4.12.0 -board = teensy31 -src_filter = ${common.default_src_filter} + -lib_ignore = NativeEthernet +extends = teensy_arm +board = teensy31 +src_filter = ${teensy_arm.src_filter} + # # Teensy 3.5 / 3.6 (ARM Cortex-M4) # [env:teensy35] -platform = teensy@~4.12.0 -board = teensy35 -src_filter = ${common.default_src_filter} + -lib_ignore = NativeEthernet +extends = teensy_arm +board = teensy35 +src_filter = ${teensy_arm.src_filter} + [env:teensy36] -platform = teensy@~4.12.0 -board = teensy36 -src_filter = ${common.default_src_filter} + -lib_ignore = NativeEthernet +extends = teensy_arm +board = teensy36 +src_filter = ${teensy_arm.src_filter} + # # Teensy 4.0 / 4.1 (ARM Cortex-M7) # [env:teensy41] -platform = teensy@~4.12.0 -board = teensy41 -src_filter = ${common.default_src_filter} + +extends = teensy_arm +board = teensy41 +src_filter = ${teensy_arm.src_filter} + +lib_ignore = From 90fc120182d97c27340632469335a64fcc782c16 Mon Sep 17 00:00:00 2001 From: hwmland <12407423+hwmland@users.noreply.github.com> Date: Mon, 3 Jan 2022 06:54:12 +0100 Subject: [PATCH 238/273] =?UTF-8?q?=F0=9F=A9=B9=20RAMPS=20FET=20order=20ov?= =?UTF-8?q?erridable,=20E=20+=20Laser=20(#23428)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins.h | 40 ++++++++++++++++++++++------------------ 1 file changed, 22 insertions(+), 18 deletions(-) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 1cb9462de4874..0d24ee6696bd3 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -37,24 +37,28 @@ #define MAX_E_STEPPERS 8 -#if MB(RAMPS_13_EFB, RAMPS_14_EFB, RAMPS_PLUS_EFB, RAMPS_14_RE_ARM_EFB, RAMPS_SMART_EFB, RAMPS_DUO_EFB, RAMPS4DUE_EFB) - #define FET_ORDER_EFB 1 -#elif MB(RAMPS_13_EEB, RAMPS_14_EEB, RAMPS_PLUS_EEB, RAMPS_14_RE_ARM_EEB, RAMPS_SMART_EEB, RAMPS_DUO_EEB, RAMPS4DUE_EEB) - #define FET_ORDER_EEB 1 -#elif MB(RAMPS_13_EFF, RAMPS_14_EFF, RAMPS_PLUS_EFF, RAMPS_14_RE_ARM_EFF, RAMPS_SMART_EFF, RAMPS_DUO_EFF, RAMPS4DUE_EFF) - #define FET_ORDER_EFF 1 -#elif MB(RAMPS_13_EEF, RAMPS_14_EEF, RAMPS_PLUS_EEF, RAMPS_14_RE_ARM_EEF, RAMPS_SMART_EEF, RAMPS_DUO_EEF, RAMPS4DUE_EEF) - #define FET_ORDER_EEF 1 -#elif MB(RAMPS_13_SF, RAMPS_14_SF, RAMPS_PLUS_SF, RAMPS_14_RE_ARM_SF, RAMPS_SMART_SF, RAMPS_DUO_SF, RAMPS4DUE_SF) - #define FET_ORDER_SF 1 -#elif HAS_MULTI_HOTEND && TEMP_SENSOR_BED - #define FET_ORDER_EEB 1 -#elif HAS_MULTI_HOTEND - #define FET_ORDER_EEF 1 -#elif TEMP_SENSOR_BED - #define FET_ORDER_EFB 1 -#else - #define FET_ORDER_EFF 1 +#if NONE(FET_ORDER_EEF, FET_ORDER_EEB, FET_ORDER_EFF, FET_ORDER_EFB, FET_ORDER_SF) + #if MB(RAMPS_13_EFB, RAMPS_14_EFB, RAMPS_PLUS_EFB, RAMPS_14_RE_ARM_EFB, RAMPS_SMART_EFB, RAMPS_DUO_EFB, RAMPS4DUE_EFB) + #define FET_ORDER_EFB 1 + #elif MB(RAMPS_13_EEB, RAMPS_14_EEB, RAMPS_PLUS_EEB, RAMPS_14_RE_ARM_EEB, RAMPS_SMART_EEB, RAMPS_DUO_EEB, RAMPS4DUE_EEB) + #define FET_ORDER_EEB 1 + #elif MB(RAMPS_13_EFF, RAMPS_14_EFF, RAMPS_PLUS_EFF, RAMPS_14_RE_ARM_EFF, RAMPS_SMART_EFF, RAMPS_DUO_EFF, RAMPS4DUE_EFF) + #define FET_ORDER_EFF 1 + #elif MB(RAMPS_13_EEF, RAMPS_14_EEF, RAMPS_PLUS_EEF, RAMPS_14_RE_ARM_EEF, RAMPS_SMART_EEF, RAMPS_DUO_EEF, RAMPS4DUE_EEF) + #define FET_ORDER_EEF 1 + #elif MB(RAMPS_13_SF, RAMPS_14_SF, RAMPS_PLUS_SF, RAMPS_14_RE_ARM_SF, RAMPS_SMART_SF, RAMPS_DUO_SF, RAMPS4DUE_SF) + #define FET_ORDER_SF 1 + #elif HAS_MULTI_HOTEND || (HAS_EXTRUDERS && HAS_CUTTER) + #if TEMP_SENSOR_BED + #define FET_ORDER_EEB 1 + #else + #define FET_ORDER_EEF 1 + #endif + #elif TEMP_SENSOR_BED + #define FET_ORDER_EFB 1 + #else + #define FET_ORDER_EFF 1 + #endif #endif #if !(BOTH(IS_ULTRA_LCD, IS_NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, WYH_L12864, MINIPANEL, REPRAPWORLD_KEYPAD)) From b8a376a28af8fd4d850f6a2080f5643593eec722 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 3 Jan 2022 09:18:10 -0600 Subject: [PATCH 239/273] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20RADDS+RRD=20encode?= =?UTF-8?q?r=20button?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/sam/pins_RADDS.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/sam/pins_RADDS.h b/Marlin/src/pins/sam/pins_RADDS.h index 7a865b4ad870a..da176f4447849 100644 --- a/Marlin/src/pins/sam/pins_RADDS.h +++ b/Marlin/src/pins/sam/pins_RADDS.h @@ -286,7 +286,7 @@ #endif // SPARK_FULL_GRAPHICS #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #define BTN_ENC_EN 47 // Detect the presence of the encoder #endif #endif // HAS_WIRED_LCD From 9a194826e3e424e404e95443976f1bdfb1d2b245 Mon Sep 17 00:00:00 2001 From: John Lagonikas <39417467+zeleps@users.noreply.github.com> Date: Mon, 3 Jan 2022 18:11:39 +0200 Subject: [PATCH 240/273] =?UTF-8?q?=E2=9C=A8=20M81=20D=20/=20S=20-=20Power?= =?UTF-8?q?-off=20Delay=20(#23396)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 11 +++-- Marlin/src/MarlinCore.cpp | 4 ++ Marlin/src/feature/power.cpp | 70 +++++++++++++++++++++------ Marlin/src/feature/power.h | 40 ++++++++++----- Marlin/src/gcode/control/M80_M81.cpp | 30 +++++++++--- Marlin/src/inc/SanityCheck.h | 2 + Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 4 +- Marlin/src/module/temperature.h | 7 ++- buildroot/tests/rambo | 4 +- 9 files changed, 130 insertions(+), 42 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 236c6a8a54612..c66c8eff95cfc 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -374,6 +374,9 @@ //#define PSU_DEFAULT_OFF // Keep power off until enabled directly with M80 //#define PSU_POWERUP_DELAY 250 // (ms) Delay for the PSU to warm up to full power + //#define POWER_OFF_TIMER // Enable M81 D to power off after a delay + //#define POWER_OFF_WAIT_FOR_COOLDOWN // Enable M81 S to power off only after cooldown + //#define PSU_POWERUP_GCODE "M355 S1" // G-code to run after power-on (e.g., case light on) //#define PSU_POWEROFF_GCODE "M355 S0" // G-code to run before power-off (e.g., case light off) @@ -384,12 +387,14 @@ #define AUTO_POWER_CONTROLLERFAN #define AUTO_POWER_CHAMBER_FAN #define AUTO_POWER_COOLER_FAN - //#define AUTO_POWER_E_TEMP 50 // (°C) Turn on PSU if any extruder is over this temperature - //#define AUTO_POWER_CHAMBER_TEMP 30 // (°C) Turn on PSU if the chamber is over this temperature - //#define AUTO_POWER_COOLER_TEMP 26 // (°C) Turn on PSU if the cooler is over this temperature #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) + //#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 + #endif #endif //=========================================================================== diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 16cd43443c1c9..2c290306693af 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1652,6 +1652,10 @@ void loop() { queue.advance(); + #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + powerManager.checkAutoPowerOff(); + #endif + endstops.event_handler(); TERN_(HAS_TFT_LVGL_UI, printer_state_polling()); diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index fabe35b989c7e..480cb91a918af 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -27,7 +27,9 @@ #include "../inc/MarlinConfig.h" #include "power.h" +#include "../module/planner.h" #include "../module/stepper.h" +#include "../module/temperature.h" #include "../MarlinCore.h" #if ENABLED(PS_OFF_SOUND) @@ -75,6 +77,10 @@ void Power::power_on() { if (psu_on) return; + #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + cancelAutoPowerOff(); + #endif + OUT_WRITE(PS_ON_PIN, PSU_ACTIVE_STATE); psu_on = true; safe_delay(PSU_POWERUP_DELAY); @@ -89,7 +95,6 @@ void Power::power_on() { /** * Power off if the power is currently on. * Processes any PSU_POWEROFF_GCODE and makes a PS_OFF_SOUND if enabled. - * */ void Power::power_off() { if (!psu_on) return; @@ -104,8 +109,56 @@ 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) + cancelAutoPowerOff(); + #endif } +#if EITHER(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) + + bool Power::is_cooling_needed() { + #if HAS_HOTEND && AUTO_POWER_E_TEMP + HOTEND_LOOP() if (thermalManager.degHotend(e) >= (AUTO_POWER_E_TEMP)) return true; + #endif + + #if HAS_HEATED_CHAMBER && AUTO_POWER_CHAMBER_TEMP + if (thermalManager.degChamber() >= (AUTO_POWER_CHAMBER_TEMP)) return true; + #endif + + #if HAS_COOLER && AUTO_POWER_COOLER_TEMP + if (thermalManager.degCooler() >= (AUTO_POWER_COOLER_TEMP)) return true; + #endif + + return false; + } + +#endif + +#if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + + #if ENABLED(POWER_OFF_TIMER) + millis_t Power::power_off_time = 0; + void Power::setPowerOffTimer(const millis_t delay_ms) { power_off_time = millis() + delay_ms; } + #endif + + #if ENABLED(POWER_OFF_WAIT_FOR_COOLDOWN) + bool Power::power_off_on_cooldown = false; + void Power::setPowerOffOnCooldown(const bool ena) { power_off_on_cooldown = ena; } + #endif + + void Power::cancelAutoPowerOff() { + TERN_(POWER_OFF_TIMER, power_off_time = 0); + TERN_(POWER_OFF_WAIT_FOR_COOLDOWN, power_off_on_cooldown = false); + } + + void Power::checkAutoPowerOff() { + if (TERN0(POWER_OFF_WAIT_FOR_COOLDOWN, power_off_on_cooldown && is_cooling_needed())) return; + if (TERN0(POWER_OFF_TIMER, power_off_time && PENDING(millis(), power_off_time))) return; + power_off(); + } + +#endif // POWER_OFF_TIMER || POWER_OFF_WAIT_FOR_COOLDOWN #if ENABLED(AUTO_POWER_CONTROL) @@ -149,19 +202,7 @@ void Power::power_off() { if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0 || thermalManager.temp_bed.soft_pwm_amount > 0)) return true; - #if HAS_HOTEND && AUTO_POWER_E_TEMP - HOTEND_LOOP() if (thermalManager.degHotend(e) >= (AUTO_POWER_E_TEMP)) return true; - #endif - - #if HAS_HEATED_CHAMBER && AUTO_POWER_CHAMBER_TEMP - if (thermalManager.degChamber() >= (AUTO_POWER_CHAMBER_TEMP)) return true; - #endif - - #if HAS_COOLER && AUTO_POWER_COOLER_TEMP - if (thermalManager.degCooler() >= (AUTO_POWER_COOLER_TEMP)) return true; - #endif - - return false; + return is_cooling_needed(); } /** @@ -193,7 +234,6 @@ void Power::power_off() { /** * Power off with a delay. Power off is triggered by check() after the delay. - * */ void Power::power_off_soon() { lastPowerOn = millis() - SEC_TO_MS(POWER_TIMEOUT) + SEC_TO_MS(POWER_OFF_DELAY); diff --git a/Marlin/src/feature/power.h b/Marlin/src/feature/power.h index 42c2c8494288e..38f7ed6ce7c7f 100644 --- a/Marlin/src/feature/power.h +++ b/Marlin/src/feature/power.h @@ -36,21 +36,37 @@ class Power { static void init(); static void power_on(); static void power_off(); + + #if EITHER(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); + #endif + #if ENABLED(POWER_OFF_WAIT_FOR_COOLDOWN) + static bool power_off_on_cooldown; + static void setPowerOffOnCooldown(const bool ena); + #endif + static void cancelAutoPowerOff(); + static void checkAutoPowerOff(); + #endif - #if ENABLED(AUTO_POWER_CONTROL) && POWER_OFF_DELAY > 0 - static void power_off_soon(); - #else - static void power_off_soon() { power_off(); } - #endif + #if ENABLED(AUTO_POWER_CONTROL) && POWER_OFF_DELAY > 0 + static void power_off_soon(); + #else + static void power_off_soon() { power_off(); } + #endif - #if ENABLED(AUTO_POWER_CONTROL) - static void check(const bool pause); + #if ENABLED(AUTO_POWER_CONTROL) + static void check(const bool pause); - private: - static millis_t lastPowerOn; - static bool is_power_needed(); - - #endif + private: + static millis_t lastPowerOn; + static bool is_power_needed(); + static bool is_cooling_needed(); + #elif ENABLED(POWER_OFF_WAIT_FOR_COOLDOWN) + private: + static bool is_cooling_needed(); + #endif }; extern Power powerManager; diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index b8be9daa40152..dc9b09c4e1b3f 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -79,13 +79,31 @@ void GcodeSuite::M81() { print_job_timer.stop(); - #if HAS_FAN - #if ENABLED(PROBING_FANS_OFF) - thermalManager.fans_paused = false; - ZERO(thermalManager.saved_fan_speed); - #endif + #if BOTH(HAS_FAN, PROBING_FANS_OFF) + thermalManager.fans_paused = false; + ZERO(thermalManager.saved_fan_speed); + #endif + + LCD_MESSAGE_F(MACHINE_NAME " " STR_OFF "."); + + bool delayed_power_off = false; + + #if ENABLED(POWER_OFF_TIMER) + if (parser.seenval('D')) { + delayed_power_off = true; + powerManager.setPowerOffTimer(SEC_TO_MS(parser.value_ushort())); + } #endif + #if ENABLED(POWER_OFF_WAIT_FOR_COOLDOWN) + if (parser.boolval('S')) { + delayed_power_off = true; + powerManager.setPowerOffOnCooldown(true); + } + #endif + + if (delayed_power_off) return; + safe_delay(1000); // Wait 1 second before switching off #if HAS_SUICIDE @@ -93,6 +111,4 @@ void GcodeSuite::M81() { #elif ENABLED(PSU_CONTROL) powerManager.power_off_soon(); #endif - - LCD_MESSAGE_F(MACHINE_NAME " " STR_OFF "."); } diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index f884046a96d50..06e0dfbb426de 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3577,6 +3577,8 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #error "PSU_CONTROL requires PS_ON_PIN." #elif POWER_OFF_DELAY < 0 #error "POWER_OFF_DELAY must be a positive value." + #elif ENABLED(POWER_OFF_WAIT_FOR_COOLDOWN) && !(defined(AUTO_POWER_E_TEMP) || defined(AUTO_POWER_CHAMBER_TEMP) || defined(AUTO_POWER_COOLER_TEMP)) + #error "POWER_OFF_WAIT_FOR_COOLDOWN requires AUTO_POWER_E_TEMP, AUTO_POWER_CHAMBER_TEMP, and/or AUTO_POWER_COOLER_TEMP." #endif #endif diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 4e730d04e7278..3612fb6bd19d7 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -481,7 +481,7 @@ void Popup_window_PauseOrStop() { Draw_Select_Highlight(true); DWIN_UpdateLCD(); } - else + else DWIN_Popup_ConfirmCancel(ICON_BLTouch, select_print.now == PRINT_PAUSE_RESUME ? GET_TEXT_F(MSG_PAUSE_PRINT) : GET_TEXT_F(MSG_STOP_PRINT)); } @@ -2015,7 +2015,7 @@ void HMI_LockScreen() { #endif //============================================================================= -// NEW MENU SUBSYSTEM +// NEW MENU SUBSYSTEM //============================================================================= // On click functions diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index e3515f0db870e..089694ab4adb6 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -993,7 +993,12 @@ class Temperature { static int16_t read_max_tc(TERN_(HAS_MULTI_MAX_TC, const uint8_t hindex=0)); #endif - static void update_autofans(); + #if HAS_AUTO_FAN + #if ENABLED(POWER_OFF_WAIT_FOR_COOLDOWN) + static bool autofans_on; + #endif + static void update_autofans(); + #endif #if HAS_HOTEND static float get_pid_output_hotend(const uint8_t e); diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index a54c04eeb21c5..92e8bc2b5f45f 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -14,7 +14,7 @@ opt_set MOTHERBOARD BOARD_RAMBO \ EXTRUDERS 2 TEMP_SENSOR_0 -2 TEMP_SENSOR_1 1 TEMP_SENSOR_BED 2 \ TEMP_SENSOR_PROBE 1 TEMP_PROBE_PIN 12 \ TEMP_SENSOR_CHAMBER 3 TEMP_CHAMBER_PIN 3 HEATER_CHAMBER_PIN 45 \ - GRID_MAX_POINTS_X 16 \ + GRID_MAX_POINTS_X 16 AUTO_POWER_E_TEMP 80 \ FANMUX0_PIN 53 opt_disable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN USE_WATCHDOG opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TEST \ @@ -32,7 +32,7 @@ opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_P SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE \ BACKLASH_COMPENSATION BACKLASH_GCODE BAUD_RATE_GCODE BEZIER_CURVE_SUPPORT \ FWRETRACT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \ - PSU_CONTROL PS_OFF_CONFIRM PS_OFF_SOUND AUTO_POWER_CONTROL \ + PSU_CONTROL PS_OFF_CONFIRM PS_OFF_SOUND POWER_OFF_WAIT_FOR_COOLDOWN \ POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE POWER_LOSS_RECOVER_ZHOME POWER_LOSS_ZHOME_POS \ SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL From e1ab7f3b751103296a0e8601b22b1ce22a90112b Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 4 Jan 2022 01:07:15 +0000 Subject: [PATCH 241/273] [cron] Bump distribution date (2022-01-04) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 1279caef59ac9..ce9d3387ed956 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2022-01-03" +//#define STRING_DISTRIBUTION_DATE "2022-01-04" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index d01fd0f543991..6a7295463acb1 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2022-01-03" + #define STRING_DISTRIBUTION_DATE "2022-01-04" #endif /** From e379a46639b76d551ae99a55d288b944d2e22031 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 5 Jan 2022 01:09:13 +0000 Subject: [PATCH 242/273] [cron] Bump distribution date (2022-01-05) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ce9d3387ed956..78afe004fcd94 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2022-01-04" +//#define STRING_DISTRIBUTION_DATE "2022-01-05" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6a7295463acb1..65ce6f7ff380e 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2022-01-04" + #define STRING_DISTRIBUTION_DATE "2022-01-05" #endif /** From cc919ae8999635dc45e3852f1d2a07fd15784d48 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 5 Jan 2022 01:52:02 -0600 Subject: [PATCH 243/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20strlen=5FP=20param?= =?UTF-8?q?eter=20error?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #23447 --- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 3612fb6bd19d7..5b5ae7d228a20 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -295,7 +295,7 @@ void ICON_Button(const bool selected, const int iconid, const frame_rect_t &ico, DWIN_Frame_AreaCopy(1, txt.x, txt.y[selected], txt.x + txt.w - 1, txt.y[selected] + txt.h - 1, ico.x + (ico.w - txt.w) / 2, (ico.y + ico.h - 28) - txt.h/2); } else { - const uint16_t x = ico.x + (ico.w - strlen_P(caption)*DWINUI::fontWidth()) / 2, + const uint16_t x = ico.x + (ico.w - strlen_P(FTOP(caption)) * DWINUI::fontWidth()) / 2, y = (ico.y + ico.h - 28) - DWINUI::fontHeight() / 2; DWINUI::Draw_String(x, y, caption); } From c55b66becea10c795ad271681a365925e0d62628 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 5 Jan 2022 01:48:18 -0600 Subject: [PATCH 244/273] =?UTF-8?q?=F0=9F=94=A8=20Strip=20CR=20in=20mftest?= =?UTF-8?q?=20>=20awk?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/bin/mftest | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/bin/mftest b/buildroot/bin/mftest index 9a58ba9cfcd21..77e53ff9ace44 100755 --- a/buildroot/bin/mftest +++ b/buildroot/bin/mftest @@ -150,7 +150,7 @@ if ((AUTO_BUILD)); then *) SYS='uni' ;; esac echo ; echo -n "Auto " ; ((AUTO_BUILD == 2)) && echo "Upload..." || echo "Build..." - MB=$( grep -E "^\s*#define MOTHERBOARD" Marlin/Configuration.h | awk '{ print $3 }' | $SED 's/BOARD_//' ) + MB=$( grep -E "^\s*#define MOTHERBOARD" Marlin/Configuration.h | awk '{ print $3 }' | $SED 's/BOARD_//;s/\r//' ) [[ -z $MB ]] && { echo "Error - Can't read MOTHERBOARD setting." ; exit 1 ; } BLINE=$( grep -E "define\s+BOARD_$MB\b" Marlin/src/core/boards.h ) BNUM=$( $SED -E 's/^.+BOARD_[^ ]+ +([0-9]+).+$/\1/' <<<"$BLINE" ) From 1fe07bf3652c67c2266b2d70c4562c1b94244f02 Mon Sep 17 00:00:00 2001 From: John Lagonikas <39417467+zeleps@users.noreply.github.com> Date: Wed, 5 Jan 2022 13:57:32 +0200 Subject: [PATCH 245/273] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20M80,=201s=20delay?= =?UTF-8?q?=20(#23455)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/power.cpp | 1 + Marlin/src/gcode/control/M80_M81.cpp | 11 +++++++---- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 480cb91a918af..0e4d5452e4864 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -153,6 +153,7 @@ void Power::power_off() { } void Power::checkAutoPowerOff() { + if (TERN1(POWER_OFF_TIMER, !power_off_time) && TERN1(POWER_OFF_WAIT_FOR_COOLDOWN, !power_off_on_cooldown)) return; if (TERN0(POWER_OFF_WAIT_FOR_COOLDOWN, power_off_on_cooldown && is_cooling_needed())) return; if (TERN0(POWER_OFF_TIMER, power_off_time && PENDING(millis(), power_off_time))) return; power_off(); diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index dc9b09c4e1b3f..cbb3c85f40caa 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -84,14 +84,19 @@ void GcodeSuite::M81() { ZERO(thermalManager.saved_fan_speed); #endif + safe_delay(1000); // Wait 1 second before switching off + LCD_MESSAGE_F(MACHINE_NAME " " STR_OFF "."); bool delayed_power_off = false; #if ENABLED(POWER_OFF_TIMER) if (parser.seenval('D')) { - delayed_power_off = true; - powerManager.setPowerOffTimer(SEC_TO_MS(parser.value_ushort())); + uint16_t delay = parser.value_ushort(); + if (delay > 1) { // skip already observed 1s delay + delayed_power_off = true; + powerManager.setPowerOffTimer(SEC_TO_MS(delay - 1)); + } } #endif @@ -104,8 +109,6 @@ void GcodeSuite::M81() { if (delayed_power_off) return; - safe_delay(1000); // Wait 1 second before switching off - #if HAS_SUICIDE suicide(); #elif ENABLED(PSU_CONTROL) From 4ceba981b1557ce72b1789cec983e098bb0bc9bf Mon Sep 17 00:00:00 2001 From: Mike La Spina Date: Wed, 5 Jan 2022 06:14:40 -0600 Subject: [PATCH 246/273] =?UTF-8?q?=F0=9F=90=9B=20Define=20required=20ends?= =?UTF-8?q?top=20enums=20(#23425)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/endstops.h | 30 ++++++++++++++++++++---------- 1 file changed, 20 insertions(+), 10 deletions(-) diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index e1ee933e83ba7..82a44cf95b83c 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -47,16 +47,26 @@ enum EndstopEnum : char { _ES_ITEM(HAS_K_MAX, K_MAX) // Extra Endstops for XYZ - _ES_ITEM(HAS_X2_MIN, X2_MIN) - _ES_ITEM(HAS_X2_MAX, X2_MAX) - _ES_ITEM(HAS_Y2_MIN, Y2_MIN) - _ES_ITEM(HAS_Y2_MAX, Y2_MAX) - _ES_ITEM(HAS_Z2_MIN, Z2_MIN) - _ES_ITEM(HAS_Z2_MAX, Z2_MAX) - _ES_ITEM(HAS_Z3_MIN, Z3_MIN) - _ES_ITEM(HAS_Z3_MAX, Z3_MAX) - _ES_ITEM(HAS_Z4_MIN, Z4_MIN) - _ES_ITEM(HAS_Z4_MAX, Z4_MAX) + #if ENABLED(X_DUAL_ENDSTOPS) + _ES_ITEM(HAS_X_MIN, X2_MIN) + _ES_ITEM(HAS_X_MAX, X2_MAX) + #endif + #if ENABLED(Y_DUAL_ENDSTOPS) + _ES_ITEM(HAS_Y_MIN, Y2_MIN) + _ES_ITEM(HAS_Y_MAX, Y2_MAX) + #endif + #if ENABLED(Z_MULTI_ENDSTOPS) + _ES_ITEM(HAS_Z_MIN, Z2_MIN) + _ES_ITEM(HAS_Z_MAX, Z2_MAX) + #if NUM_Z_STEPPER_DRIVERS >= 3 + _ES_ITEM(HAS_Z_MIN, Z3_MIN) + _ES_ITEM(HAS_Z_MAX, Z3_MAX) + #endif + #if NUM_Z_STEPPER_DRIVERS >= 4 + _ES_ITEM(HAS_Z_MIN, Z4_MIN) + _ES_ITEM(HAS_Z_MAX, Z4_MAX) + #endif + #endif // Bed Probe state is distinct or shared with Z_MIN (i.e., when the probe is the only Z endstop) #if !HAS_DELTA_SENSORLESS_PROBING From 9140016e0264b731b074e6d04f286f1e8c23a29e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 5 Jan 2022 11:44:22 -0600 Subject: [PATCH 247/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20X2=5FHOME=5FTO=5F*?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_LCD.h | 5 ----- Marlin/src/inc/Conditionals_adv.h | 6 ++++++ 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 53c1bb302a9c9..d49a917842e28 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -935,11 +935,6 @@ #elif X_HOME_DIR < 0 #define X_HOME_TO_MIN 1 #endif -#if X2_HOME_DIR > 0 - #define X2_HOME_TO_MAX 1 -#elif X2_HOME_DIR < 0 - #define X2_HOME_TO_MIN 1 -#endif #if Y_HOME_DIR > 0 #define Y_HOME_TO_MAX 1 #elif Y_HOME_DIR < 0 diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 2db80f9955adc..8c6e79f36ab14 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -823,6 +823,12 @@ #define POLL_JOG #endif +#if X2_HOME_DIR > 0 + #define X2_HOME_TO_MAX 1 +#elif X2_HOME_DIR < 0 + #define X2_HOME_TO_MIN 1 +#endif + #ifndef HOMING_BUMP_MM #define HOMING_BUMP_MM { 0, 0, 0 } #endif From 15936d32f5acb19d0a625e8974e53d77ebf487a8 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 6 Jan 2022 01:13:30 +0000 Subject: [PATCH 248/273] [cron] Bump distribution date (2022-01-06) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 78afe004fcd94..c356855a5af8e 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2022-01-05" +//#define STRING_DISTRIBUTION_DATE "2022-01-06" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 65ce6f7ff380e..845210871a583 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2022-01-05" + #define STRING_DISTRIBUTION_DATE "2022-01-06" #endif /** From 8e490e84be80ef9eb4e1f9de08939e1126c1c23d Mon Sep 17 00:00:00 2001 From: Kyle Hu Date: Thu, 6 Jan 2022 15:54:04 +0800 Subject: [PATCH 249/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Artillery=20Ruby?= =?UTF-8?q?=20(startup=20code,=20build=20flags)=20(#23446)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .gitignore | 1 - .../variants/MARLIN_ARTILLERY_RUBY/startup.S | 124 ++++++++++++++++++ ini/stm32f4.ini | 1 + 3 files changed, 125 insertions(+), 1 deletion(-) create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/startup.S diff --git a/.gitignore b/.gitignore index 191dd65ed9f87..0b852d767325a 100755 --- a/.gitignore +++ b/.gitignore @@ -41,7 +41,6 @@ applet/ *.rej *.bak *.idea -*.s *.i *.ii *.swp diff --git a/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/startup.S b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/startup.S new file mode 100644 index 0000000000000..81999dda6a425 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_ARTILLERY_RUBY/startup.S @@ -0,0 +1,124 @@ + /** + ****************************************************************************** + * @file startup_stm32f401xc.s + * @author MCD Application Team + * @version V2.4.2 + * @date 13-November-2015 + * @brief STM32F401xCxx Devices vector table for GCC based toolchains. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M4 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m4 + .fpu softvfp + .thumb + +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None + */ + + .section .text.Reset_Handler + .globl Reset_Handler + .type Reset_Handler, %function +Reset_Handler: +/* Check for magic code at the end of SRAM to detemine whether to jump to DFU */ + ldr r0, =0x2000FFF0 // End of SRAM for your CPU + ldr r1, =0xDEADBEEF + ldr r2, [r0, #0] + str r0, [r0, #0] // Invalidate + cmp r2, r1 + beq Jump_To_DFU + +/* Original Reset_Handler code */ + ldr sp, =_estack /* set stack pointer */ + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr + +Jump_To_DFU: + ldr r0, =0x40023844 // RCC_APB2ENR + ldr r1, =0x00004000 // ENABLE SYSCFG CLOCK + str r1, [r0, #0] + ldr r0, =0x40013800 // SYSCFG_MEMRMP + ldr r1, =0x00000001 // MAP ROM AT ZERO + str r1, [r0, #0] + ldr r0, =0x1FFF0000 // ROM BASE + ldr sp, [r0, #0] // SP @ +0 + ldr r0, [r0, #4] // PC @ +4 + bx r0 +.size Reset_Handler, .-Reset_Handler + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 1c3d9a8892624..f721f3075d798 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -570,5 +570,6 @@ build_flags = ${common_stm32.build_flags} -DSTM32F401xC -DTARGET_STM32F4 -DDISABLE_GENERIC_SERIALUSB -DARDUINO_ARCH_STM32 -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS -DUSB_PRODUCT=\"Artillery_3D_Printer\" + -DFLASH_DATA_SECTOR=1U -DFLASH_BASE_ADDRESS=0x08004000 extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py From 1bd921d6a69412686fa4b31c4c1e5710de9840cf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 Jan 2022 05:07:47 -0600 Subject: [PATCH 250/273] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20cleanup,=20comme?= =?UTF-8?q?nts?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 2 +- Marlin/src/feature/easythreed_ui.cpp | 10 +++--- Marlin/src/feature/power.h | 2 +- Marlin/src/gcode/bedlevel/abl/G29.cpp | 6 ++++ Marlin/src/lcd/e3v2/creality/dwin.cpp | 5 ++- Marlin/src/lcd/touch/touch_buttons.cpp | 2 +- Marlin/src/module/endstops.cpp | 15 +++++---- Marlin/src/module/stepper.cpp | 10 ++---- Marlin/src/sd/cardreader.cpp | 43 +++++++++----------------- Marlin/src/sd/cardreader.h | 3 +- 10 files changed, 45 insertions(+), 53 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index c66c8eff95cfc..a0dae835931bc 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -390,7 +390,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 EITHER(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 diff --git a/Marlin/src/feature/easythreed_ui.cpp b/Marlin/src/feature/easythreed_ui.cpp index 9f8af039478ca..b15daffc09bee 100644 --- a/Marlin/src/feature/easythreed_ui.cpp +++ b/Marlin/src/feature/easythreed_ui.cpp @@ -194,11 +194,11 @@ void EasythreedUI::printButton() { print_key_flag = PF_START; return; // Bail out } - card.ls(); // List all files to serial output - const uint16_t filecnt = card.countFilesInWorkDir(); // Count printable files in cwd - if (filecnt == 0) return; // None are printable? - card.selectFileByIndex(filecnt); // Select the last file according to current sort options - card.openAndPrintFile(card.filename); // Start printing it + card.ls(); // List all files to serial output + const uint16_t filecnt = card.countFilesInWorkDir(); // Count printable files in cwd + if (filecnt == 0) return; // None are printable? + card.selectFileByIndex(filecnt); // Select the last file according to current sort options + card.openAndPrintFile(card.filename); // Start printing it break; } case PF_PAUSE: { // Pause printing (not currently firing) diff --git a/Marlin/src/feature/power.h b/Marlin/src/feature/power.h index 38f7ed6ce7c7f..9ecd832afce6c 100644 --- a/Marlin/src/feature/power.h +++ b/Marlin/src/feature/power.h @@ -36,7 +36,7 @@ class Power { static void init(); static void power_on(); static void power_off(); - + #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) #if ENABLED(POWER_OFF_TIMER) static millis_t power_off_time; diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 6765ec86a6ec7..eea5d4a7f2516 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -290,6 +290,9 @@ G29_TYPE GcodeSuite::G29() { ry = RAW_Y_POSITION(parser.linearval('Y', NAN)); int8_t i = parser.byteval('I', -1), j = parser.byteval('J', -1); + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wmaybe-uninitialized" + if (!isnan(rx) && !isnan(ry)) { // Get nearest i / j from rx / ry i = (rx - bilinear_start.x + 0.5 * abl.gridSpacing.x) / abl.gridSpacing.x; @@ -297,6 +300,9 @@ G29_TYPE GcodeSuite::G29() { LIMIT(i, 0, (GRID_MAX_POINTS_X) - 1); LIMIT(j, 0, (GRID_MAX_POINTS_Y) - 1); } + + #pragma GCC diagnostic pop + if (WITHIN(i, 0, (GRID_MAX_POINTS_X) - 1) && WITHIN(j, 0, (GRID_MAX_POINTS_Y) - 1)) { set_bed_leveling_enabled(false); z_values[i][j] = rz; diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index adf8f3771f3de..3eed9650c1e76 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -2760,7 +2760,10 @@ void HMI_Prepare() { #endif #if HAS_HOTEND || HAS_HEATED_BED - case PREPARE_CASE_COOL: thermalManager.cooldown(); break; + case PREPARE_CASE_COOL: + thermalManager.cooldown(); + ui.reset_status(); + break; #endif case PREPARE_CASE_LANG: diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index c15bb08281f22..dcdc7def86675 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -79,7 +79,7 @@ uint8_t TouchButtons::read_buttons() { #if ENABLED(TOUCH_SCREEN_CALIBRATION) const calibrationState state = touch_calibration.get_calibration_state(); - if (state >= CALIBRATION_TOP_LEFT && state <= CALIBRATION_BOTTOM_RIGHT) { + if (WITHIN(state, CALIBRATION_TOP_LEFT, CALIBRATION_BOTTOM_RIGHT)) { if (touch_calibration.handleTouch(x, y)) ui.refresh(); return 0; } diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 50ee33b3c06a1..b9c5aebf39156 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -593,9 +593,6 @@ void _O2 Endstops::report_states() { } // Endstops::report_states -// The following routines are called from an ISR context. It could be the temperature ISR, the -// endstop ISR or the Stepper ISR. - #if HAS_DELTA_SENSORLESS_PROBING #define __ENDSTOP(AXIS, ...) AXIS ##_MAX #define _ENDSTOP_PIN(AXIS, ...) AXIS ##_MAX_PIN @@ -607,13 +604,18 @@ void _O2 Endstops::report_states() { #endif #define _ENDSTOP(AXIS, MINMAX) __ENDSTOP(AXIS, MINMAX) -// Check endstops - Could be called from Temperature ISR! +/** + * Called from interrupt context by the Endstop ISR or Stepper ISR! + * Read endstops to get their current states, register hits for all + * axes moving in the direction of their endstops, and abort moves. + */ void Endstops::update() { - #if !ENDSTOP_NOISE_THRESHOLD - if (!abort_enabled()) return; + #if !ENDSTOP_NOISE_THRESHOLD // If not debouncing... + if (!abort_enabled()) return; // ...and not enabled, exit. #endif + // Macros to update / copy the live_state #define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT_TO(live_state, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX))) #define COPY_LIVE_STATE(SRC_BIT, DST_BIT) SET_BIT_TO(live_state, DST_BIT, TEST(live_state, SRC_BIT)) @@ -1107,6 +1109,7 @@ void Endstops::update() { #if ENABLED(SPI_ENDSTOPS) + // Called from idle() to read Trinamic stall states bool Endstops::tmc_spi_homing_check() { bool hit = false; #if X_SPI_SENSORLESS diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index b61f36bbb45db..9a1c8278ba2d8 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2346,13 +2346,9 @@ uint32_t Stepper::block_phase_isr() { #endif #endif // LASER_POWER_INLINE - // At this point, we must ensure the movement about to execute isn't - // trying to force the head against a limit switch. If using interrupt- - // driven change detection, and already against a limit then no call to - // the endstop_triggered method will be done and the movement will be - // done against the endstop. So, check the limits here: If the movement - // is against the limits, the block will be marked as to be killed, and - // on the next call to this ISR, will be discarded. + // If the endstop is already pressed, endstop interrupts won't invoke + // endstop_triggered and the move will grind. So check here for a + // triggered endstop, which marks the block for discard on the next ISR. endstops.update(); #if ENABLED(Z_LATE_ENABLE) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index da6e84c759429..66c08b6455cfd 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -271,9 +271,8 @@ void CardReader::selectByName(SdFile dir, const char * const match) { * good addition. */ void CardReader::printListing( - SdFile parent + SdFile parent, const char * const prepend OPTARG(LONG_FILENAME_HOST_SUPPORT, const bool includeLongNames/*=false*/) - , const char * const prepend/*=nullptr*/ OPTARG(LONG_FILENAME_HOST_SUPPORT, const char * const prependLong/*=nullptr*/) ) { dir_t p; @@ -283,61 +282,47 @@ void CardReader::printListing( size_t lenPrepend = prepend ? strlen(prepend) + 1 : 0; // Allocate enough stack space for the full path including / separator char path[lenPrepend + FILENAME_LENGTH]; - if (prepend) { - strcpy(path, prepend); - path[lenPrepend - 1] = '/'; - } + if (prepend) { strcpy(path, prepend); path[lenPrepend - 1] = '/'; } char* dosFilename = path + lenPrepend; createFilename(dosFilename, p); // Get a new directory object using the full path // and dive recursively into it. SdFile child; // child.close() in destructor - if (child.open(&parent, dosFilename, O_READ)) + if (child.open(&parent, dosFilename, O_READ)) { #if ENABLED(LONG_FILENAME_HOST_SUPPORT) if (includeLongNames) { size_t lenPrependLong = prependLong ? strlen(prependLong) + 1 : 0; // Allocate enough stack space for the full long path including / separator char pathLong[lenPrependLong + strlen(longFilename) + 1]; - if (prependLong) { - strcpy(pathLong, prependLong); - pathLong[lenPrependLong - 1] = '/'; - } + if (prependLong) { strcpy(pathLong, prependLong); pathLong[lenPrependLong - 1] = '/'; } strcpy(pathLong + lenPrependLong, longFilename); - printListing(child, true, path, pathLong); + printListing(child, path, true, pathLong); } else - printListing(child, false, path); + printListing(child, path); #else printListing(child, path); #endif + } else { SERIAL_ECHO_MSG(STR_SD_CANT_OPEN_SUBDIR, dosFilename); return; } } else if (is_dir_or_gcode(p)) { - if (prepend) { - SERIAL_ECHO(prepend); - SERIAL_CHAR('/'); - } + if (prepend) { SERIAL_ECHO(prepend); SERIAL_CHAR('/'); } SERIAL_ECHO(createFilename(filename, p)); SERIAL_CHAR(' '); + SERIAL_ECHO(p.fileSize); #if ENABLED(LONG_FILENAME_HOST_SUPPORT) - if (!includeLongNames) - #endif - SERIAL_ECHOLN(p.fileSize); - #if ENABLED(LONG_FILENAME_HOST_SUPPORT) - else { - SERIAL_ECHO(p.fileSize); + if (includeLongNames) { SERIAL_CHAR(' '); - if (prependLong) { - SERIAL_ECHO(prependLong); - SERIAL_CHAR('/'); - } - SERIAL_ECHOLN(longFilename[0] ? longFilename : "???"); + if (prependLong) { SERIAL_ECHO(prependLong); SERIAL_CHAR('/'); } + SERIAL_ECHO(longFilename[0] ? longFilename : "???"); } #endif + SERIAL_EOL(); } } } @@ -348,7 +333,7 @@ void CardReader::printListing( void CardReader::ls(TERN_(LONG_FILENAME_HOST_SUPPORT, bool includeLongNames/*=false*/)) { if (flag.mounted) { root.rewind(); - printListing(root OPTARG(LONG_FILENAME_HOST_SUPPORT, includeLongNames)); + printListing(root, nullptr OPTARG(LONG_FILENAME_HOST_SUPPORT, includeLongNames)); } } diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 97e9bba867574..8761f57de53cd 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -336,9 +336,8 @@ class CardReader { static void selectByIndex(SdFile dir, const uint8_t index); static void selectByName(SdFile dir, const char * const match); static void printListing( - SdFile parent + SdFile parent, const char * const prepend OPTARG(LONG_FILENAME_HOST_SUPPORT, const bool includeLongNames=false) - , const char * const prepend=nullptr OPTARG(LONG_FILENAME_HOST_SUPPORT, const char * const prependLong=nullptr) ); From e99d95b7707f04bc28513322dad88eeb0d45778e Mon Sep 17 00:00:00 2001 From: Anson Liu Date: Thu, 6 Jan 2022 06:26:12 -0500 Subject: [PATCH 251/273] =?UTF-8?q?=F0=9F=93=BA=20Tune=20ULTI=5FCONTROLLER?= =?UTF-8?q?=20encoder,=20enable=20PCA9632=20(#23461)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals_LCD.h | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index d49a917842e28..4386964744dcd 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -207,8 +207,11 @@ #define IS_ULTIPANEL 1 #define U8GLIB_SSD1309 #define LCD_RESET_PIN LCD_PINS_D6 // This controller need a reset pin - #define ENCODER_PULSES_PER_STEP 2 - #define ENCODER_STEPS_PER_MENU_ITEM 2 + #define ENCODER_PULSES_PER_STEP 4 + #define ENCODER_STEPS_PER_MENU_ITEM 1 + #ifndef PCA9632 + #define PCA9632 + #endif #elif ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602) From 4d28c9d12bbed7c742f94f7367348e3c4d36dcc2 Mon Sep 17 00:00:00 2001 From: Lefteris Garyfalakis <46350667+lefterisgar@users.noreply.github.com> Date: Thu, 6 Jan 2022 13:30:41 +0200 Subject: [PATCH 252/273] =?UTF-8?q?=F0=9F=8C=90=20Localize=20E3V2=20Enhanc?= =?UTF-8?q?ed=20UI=20(#23424)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 50 ++++++++++----------- Marlin/src/lcd/e3v2/enhanced/printstats.cpp | 10 ++--- Marlin/src/lcd/language/language_en.h | 25 ++++++++++- 3 files changed, 53 insertions(+), 32 deletions(-) diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 5b5ae7d228a20..294d09956ab0d 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -499,7 +499,7 @@ void Popup_window_PauseOrStop() { DWIN_UpdateLCD(); } else - DWIN_Popup_Confirm(ICON_TempTooLow, F("Nozzle is too cold"), F("Preheat the hotend")); + DWIN_Popup_Confirm(ICON_TempTooLow, GET_TEXT_F(MSG_HOTEND_TOO_COLD), GET_TEXT_F(MSG_PLEASE_PREHEAT)); } #endif @@ -613,8 +613,8 @@ void Draw_Print_Labels() { DWIN_Frame_AreaCopy(1, 65, 72, 128, 86, 176, 173); // Remain } else { - DWINUI::Draw_String( 46, 173, F("Print Time")); - DWINUI::Draw_String(181, 173, F("Remain")); + DWINUI::Draw_String( 46, 173, GET_TEXT_F(MSG_INFO_PRINT_TIME)); + DWINUI::Draw_String(181, 173, GET_TEXT_F(MSG_REMAINING_TIME)); } } @@ -984,7 +984,7 @@ void Redraw_SD_List() { } else { DWIN_Draw_Rectangle(1, HMI_data.AlertBg_Color, 10, MBASE(3) - 10, DWIN_WIDTH - 10, MBASE(4)); - DWINUI::Draw_CenteredString(font16x32, HMI_data.AlertTxt_Color, MBASE(3), F("No Media")); + DWINUI::Draw_CenteredString(font16x32, HMI_data.AlertTxt_Color, MBASE(3), GET_TEXT_F(MSG_MEDIA_NOT_INSERTED)); } } @@ -1404,7 +1404,7 @@ void HMI_PauseOrStop() { #ifdef ACTION_ON_CANCEL hostui.cancel(); #endif - DWIN_Draw_Popup(ICON_BLTouch, F("Stopping..."), F("Please wait until done.")); + DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_STOPPING), GET_TEXT_F(MSG_PLEASE_WAIT)); } else Goto_PrintProcess(); // cancel stop @@ -1619,7 +1619,7 @@ void EachMomentUpdate() { void Goto_PowerLossRecovery() { recovery.dwin_flag = false; - LCD_MESSAGE_F("Recovery from power loss"); + LCD_MESSAGE_F(GET_TEXT_F(MSG_CONTINUE_PRINT_JOB)); HMI_flag.select_flag = false; Popup_PowerLossRecovery(); last_checkkey = MainMenu; @@ -1704,7 +1704,7 @@ void DWIN_StartHoming() { HMI_flag.home_flag = true; HMI_SaveProcessID(Homing); Title.ShowCaption(GET_TEXT_F(MSG_LEVEL_BED_HOMING)); - DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_LEVEL_BED_HOMING), F("Please wait until done.")); + DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_LEVEL_BED_HOMING), GET_TEXT_F(MSG_PLEASE_WAIT)); } void DWIN_CompletedHoming() { @@ -1720,7 +1720,7 @@ void DWIN_MeshLevelingStart() { #if HAS_ONESTEP_LEVELING HMI_SaveProcessID(Leveling); Title.ShowCaption(GET_TEXT_F(MSG_BED_LEVELING)); - DWIN_Draw_Popup(ICON_AutoLeveling, GET_TEXT_F(MSG_BED_LEVELING), F("Please wait until done.")); + DWIN_Draw_Popup(ICON_AutoLeveling, GET_TEXT_F(MSG_BED_LEVELING), GET_TEXT_F(MSG_PLEASE_WAIT)); #elif ENABLED(MESH_BED_LEVELING) Draw_ManualMesh_Menu(); #endif @@ -1894,7 +1894,7 @@ void MarlinUI::kill_screen(FSTR_P const lcd_error, FSTR_P const lcd_component) { void DWIN_RebootScreen() { DWIN_Frame_Clear(Color_Bg_Black); DWIN_JPG_ShowAndCache(0); - DWINUI::Draw_CenteredString(Color_White, 220, F("Please wait until reboot. ")); + DWINUI::Draw_CenteredString(Color_White, 220, GET_TEXT_F(MSG_PLEASE_WAIT_REBOOT)); DWIN_UpdateLCD(); delay(500); } @@ -1908,7 +1908,7 @@ void DWIN_Redraw_screen() { void DWIN_Popup_Pause(FSTR_P const fmsg, uint8_t button = 0) { HMI_SaveProcessID(button ? WaitResponse : NothingToDo); - DWIN_Draw_Popup(ICON_BLTouch, F("Advanced Pause"), fmsg, button); + DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_ADVANCED_PAUSE), fmsg, button); ui.reset_status(true); } @@ -1918,7 +1918,7 @@ void DWIN_Redraw_screen() { case PAUSE_MESSAGE_CHANGING: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_INIT)); break; case PAUSE_MESSAGE_UNLOAD: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_UNLOAD)); break; case PAUSE_MESSAGE_WAITING: DWIN_Popup_Pause(GET_TEXT_F(MSG_ADVANCED_PAUSE_WAITING), ICON_Continue_E); break; - case PAUSE_MESSAGE_INSERT: DWIN_Popup_Continue(ICON_BLTouch, F("Advanced Pause"), GET_TEXT_F(MSG_FILAMENT_CHANGE_INSERT)); break; + case PAUSE_MESSAGE_INSERT: DWIN_Popup_Continue(ICON_BLTouch, GET_TEXT_F(MSG_ADVANCED_PAUSE), GET_TEXT_F(MSG_FILAMENT_CHANGE_INSERT)); break; case PAUSE_MESSAGE_LOAD: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_LOAD)); break; case PAUSE_MESSAGE_PURGE: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE)); break; case PAUSE_MESSAGE_OPTION: DWIN_Popup_FilamentPurge(); break; @@ -1931,7 +1931,7 @@ void DWIN_Redraw_screen() { } void Draw_Popup_FilamentPurge() { - DWIN_Draw_Popup(ICON_BLTouch, F("Advanced Pause"), F("Purge or Continue?")); + DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_ADVANCED_PAUSE), F("Purge or Continue?")); DWINUI::Draw_Icon(ICON_Confirm_E, 26, 280); DWINUI::Draw_Icon(ICON_Continue_E, 146, 280); Draw_Select_Highlight(true); @@ -1970,7 +1970,7 @@ void DWIN_Redraw_screen() { #if HAS_MESH void DWIN_MeshViewer() { if (!leveling_is_valid()) - DWIN_Popup_Continue(ICON_BLTouch, F("Mesh viewer"), F("No valid mesh")); + DWIN_Popup_Continue(ICON_BLTouch, GET_TEXT_F(MSG_MESH_VIEWER), GET_TEXT_F(MSG_NO_VALID_MESH)); else { HMI_SaveProcessID(WaitResponse); MeshViewer.Draw(); @@ -2354,7 +2354,7 @@ void DWIN_ApplyColor() { DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); Draw_Status_Area(false); Draw_SelectColors_Menu(); - LCD_MESSAGE_F("Colors applied"); + LCD_MESSAGE_F(GET_TEXT_F(MSG_COLORS_APPLIED)); } void SetSpeed() { SetPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } @@ -3211,7 +3211,7 @@ void Draw_Prepare_Menu() { #endif #endif ADDMENUITEM(ICON_Cool, GET_TEXT_F(MSG_COOLDOWN), onDrawCooldown, DoCoolDown); - ADDMENUITEM(ICON_Language, PSTR("UI Language"), onDrawLanguage, SetLanguage); + ADDMENUITEM(ICON_Language, PSTR(GET_TEXT_F(MSG_UI_LANGUAGE)), onDrawLanguage, SetLanguage); } CurrentMenu->draw(); } @@ -3285,9 +3285,9 @@ void Draw_AdvancedSettings_Menu() { #if HAS_LCD_BRIGHTNESS ADDMENUITEM_P(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS), onDrawPInt8Menu, SetBrightness, &ui.brightness); #endif - ADDMENUITEM(ICON_Scolor, F("Select Colors"), onDrawSubMenu, Draw_SelectColors_Menu); + ADDMENUITEM(ICON_Scolor, GET_TEXT_F(MSG_COLORS_SELECT), onDrawSubMenu, Draw_SelectColors_Menu); #if ENABLED(SOUND_MENU_ITEM) - ADDMENUITEM(ICON_Sound, F("Enable Sound"), onDrawEnableSound, SetEnableSound); + ADDMENUITEM(ICON_Sound, GET_TEXT_F(MSG_SOUND_ENABLE), onDrawEnableSound, SetEnableSound); #endif #if HAS_MESH ADDMENUITEM(ICON_MeshViewer, GET_TEXT_F(MSG_MESH_VIEW), onDrawSubMenu, DWIN_MeshViewer); @@ -3299,7 +3299,7 @@ void Draw_AdvancedSettings_Menu() { ADDMENUITEM(ICON_PrintStats, GET_TEXT_F(MSG_INFO_STATS_MENU), onDrawSubMenu, Draw_PrintStats); ADDMENUITEM(ICON_PrintStatsReset, GET_TEXT_F(MSG_INFO_PRINT_COUNT_RESET), onDrawSubMenu, PrintStats.Reset); #endif - ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, DWIN_LockScreen); + ADDMENUITEM(ICON_Lock, GET_TEXT_F(MSG_LOCKSCREEN), onDrawMenuItem, DWIN_LockScreen); } CurrentMenu->draw(); } @@ -3398,7 +3398,7 @@ void Draw_SelectColors_Menu() { if (!SelectColorMenu) SelectColorMenu = new MenuClass(); if (CurrentMenu != SelectColorMenu) { CurrentMenu = SelectColorMenu; - SetMenuTitle({0}, F("Select Colors")); // TODO: Chinese, English "Select Color" JPG + SetMenuTitle({0}, GET_TEXT_F(MSG_COLORS_SELECT)); // TODO: Chinese, English "Select Color" JPG DWINUI::MenuItemsPrepare(20); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); ADDMENUITEM(ICON_StockConfiguration, GET_TEXT_F(MSG_RESTORE_DEFAULTS), onDrawMenuItem, RestoreDefaultsColors); @@ -3429,13 +3429,13 @@ void Draw_GetColor_Menu() { if (!GetColorMenu) GetColorMenu = new MenuClass(); if (CurrentMenu != GetColorMenu) { CurrentMenu = GetColorMenu; - SetMenuTitle({0}, F("Get Color")); // TODO: Chinese, English "Get Color" JPG + SetMenuTitle({0}, GET_TEXT_F(MSG_COLORS_GET)); // TODO: Chinese, English "Get Color" JPG DWINUI::MenuItemsPrepare(5); ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, DWIN_ApplyColor); ADDMENUITEM(ICON_Cancel, GET_TEXT_F(MSG_BUTTON_CANCEL), onDrawMenuItem, Draw_SelectColors_Menu); - ADDMENUITEM(0, "Red", onDrawGetColorItem, SetRGBColor); - ADDMENUITEM(1, "Green", onDrawGetColorItem, SetRGBColor); - ADDMENUITEM(2, "Blue", onDrawGetColorItem, SetRGBColor); + ADDMENUITEM(0, GET_TEXT_F(MSG_COLORS_RED), onDrawGetColorItem, SetRGBColor); + ADDMENUITEM(1, GET_TEXT_F(MSG_COLORS_GREEN), onDrawGetColorItem, SetRGBColor); + ADDMENUITEM(2, GET_TEXT_F(MSG_COLORS_BLUE), onDrawGetColorItem, SetRGBColor); } CurrentMenu->draw(); DWIN_Draw_Rectangle(1, *HMI_value.P_Int, 20, 315, DWIN_WIDTH - 20, 335); @@ -3472,9 +3472,9 @@ void Draw_Tune_Menu() { #if ENABLED(ADVANCED_PAUSE_FEATURE) ADDMENUITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); #endif - ADDMENUITEM(ICON_Lock, F("Lock Screen"), onDrawMenuItem, DWIN_LockScreen); + ADDMENUITEM(ICON_Lock, GET_TEXT_F(MSG_LOCKSCREEN), onDrawMenuItem, DWIN_LockScreen); #if HAS_LCD_BRIGHTNESS - ADDMENUITEM_P(ICON_Brightness, F("LCD Brightness"), onDrawPInt8Menu, SetBrightness, &ui.brightness); + ADDMENUITEM_P(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS), onDrawPInt8Menu, SetBrightness, &ui.brightness); #endif } CurrentMenu->draw(); diff --git a/Marlin/src/lcd/e3v2/enhanced/printstats.cpp b/Marlin/src/lcd/e3v2/enhanced/printstats.cpp index 54205363be1f8..a32d698b961ad 100644 --- a/Marlin/src/lcd/e3v2/enhanced/printstats.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/printstats.cpp @@ -54,17 +54,17 @@ void PrintStatsClass::Draw() { DWINUI::Draw_Icon(ICON_Continue_E, 86, 250); printStatistics ps = print_job_timer.getStats(); - sprintf_P(buf, PSTR("%s: %i"), GET_TEXT(MSG_INFO_PRINT_COUNT), ps.totalPrints); + sprintf_P(buf, PSTR(S_FMT ": %i"), GET_TEXT(MSG_INFO_PRINT_COUNT), ps.totalPrints); DWINUI::Draw_String(MRG, 80, buf); - sprintf_P(buf, PSTR("%s: %i"), GET_TEXT(MSG_INFO_COMPLETED_PRINTS), ps.finishedPrints); + sprintf_P(buf, PSTR(S_FMT ": %i"), GET_TEXT(MSG_INFO_COMPLETED_PRINTS), ps.finishedPrints); DWINUI::Draw_String(MRG, 100, buf); duration_t(print_job_timer.getStats().printTime).toDigital(str, true); - sprintf_P(buf, PSTR("%s: %s"), GET_TEXT(MSG_INFO_PRINT_TIME), str); + sprintf_P(buf, PSTR(S_FMT ": %s"), GET_TEXT(MSG_INFO_PRINT_TIME), str); DWINUI::Draw_String(MRG, 120, buf); duration_t(print_job_timer.getStats().longestPrint).toDigital(str, true); - sprintf_P(buf, PSTR("%s: %s"), GET_TEXT(MSG_INFO_PRINT_LONGEST), str); + sprintf_P(buf, PSTR(S_FMT ": %s"), GET_TEXT(MSG_INFO_PRINT_LONGEST), str); DWINUI::Draw_String(MRG, 140, buf); - sprintf_P(buf, PSTR("%s: %s m"), GET_TEXT(MSG_INFO_PRINT_FILAMENT), dtostrf(ps.filamentUsed / 1000, 1, 2, str)); + sprintf_P(buf, PSTR(S_FMT ": %s m"), GET_TEXT(MSG_INFO_PRINT_FILAMENT), dtostrf(ps.filamentUsed / 1000, 1, 2, str)); DWINUI::Draw_String(MRG, 160, buf); } diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index f1beb62e07029..08370d3a2fb55 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -157,9 +157,11 @@ namespace Language_en { LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Last Z: "); LSTR MSG_NEXT_CORNER = _UxGT("Next Corner"); LSTR MSG_MESH_EDITOR = _UxGT("Mesh Editor"); + LSTR MSG_MESH_VIEWER = _UxGT("Mesh Viewer"); LSTR MSG_EDIT_MESH = _UxGT("Edit Mesh"); LSTR MSG_MESH_VIEW = _UxGT("View Mesh"); LSTR MSG_EDITING_STOPPED = _UxGT("Mesh Editing Stopped"); + LSTR MSG_NO_VALID_MESH = _UxGT("No valid mesh"); LSTR MSG_PROBING_POINT = _UxGT("Probing Point"); LSTR MSG_MESH_X = _UxGT("Index X"); LSTR MSG_MESH_Y = _UxGT("Index Y"); @@ -437,6 +439,7 @@ namespace Language_en { LSTR MSG_BUTTON_ADVANCED = _UxGT("Advanced"); LSTR MSG_PAUSING = _UxGT("Pausing..."); LSTR MSG_PAUSE_PRINT = _UxGT("Pause Print"); + LSTR MSG_ADVANCED_PAUSE = _UxGT("Advanced Pause"); LSTR MSG_RESUME_PRINT = _UxGT("Resume Print"); LSTR MSG_HOST_START_PRINT = _UxGT("Start Host Print"); LSTR MSG_STOP_PRINT = _UxGT("Stop Print"); @@ -445,12 +448,14 @@ namespace Language_en { LSTR MSG_CANCEL_OBJECT = _UxGT("Cancel Object"); LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancel Object ="); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Power Outage"); + LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Continue Print Job"); LSTR MSG_MEDIA_MENU = _UxGT("Print from ") MEDIA_TYPE_EN; LSTR MSG_NO_MEDIA = _UxGT("No ") MEDIA_TYPE_EN; LSTR MSG_DWELL = _UxGT("Sleep..."); LSTR MSG_USERWAIT = _UxGT("Click to Resume..."); LSTR MSG_PRINT_PAUSED = _UxGT("Print Paused"); LSTR MSG_PRINTING = _UxGT("Printing..."); + LSTR MSG_STOPPING = _UxGT("Stopping..."); LSTR MSG_PRINT_ABORTED = _UxGT("Print Aborted"); LSTR MSG_PRINT_DONE = _UxGT("Print Done"); LSTR MSG_NO_MOVE = _UxGT("No Move."); @@ -541,6 +546,7 @@ namespace Language_en { LSTR MSG_ERR_MAXTEMP = _UxGT("Err: MAXTEMP"); LSTR MSG_ERR_MINTEMP = _UxGT("Err: MINTEMP"); LSTR MSG_HALTED = _UxGT("PRINTER HALTED"); + LSTR MSG_PLEASE_WAIT = _UxGT("Please wait..."); LSTR MSG_PLEASE_RESET = _UxGT("Please Reset"); LSTR MSG_PREHEATING = _UxGT("Preheating..."); LSTR MSG_HEATING = _UxGT("Heating..."); @@ -588,20 +594,35 @@ namespace Language_en { LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("INCORRECT PRINTER"); #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 + LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("No media inserted."); + LSTR MSG_REMAINING_TIME = _UxGT("Remaining time"); + LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Please wait until reboot. "); + LSTR MSG_PLEASE_PREHEAT = _UxGT("Please preheat the hot end."); LSTR MSG_INFO_PRINT_COUNT_RESET = _UxGT("Reset Print Count"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Print Count"); - LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completed"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Total Print Time"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Longest Job Time"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruded Total"); + LSTR MSG_COLORS_GET = _UxGT("Get Color"); + LSTR MSG_COLORS_SELECT = _UxGT("Select Colors"); + LSTR MSG_COLORS_APPLIED = _UxGT("Colors applied"); + LSTR MSG_COLORS_RED = _UxGT("Red"); + LSTR MSG_COLORS_GREEN = _UxGT("Green"); + LSTR MSG_COLORS_BLUE = _UxGT("Blue"); + LSTR MSG_UI_LANGUAGE = _UxGT("UI Language"); + LSTR MSG_SOUND_ENABLE = _UxGT("Enable sound"); + LSTR MSG_LOCKSCREEN = _UxGT("Lock Screen"); #else + LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("No Media"); + LSTR MSG_PLEASE_PREHEAT = _UxGT("Please Preheat"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Prints"); - LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completed"); + LSTR MSG_REMAINING_TIME = _UxGT("Remaining"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Total"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Longest"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruded"); #endif + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completed"); LSTR MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); LSTR MSG_INFO_PSU = _UxGT("PSU"); From 73624133c9eec397c5030b6d17ef82a29cc5007f Mon Sep 17 00:00:00 2001 From: jdegenstein Date: Thu, 6 Jan 2022 19:03:02 -0600 Subject: [PATCH 253/273] =?UTF-8?q?=F0=9F=93=8C=20LCD=5FFOR=5FMELZI=20for?= =?UTF-8?q?=20BTT=20E3=20RRF=20(#23453)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 48 ++++++++++++++++++++--- 1 file changed, 43 insertions(+), 5 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index 740164a197999..554b2704c7df9 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -197,11 +197,11 @@ #if HAS_WIRED_LCD - #if ENABLED(CR10_STOCKDISPLAY) + #if EITHER(CR10_STOCKDISPLAY, LCD_FOR_MELZI) #define BEEPER_PIN PE8 - #define BTN_ENC PE9 + #define BTN_ENC PE9 #define BTN_EN1 PE7 #define BTN_EN2 PB2 @@ -209,6 +209,40 @@ #define LCD_PINS_ENABLE PE11 #define LCD_PINS_D4 PE10 + #if ENABLED(LCD_FOR_MELZI) + + #error "CAUTION! LCD_FOR_MELZI requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. Comment out this line to continue." + + /** LCD_FOR_MELZI display pinout + * + * BTT E3 RRF Display Ribbon + * ------ ------ + * (BEEPER) PE8 |10 9 | PE9 (BTN_ENC) GND |10 9 | 5V + * (BTN_EN1) PE7 | 8 7 | RESET BEEPER | 8 7 | ESTOP (RESET) + * (BTN_EN2) PB2 6 5 | PE10 (LCD_D4) (BTN_ENC) ENC_BTN | 6 5 | LCD_SCLK (LCD_D4) + * (LCD_RS) PB1 | 4 3 | PE11 (LCD_EN) (BTN_EN2) ENC_A | 4 3 | LCD_DATA (LCD_EN) + * GND | 2 1 | 5V (BTN_EN1) ENC_B | 2 1 | LCD_CS (LCD_RS) + * ------ ------ + * EXP1 Ribbon + * + * Needs custom cable: + * + * Board Adapter Display Ribbon (coming from display) + * + * EXP1-1 ----------- EXP1-9 + * EXP1-2 ----------- EXP1-10 + * EXP1-3 ----------- EXP1-3 + * EXP1-4 ----------- EXP1-1 + * EXP1-5 ----------- EXP1-5 + * EXP1-6 ----------- EXP1-4 + * EXP1-7 ----------- EXP1-7 + * EXP1-8 ----------- EXP1-8 + * EXP1-9 ----------- EXP1-6 + * EXP1-10 ----------- EXP1-8 + */ + + #endif + #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. Comment out this line to continue." @@ -275,11 +309,15 @@ #endif #else - #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, and TFTGLCD_PANEL_(SPI|I2C) are currently supported on the BTT_E3_RRF." + #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, LCD_FOR_MELZI, and TFTGLCD_PANEL_(SPI|I2C) are currently supported on the BTT_E3_RRF." #endif // Alter timing for graphical display - #if IS_U8GLIB_ST7920 + #if ENABLED(LCD_FOR_MELZI) // LCD_FOR_MELZI default timing is too fast. This works but may be reduced. + #define BOARD_ST7920_DELAY_1 200 + #define BOARD_ST7920_DELAY_2 400 + #define BOARD_ST7920_DELAY_3 1200 + #elif IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 #define BOARD_ST7920_DELAY_3 600 @@ -306,7 +344,7 @@ * Needs custom cable: * * Board Adapter Display - * _________ + * * EXP1-1 ----------- EXP1-10 * EXP1-2 ----------- EXP1-9 * SPI1-4 ----------- EXP1-6 From 3eb794d6d5d80f5d1bf17d94ae3af29eb9263763 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 7 Jan 2022 01:13:26 +0000 Subject: [PATCH 254/273] [cron] Bump distribution date (2022-01-07) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c356855a5af8e..bba2eda1043e3 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2022-01-06" +//#define STRING_DISTRIBUTION_DATE "2022-01-07" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 845210871a583..ec1bc8950791c 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2022-01-06" + #define STRING_DISTRIBUTION_DATE "2022-01-07" #endif /** From 9564d684844fd9032eb5cec68825b7a70441e78a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 8 Jan 2022 01:06:56 +0000 Subject: [PATCH 255/273] [cron] Bump distribution date (2022-01-08) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index bba2eda1043e3..ae5519e87d8a6 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2022-01-07" +//#define STRING_DISTRIBUTION_DATE "2022-01-08" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ec1bc8950791c..a761b0955a3a0 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2022-01-07" + #define STRING_DISTRIBUTION_DATE "2022-01-08" #endif /** From 3949142214e2aae9a9f23dae811d94811fd140e1 Mon Sep 17 00:00:00 2001 From: ClockeNessMnstr Date: Sat, 8 Jan 2022 15:09:25 -0500 Subject: [PATCH 256/273] =?UTF-8?q?=F0=9F=9A=B8=20Do=20G34=20"Z=20Backoff"?= =?UTF-8?q?=20at=20full=20current?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/calibrate/G34.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G34.cpp b/Marlin/src/gcode/calibrate/G34.cpp index 98a0bdef88988..ea5d5fa150cfd 100644 --- a/Marlin/src/gcode/calibrate/G34.cpp +++ b/Marlin/src/gcode/calibrate/G34.cpp @@ -114,10 +114,6 @@ void GcodeSuite::G34() { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Final Z Move"); do_blocking_move_to_z(zgrind, MMM_TO_MMS(GANTRY_CALIBRATION_FEEDRATE)); - // Back off end plate, back to normal motion range - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Z Backoff"); - do_blocking_move_to_z(zpounce, MMM_TO_MMS(GANTRY_CALIBRATION_FEEDRATE)); - #if _REDUCE_CURRENT // Reset current to original values if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Restore Current"); @@ -146,6 +142,10 @@ void GcodeSuite::G34() { #endif #endif + // Back off end plate, back to normal motion range + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Z Backoff"); + do_blocking_move_to_z(zpounce, MMM_TO_MMS(GANTRY_CALIBRATION_FEEDRATE)); + #ifdef GANTRY_CALIBRATION_COMMANDS_POST if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Running Post Commands"); process_subcommands_now(F(GANTRY_CALIBRATION_COMMANDS_POST)); From 5a9755e5bbfdbacf74fda85baf9334a309570da2 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 9 Jan 2022 01:10:43 +0000 Subject: [PATCH 257/273] [cron] Bump distribution date (2022-01-09) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ae5519e87d8a6..8d302652092d8 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2022-01-08" +//#define STRING_DISTRIBUTION_DATE "2022-01-09" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a761b0955a3a0..e571b342a0523 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2022-01-08" + #define STRING_DISTRIBUTION_DATE "2022-01-09" #endif /** From 54f218e348f2da18d02512fba9ba4b1cc3e454e7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 9 Jan 2022 01:06:19 -0600 Subject: [PATCH 258/273] =?UTF-8?q?=F0=9F=94=A8=20Get=20FIRMWARE=5FBIN=20f?= =?UTF-8?q?rom=20env?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/PlatformIO/scripts/marlin.py | 9 ++------- 1 file changed, 2 insertions(+), 7 deletions(-) diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py index 2114a05fb388c..8ac36b7d59b5b 100644 --- a/buildroot/share/PlatformIO/scripts/marlin.py +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -49,13 +49,8 @@ def encrypt_mks(source, target, env, new_name): key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] # If FIRMWARE_BIN is defined by config, override all - import re - patt = re.compile("^\\s*#define\\s+FIRMWARE_BIN\\s+\"?(.+)\"?") - with open(join("Marlin", "Configuration.h"), encoding="utf-8") as f: - for line in f: - m = patt.search(line) - if m != None: - new_name = m.group(1) + mf = env["MARLIN_FEATURES"] + if "FIRMWARE_BIN" in mf: new_name = mf["FIRMWARE_BIN"] fwpath = target[0].path fwfile = open(fwpath, "rb") From 1363b439462af4fac2e9e3a8801abde5981575cf Mon Sep 17 00:00:00 2001 From: GHGiampy <83699429+GHGiampy@users.noreply.github.com> Date: Sun, 9 Jan 2022 08:14:03 +0100 Subject: [PATCH 259/273] =?UTF-8?q?=E2=9C=A8=20Firmware=20Upload=20via=20B?= =?UTF-8?q?inary=20Transfer=20(#23462)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 5 + Marlin/src/gcode/sd/M20.cpp | 8 +- Marlin/src/pins/pins.h | 16 +- Marlin/src/sd/cardreader.cpp | 39 +- Marlin/src/sd/cardreader.h | 11 +- .../share/scripts/MarlinBinaryProtocol.py | 434 ++++++++++++++++++ buildroot/share/scripts/upload.py | 274 +++++++++++ ini/stm32f1.ini | 7 +- 8 files changed, 770 insertions(+), 24 deletions(-) create mode 100644 buildroot/share/scripts/MarlinBinaryProtocol.py create mode 100644 buildroot/share/scripts/upload.py diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 16c5587f9c6e8..d49d2d00b9cc0 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1621,6 +1621,11 @@ // Add an optimized binary file transfer mode, initiated with 'M28 B1' //#define BINARY_FILE_TRANSFER + #if ENABLED(BINARY_FILE_TRANSFER) + // Include extra facilities (e.g., 'M20 F') supporting firmware upload via BINARY_FILE_TRANSFER + //#define CUSTOM_FIRMWARE_UPLOAD + #endif + /** * Set this option to one of the following (or the board's defaults apply): * diff --git a/Marlin/src/gcode/sd/M20.cpp b/Marlin/src/gcode/sd/M20.cpp index 5731838338540..c640309be8c87 100644 --- a/Marlin/src/gcode/sd/M20.cpp +++ b/Marlin/src/gcode/sd/M20.cpp @@ -33,7 +33,13 @@ void GcodeSuite::M20() { if (card.flag.mounted) { SERIAL_ECHOLNPGM(STR_BEGIN_FILE_LIST); - card.ls(TERN_(LONG_FILENAME_HOST_SUPPORT, parser.boolval('L'))); + card.ls( + TERN_(CUSTOM_FIRMWARE_UPLOAD, parser.boolval('F')) + #if BOTH(CUSTOM_FIRMWARE_UPLOAD, LONG_FILENAME_HOST_SUPPORT) + , + #endif + TERN_(LONG_FILENAME_HOST_SUPPORT, parser.boolval('L')) + ); SERIAL_ECHOLNPGM(STR_END_FILE_LIST); } else diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 0d24ee6696bd3..7ca78677e9ff2 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -558,21 +558,21 @@ #elif MB(CHITU3D_V9) #include "stm32f1/pins_CHITU3D_V9.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple #elif MB(CREALITY_V4) - #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple + #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_xfer env:STM32F103RET6_creality_maple #elif MB(CREALITY_V4210) - #include "stm32f1/pins_CREALITY_V4210.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple + #include "stm32f1/pins_CREALITY_V4210.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_xfer env:STM32F103RET6_creality_maple #elif MB(CREALITY_V423) - #include "stm32f1/pins_CREALITY_V423.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V423.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_xfer #elif MB(CREALITY_V427) - #include "stm32f1/pins_CREALITY_V427.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple + #include "stm32f1/pins_CREALITY_V427.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_xfer env:STM32F103RET6_creality_maple #elif MB(CREALITY_V431, CREALITY_V431_A, CREALITY_V431_B, CREALITY_V431_C, CREALITY_V431_D) - #include "stm32f1/pins_CREALITY_V431.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple + #include "stm32f1/pins_CREALITY_V431.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_xfer env:STM32F103RET6_creality_maple #elif MB(CREALITY_V452) - #include "stm32f1/pins_CREALITY_V452.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple + #include "stm32f1/pins_CREALITY_V452.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_xfer env:STM32F103RET6_creality_maple #elif MB(CREALITY_V453) - #include "stm32f1/pins_CREALITY_V453.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple + #include "stm32f1/pins_CREALITY_V453.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_xfer env:STM32F103RET6_creality_maple #elif MB(CREALITY_V24S1) - #include "stm32f1/pins_CREALITY_V24S1.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple + #include "stm32f1/pins_CREALITY_V24S1.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_xfer env:STM32F103RET6_creality_maple #elif MB(TRIGORILLA_PRO) #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro env:trigorilla_pro_maple #elif MB(FLY_MINI) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 66c08b6455cfd..25f9d7d802f95 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -195,11 +195,15 @@ char *createFilename(char * const buffer, const dir_t &p) { } // -// Return 'true' if the item is a folder or G-code file +// Return 'true' if the item is something Marlin can read // -bool CardReader::is_dir_or_gcode(const dir_t &p) { +bool CardReader::is_visible_entity(const dir_t &p OPTARG(CUSTOM_FIRMWARE_UPLOAD, bool onlyBin/*=false*/)) { //uint8_t pn0 = p.name[0]; + #if DISABLED(CUSTOM_FIRMWARE_UPLOAD) + constexpr bool onlyBin = false; + #endif + if ( (p.attributes & DIR_ATT_HIDDEN) // Hidden by attribute // When readDir() > 0 these must be false: //|| pn0 == DIR_NAME_FREE || pn0 == DIR_NAME_DELETED // Clear or Deleted entry @@ -211,7 +215,11 @@ bool CardReader::is_dir_or_gcode(const dir_t &p) { return ( flag.filenameIsDir // All Directories are ok - || (p.name[8] == 'G' && p.name[9] != '~') // Non-backup *.G* files are accepted + || (!onlyBin && p.name[8] == 'G' + && p.name[9] != '~') // Non-backup *.G* files are accepted + || ( onlyBin && p.name[8] == 'B' + && p.name[9] == 'I' + && p.name[10] == 'N') // BIN files are accepted ); } @@ -222,7 +230,7 @@ int CardReader::countItems(SdFile dir) { dir_t p; int c = 0; while (dir.readDir(&p, longFilename) > 0) - c += is_dir_or_gcode(p); + c += is_visible_entity(p); #if ALL(SDCARD_SORT_ALPHA, SDSORT_USES_RAM, SDSORT_CACHE_NAMES) nrFiles = c; @@ -237,7 +245,7 @@ int CardReader::countItems(SdFile dir) { void CardReader::selectByIndex(SdFile dir, const uint8_t index) { dir_t p; for (uint8_t cnt = 0; dir.readDir(&p, longFilename) > 0;) { - if (is_dir_or_gcode(p)) { + if (is_visible_entity(p)) { if (cnt == index) { createFilename(filename, p); return; // 0 based index @@ -253,7 +261,7 @@ void CardReader::selectByIndex(SdFile dir, const uint8_t index) { void CardReader::selectByName(SdFile dir, const char * const match) { dir_t p; for (uint8_t cnt = 0; dir.readDir(&p, longFilename) > 0; cnt++) { - if (is_dir_or_gcode(p)) { + if (is_visible_entity(p)) { createFilename(filename, p); if (strcasecmp(match, filename) == 0) return; } @@ -272,6 +280,7 @@ void CardReader::selectByName(SdFile dir, const char * const match) { */ void CardReader::printListing( SdFile parent, const char * const prepend + OPTARG(CUSTOM_FIRMWARE_UPLOAD, bool onlyBin/*=false*/) OPTARG(LONG_FILENAME_HOST_SUPPORT, const bool includeLongNames/*=false*/) OPTARG(LONG_FILENAME_HOST_SUPPORT, const char * const prependLong/*=nullptr*/) ) { @@ -297,12 +306,12 @@ void CardReader::printListing( char pathLong[lenPrependLong + strlen(longFilename) + 1]; if (prependLong) { strcpy(pathLong, prependLong); pathLong[lenPrependLong - 1] = '/'; } strcpy(pathLong + lenPrependLong, longFilename); - printListing(child, path, true, pathLong); + printListing(child, path OPTARG(CUSTOM_FIRMWARE_UPLOAD, onlyBin), true, pathLong); } else - printListing(child, path); + printListing(child, path OPTARG(CUSTOM_FIRMWARE_UPLOAD, onlyBin)); #else - printListing(child, path); + printListing(child, path OPTARG(CUSTOM_FIRMWARE_UPLOAD, onlyBin)); #endif } else { @@ -310,7 +319,7 @@ void CardReader::printListing( return; } } - else if (is_dir_or_gcode(p)) { + else if (is_visible_entity(p OPTARG(CUSTOM_FIRMWARE_UPLOAD, onlyBin))) { if (prepend) { SERIAL_ECHO(prepend); SERIAL_CHAR('/'); } SERIAL_ECHO(createFilename(filename, p)); SERIAL_CHAR(' '); @@ -330,10 +339,16 @@ void CardReader::printListing( // // List all files on the SD card // -void CardReader::ls(TERN_(LONG_FILENAME_HOST_SUPPORT, bool includeLongNames/*=false*/)) { +void CardReader::ls( + TERN_(CUSTOM_FIRMWARE_UPLOAD, const bool onlyBin/*=false*/) + #if BOTH(CUSTOM_FIRMWARE_UPLOAD, LONG_FILENAME_HOST_SUPPORT) + , + #endif + TERN_(LONG_FILENAME_HOST_SUPPORT, const bool includeLongNames/*=false*/) +) { if (flag.mounted) { root.rewind(); - printListing(root, nullptr OPTARG(LONG_FILENAME_HOST_SUPPORT, includeLongNames)); + printListing(root, nullptr OPTARG(CUSTOM_FIRMWARE_UPLOAD, onlyBin) OPTARG(LONG_FILENAME_HOST_SUPPORT, includeLongNames)); } } diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 8761f57de53cd..2b3dcd00fbfbf 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -204,7 +204,13 @@ class CardReader { FORCE_INLINE static void getfilename_sorted(const uint16_t nr) { selectFileByIndex(nr); } #endif - static void ls(TERN_(LONG_FILENAME_HOST_SUPPORT, bool includeLongNames=false)); + static void ls( + TERN_(CUSTOM_FIRMWARE_UPLOAD, const bool onlyBin=false) + #if BOTH(CUSTOM_FIRMWARE_UPLOAD, LONG_FILENAME_HOST_SUPPORT) + , + #endif + TERN_(LONG_FILENAME_HOST_SUPPORT, const bool includeLongNames=false) + ); #if ENABLED(POWER_LOSS_RECOVERY) static bool jobRecoverFileExists(); @@ -331,12 +337,13 @@ class CardReader { // // Directory items // - static bool is_dir_or_gcode(const dir_t &p); + static bool is_visible_entity(const dir_t &p OPTARG(CUSTOM_FIRMWARE_UPLOAD, const bool onlyBin=false)); static int countItems(SdFile dir); static void selectByIndex(SdFile dir, const uint8_t index); static void selectByName(SdFile dir, const char * const match); static void printListing( SdFile parent, const char * const prepend + OPTARG(CUSTOM_FIRMWARE_UPLOAD, const bool onlyBin=false) OPTARG(LONG_FILENAME_HOST_SUPPORT, const bool includeLongNames=false) OPTARG(LONG_FILENAME_HOST_SUPPORT, const char * const prependLong=nullptr) ); diff --git a/buildroot/share/scripts/MarlinBinaryProtocol.py b/buildroot/share/scripts/MarlinBinaryProtocol.py new file mode 100644 index 0000000000000..4887ad9919789 --- /dev/null +++ b/buildroot/share/scripts/MarlinBinaryProtocol.py @@ -0,0 +1,434 @@ +# +# MarlinBinaryProtocol.py +# Supporting Firmware upload via USB/Serial, saving to the attached media. +# +import serial +import math +import time +from collections import deque +import threading +import sys +import datetime +import random +try: + import heatshrink + heatshrink_exists = True +except ImportError: + heatshrink_exists = False + + +def millis(): + return time.perf_counter() * 1000 + +class TimeOut(object): + def __init__(self, milliseconds): + self.duration = milliseconds + self.reset() + + def reset(self): + self.endtime = millis() + self.duration + + def timedout(self): + return millis() > self.endtime + +class ReadTimeout(Exception): + pass +class FatalError(Exception): + pass +class SycronisationError(Exception): + pass +class PayloadOverflow(Exception): + pass +class ConnectionLost(Exception): + pass + +class Protocol(object): + device = None + baud = None + max_block_size = 0 + port = None + block_size = 0 + + packet_transit = None + packet_status = None + packet_ping = None + + errors = 0 + packet_buffer = None + simulate_errors = 0 + sync = 0 + connected = False + syncronised = False + worker_thread = None + + response_timeout = 1000 + + applications = [] + responses = deque() + + def __init__(self, device, baud, bsize, simerr, timeout): + print("pySerial Version:", serial.VERSION) + self.port = serial.Serial(device, baudrate = baud, write_timeout = 0, timeout = 1) + self.device = device + self.baud = baud + self.block_size = int(bsize) + self.simulate_errors = max(min(simerr, 1.0), 0.0); + self.connected = True + self.response_timeout = timeout + + self.register(['ok', 'rs', 'ss', 'fe'], self.process_input) + + self.worker_thread = threading.Thread(target=Protocol.receive_worker, args=(self,)) + self.worker_thread.start() + + def receive_worker(self): + while self.port.in_waiting: + self.port.reset_input_buffer() + + def dispatch(data): + for tokens, callback in self.applications: + for token in tokens: + if token == data[:len(token)]: + callback((token, data[len(token):])) + return + + def reconnect(): + print("Reconnecting..") + self.port.close() + for x in range(10): + try: + if self.connected: + self.port = serial.Serial(self.device, baudrate = self.baud, write_timeout = 0, timeout = 1) + return + else: + print("Connection closed") + return + except: + time.sleep(1) + raise ConnectionLost() + + while self.connected: + try: + data = self.port.readline().decode('utf8').rstrip() + if len(data): + #print(data) + dispatch(data) + except OSError: + reconnect() + except UnicodeDecodeError: + # dodgy client output or datastream corruption + self.port.reset_input_buffer() + + def shutdown(self): + self.connected = False + self.worker_thread.join() + self.port.close() + + def process_input(self, data): + #print(data) + self.responses.append(data) + + def register(self, tokens, callback): + self.applications.append((tokens, callback)) + + def send(self, protocol, packet_type, data = bytearray()): + self.packet_transit = self.build_packet(protocol, packet_type, data) + self.packet_status = 0 + self.transmit_attempt = 0 + + timeout = TimeOut(self.response_timeout * 20) + while self.packet_status == 0: + try: + if timeout.timedout(): + raise ConnectionLost() + self.transmit_packet(self.packet_transit) + self.await_response() + except ReadTimeout: + self.errors += 1 + #print("Packetloss detected..") + self.packet_transit = None + + def await_response(self): + timeout = TimeOut(self.response_timeout) + while not len(self.responses): + time.sleep(0.00001) + if timeout.timedout(): + raise ReadTimeout() + + while len(self.responses): + token, data = self.responses.popleft() + switch = {'ok' : self.response_ok, 'rs': self.response_resend, 'ss' : self.response_stream_sync, 'fe' : self.response_fatal_error} + switch[token](data) + + def send_ascii(self, data, send_and_forget = False): + self.packet_transit = bytearray(data, "utf8") + b'\n' + self.packet_status = 0 + self.transmit_attempt = 0 + + timeout = TimeOut(self.response_timeout * 20) + while self.packet_status == 0: + try: + if timeout.timedout(): + return + self.port.write(self.packet_transit) + if send_and_forget: + self.packet_status = 1 + else: + self.await_response_ascii() + except ReadTimeout: + self.errors += 1 + #print("Packetloss detected..") + except serial.serialutil.SerialException: + return + self.packet_transit = None + + def await_response_ascii(self): + timeout = TimeOut(self.response_timeout) + while not len(self.responses): + time.sleep(0.00001) + if timeout.timedout(): + raise ReadTimeout() + token, data = self.responses.popleft() + self.packet_status = 1 + + def corrupt_array(self, data): + rid = random.randint(0, len(data) - 1) + data[rid] ^= 0xAA + return data + + def transmit_packet(self, packet): + packet = bytearray(packet) + if(self.simulate_errors > 0 and random.random() > (1.0 - self.simulate_errors)): + if random.random() > 0.9: + #random data drop + start = random.randint(0, len(packet)) + end = start + random.randint(1, 10) + packet = packet[:start] + packet[end:] + #print("Dropping {0} bytes".format(end - start)) + else: + #random corruption + packet = self.corrupt_array(packet) + #print("Single byte corruption") + self.port.write(packet) + self.transmit_attempt += 1 + + def build_packet(self, protocol, packet_type, data = bytearray()): + PACKET_TOKEN = 0xB5AD + + if len(data) > self.max_block_size: + raise PayloadOverflow() + + packet_buffer = bytearray() + + packet_buffer += self.pack_int8(self.sync) # 8bit sync id + packet_buffer += self.pack_int4_2(protocol, packet_type) # 4 bit protocol id, 4 bit packet type + packet_buffer += self.pack_int16(len(data)) # 16bit packet length + packet_buffer += self.pack_int16(self.build_checksum(packet_buffer)) # 16bit header checksum + + if len(data): + packet_buffer += data + packet_buffer += self.pack_int16(self.build_checksum(packet_buffer)) + + packet_buffer = self.pack_int16(PACKET_TOKEN) + packet_buffer # 16bit start token, not included in checksum + return packet_buffer + + # checksum 16 fletchers + def checksum(self, cs, value): + cs_low = (((cs & 0xFF) + value) % 255); + return ((((cs >> 8) + cs_low) % 255) << 8) | cs_low; + + def build_checksum(self, buffer): + cs = 0 + for b in buffer: + cs = self.checksum(cs, b) + return cs + + def pack_int32(self, value): + return value.to_bytes(4, byteorder='little') + + def pack_int16(self, value): + return value.to_bytes(2, byteorder='little') + + def pack_int8(self, value): + return value.to_bytes(1, byteorder='little') + + def pack_int4_2(self, vh, vl): + value = ((vh & 0xF) << 4) | (vl & 0xF) + return value.to_bytes(1, byteorder='little') + + def connect(self): + print("Connecting: Switching Marlin to Binary Protocol...") + self.send_ascii("M28B1") + self.send(0, 1) + + def disconnect(self): + self.send(0, 2) + self.syncronised = False + + def response_ok(self, data): + try: + packet_id = int(data); + except ValueError: + return + if packet_id != self.sync: + raise SycronisationError() + self.sync = (self.sync + 1) % 256 + self.packet_status = 1 + + def response_resend(self, data): + packet_id = int(data); + self.errors += 1 + if not self.syncronised: + print("Retrying syncronisation") + elif packet_id != self.sync: + raise SycronisationError() + + def response_stream_sync(self, data): + sync, max_block_size, protocol_version = data.split(',') + self.sync = int(sync) + self.max_block_size = int(max_block_size) + self.block_size = self.max_block_size if self.max_block_size < self.block_size else self.block_size + self.protocol_version = protocol_version + self.packet_status = 1 + self.syncronised = True + print("Connection synced [{0}], binary protocol version {1}, {2} byte payload buffer".format(self.sync, self.protocol_version, self.max_block_size)) + + def response_fatal_error(self, data): + raise FatalError() + + +class FileTransferProtocol(object): + protocol_id = 1 + + class Packet(object): + QUERY = 0 + OPEN = 1 + CLOSE = 2 + WRITE = 3 + ABORT = 4 + + responses = deque() + def __init__(self, protocol, timeout = None): + protocol.register(['PFT:success', 'PFT:version:', 'PFT:fail', 'PFT:busy', 'PFT:ioerror', 'PTF:invalid'], self.process_input) + self.protocol = protocol + self.response_timeout = timeout or protocol.response_timeout + + def process_input(self, data): + #print(data) + self.responses.append(data) + + def await_response(self, timeout = None): + timeout = TimeOut(timeout or self.response_timeout) + while not len(self.responses): + time.sleep(0.0001) + if timeout.timedout(): + raise ReadTimeout() + + return self.responses.popleft() + + def connect(self): + self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.QUERY); + + token, data = self.await_response() + if token != 'PFT:version:': + return False + + self.version, _, compression = data.split(':') + if compression != 'none': + algorithm, window, lookahead = compression.split(',') + self.compression = {'algorithm': algorithm, 'window': int(window), 'lookahead': int(lookahead)} + else: + self.compression = {'algorithm': 'none'} + + print("File Transfer version: {0}, compression: {1}".format(self.version, self.compression['algorithm'])) + + def open(self, filename, compression, dummy): + payload = b'\1' if dummy else b'\0' # dummy transfer + payload += b'\1' if compression else b'\0' # payload compression + payload += bytearray(filename, 'utf8') + b'\0'# target filename + null terminator + + timeout = TimeOut(5000) + token = None + self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.OPEN, payload); + while token != 'PFT:success' and not timeout.timedout(): + try: + token, data = self.await_response(1000) + if token == 'PFT:success': + print(filename,"opened") + return + elif token == 'PFT:busy': + print("Broken transfer detected, purging") + self.abort() + time.sleep(0.1) + self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.OPEN, payload); + timeout.reset() + elif token == 'PFT:fail': + raise Exception("Can not open file on client") + except ReadTimeout: + pass + raise ReadTimeout() + + def write(self, data): + self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.WRITE, data); + + def close(self): + self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.CLOSE); + token, data = self.await_response(1000) + if token == 'PFT:success': + print("File closed") + return + elif token == 'PFT:ioerror': + print("Client storage device IO error") + elif token == 'PFT:invalid': + print("No open file") + + def abort(self): + self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.ABORT); + token, data = self.await_response() + if token == 'PFT:success': + print("Transfer Aborted") + + 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 + + data = open(filename, "rb").read() + filesize = len(data) + + self.open(dest_filename, compression_support, dummy) + + block_size = self.protocol.block_size + if compression_support: + data = heatshrink.encode(data, window_sz2=self.compression['window'], lookahead_sz2=self.compression['lookahead']) + + cratio = filesize / len(data) + + blocks = math.floor((len(data) + block_size - 1) / block_size) + kibs = 0 + dump_pctg = 0 + start_time = millis() + for i in range(blocks): + start = block_size * i + end = start + block_size + 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.2f}% {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='') + dump_pctg += 0.1 + print("\r{0:2.2f}% {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% + + self.close() + print("Transfer complete") + + +class EchoProtocol(object): + def __init__(self, protocol): + protocol.register(['echo:'], self.process_input) + self.protocol = protocol + + def process_input(self, data): + print(data) diff --git a/buildroot/share/scripts/upload.py b/buildroot/share/scripts/upload.py new file mode 100644 index 0000000000000..4a152067a4a28 --- /dev/null +++ b/buildroot/share/scripts/upload.py @@ -0,0 +1,274 @@ +import argparse +import sys +import os +import time +import random +import serial + +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 + +# Internal debug flag +Debug = False + +#-----------------# +# Upload Callback # +#-----------------# +def Upload(source, target, env): + + #------------------# + # Marlin functions # + #------------------# + def _GetMarlinEnv(marlinEnv, feature): + if not marlinEnv: return None + return marlinEnv[feature] if feature in marlinEnv else None + + #----------------# + # Port functions # + #----------------# + def _GetUploadPort(env): + if Debug: print('Autodetecting upload port...') + env.AutodetectUploadPort(env) + port = env.subst('$UPLOAD_PORT') + if not port: + raise Exception('Error detecting the upload port.') + if Debug: print('OK') + return port + + #-------------------------# + # Simple serial functions # + #-------------------------# + def _Send(data): + if Debug: print(f'>> {data}') + strdata = bytearray(data, 'utf8') + b'\n' + port.write(strdata) + time.sleep(0.010) + + def _Recv(): + clean_responses = [] + responses = port.readlines() + for Resp in responses: + # Test: suppress invaid chars (coming from debug info) + try: + clean_response = Resp.decode('utf8').rstrip().lstrip() + clean_responses.append(clean_response) + except: + pass + if Debug: print(f'<< {clean_response}') + return clean_responses + + #------------------# + # SDCard functions # + #------------------# + def _CheckSDCard(): + if Debug: print('Checking SD card...') + _Send('M21') + Responses = _Recv() + if len(Responses) < 1 or not any('SD card ok' in r for r in Responses): + raise Exception('Error accessing SD card') + if Debug: print('SD Card OK') + return True + + #----------------# + # File functions # + #----------------# + def _GetFirmwareFiles(): + if Debug: print('Get firmware files...') + _Send('M20 F') + Responses = _Recv() + if len(Responses) < 3 or not any('file list' in r for r in Responses): + raise Exception('Error getting firmware files') + if Debug: print('OK') + return Responses + + def _FilterFirmwareFiles(FirmwareList): + Firmwares = [] + for FWFile in FirmwareList: + if not '/' in FWFile and '.BIN' in FWFile: + idx = FWFile.index('.BIN') + Firmwares.append(FWFile[:idx+4]) + return Firmwares + + def _RemoveFirmwareFile(FirmwareFile): + _Send(f'M30 /{FirmwareFile}') + Responses = _Recv() + Removed = len(Responses) >= 1 and any('File deleted' in r for r in Responses) + if not Removed: + raise Exception(f"Firmware file '{FirmwareFile}' not removed") + return Removed + + + #---------------------# + # Callback Entrypoint # + #---------------------# + port = None + protocol = None + filetransfer = None + + # Get Marlin evironment vars + MarlinEnv = env['MARLIN_FEATURES'] + marlin_pioenv = _GetMarlinEnv(MarlinEnv, 'PIOENV') + marlin_motherboard = _GetMarlinEnv(MarlinEnv, 'MOTHERBOARD') + marlin_board_info_name = _GetMarlinEnv(MarlinEnv, 'BOARD_INFO_NAME') + marlin_board_custom_build_flags = _GetMarlinEnv(MarlinEnv, 'BOARD_CUSTOM_BUILD_FLAGS') + marlin_firmware_bin = _GetMarlinEnv(MarlinEnv, 'FIRMWARE_BIN') + marlin_custom_firmware_upload = _GetMarlinEnv(MarlinEnv, 'CUSTOM_FIRMWARE_UPLOAD') is not None + marlin_short_build_version = _GetMarlinEnv(MarlinEnv, 'SHORT_BUILD_VERSION') + marlin_string_config_h_author = _GetMarlinEnv(MarlinEnv, 'STRING_CONFIG_H_AUTHOR') + + # Get firmware upload params + upload_firmware_source_name = str(source[0]) # Source firmware filename + upload_speed = env['UPLOAD_SPEED'] if 'UPLOAD_SPEED' in env else 115200 + # baud rate of serial connection + upload_port = _GetUploadPort(env) # Serial port to use + + # Set local upload params + upload_firmware_target_name = os.path.basename(upload_firmware_source_name) # WARNING! Need rework on "binary_stream" to allow filename > 8.3 + # Target firmware filename + upload_timeout = 1000 # Communication timout, lossy/slow connections need higher values + upload_blocksize = 512 # Transfer block size. 512 = Autodetect + upload_compression = True # Enable compression + upload_error_ratio = 0 # Simulated corruption ratio + upload_test = False # Benchmark the serial link without storing the file + upload_reset = True # Trigger a soft reset for firmware update after the upload + + # Set local upload params based on board type to change script behavior + # "upload_delete_old_bins": delete all *.bin files in the root of SD Card + upload_delete_old_bins = marlin_motherboard in ['BOARD_CREALITY_V4', 'BOARD_CREALITY_V4210', 'BOARD_CREALITY_V423', 'BOARD_CREALITY_V427', + 'BOARD_CREALITY_V431', 'BOARD_CREALITY_V452', 'BOARD_CREALITY_V453', 'BOARD_CREALITY_V24S1'] + try: + + # Start upload job + print(f"Uploading firmware '{os.path.basename(upload_firmware_target_name)}' to '{marlin_motherboard}' via '{upload_port}'") + + # Dump some debug info + if Debug: + print('Upload using:') + print('---- Marlin --------------------') + print(f' PIOENV : {marlin_pioenv}') + print(f' SHORT_BUILD_VERSION : {marlin_short_build_version}') + print(f' STRING_CONFIG_H_AUTHOR : {marlin_string_config_h_author}') + print(f' MOTHERBOARD : {marlin_motherboard}') + print(f' BOARD_INFO_NAME : {marlin_board_info_name}') + print(f' CUSTOM_BUILD_FLAGS : {marlin_board_custom_build_flags}') + print(f' FIRMWARE_BIN : {marlin_firmware_bin}') + print(f' CUSTOM_FIRMWARE_UPLOAD : {marlin_custom_firmware_upload}') + print('---- Upload parameters ---------') + print(f' Source : {upload_firmware_source_name}') + print(f' Target : {upload_firmware_target_name}') + print(f' Port : {upload_port} @ {upload_speed} baudrate') + print(f' Timeout : {upload_timeout}') + print(f' Block size : {upload_blocksize}') + print(f' Compression : {upload_compression}') + print(f' Error ratio : {upload_error_ratio}') + print(f' Test : {upload_test}') + print(f' Reset : {upload_reset}') + print('--------------------------------') + + # Custom implementations based on board parameters + + # Delete all *.bin files on the root of SD Card (if flagged) + if upload_delete_old_bins: + # CUSTOM_FIRMWARE_UPLOAD is needed for this feature + if not marlin_custom_firmware_upload: + raise Exception(f"CUSTOM_FIRMWARE_UPLOAD must be enabled in 'Configuration_adv.h' for '{marlin_motherboard}'") + + # Generate a new 8.3 random filename + # This board remember the last firmware filename and doesn't allow to flash from that filename + upload_firmware_target_name = f"fw-{''.join(random.choices('ABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789', k=5))}.BIN" + print(f"Board {marlin_motherboard}: Overriding firmware filename to '{upload_firmware_target_name}'") + + # Init serial port + port = serial.Serial(upload_port, baudrate = upload_speed, write_timeout = 0, timeout = 0.1) + port.reset_input_buffer() + + # Check SD card status + _CheckSDCard() + + # Get firmware files + FirmwareFiles = _GetFirmwareFiles() + if Debug: + for FirmwareFile in FirmwareFiles: + print(f'Found: {FirmwareFile}') + + # Get all 1st level firmware files (to remove) + OldFirmwareFiles = _FilterFirmwareFiles(FirmwareFiles[1:len(FirmwareFiles)-2]) # Skip header and footers of list + if len(OldFirmwareFiles) == 0: + print('No old firmware files to delete') + else: + print(f"Remove {len(OldFirmwareFiles)} old firmware file{'s' if len(OldFirmwareFiles) != 1 else ''}:") + for OldFirmwareFile in OldFirmwareFiles: + print(f" -Removing- '{OldFirmwareFile}'...") + print(' OK' if _RemoveFirmwareFile(OldFirmwareFile) else ' Error!') + + # Close serial + port.close() + + # Cleanup completed + if Debug: print('Cleanup completed') + + # WARNING! The serial port must be closed here because the serial transfer that follow needs it! + + # Upload firmware file + if Debug: print(f"Copy '{upload_firmware_source_name}' --> '{upload_firmware_target_name}'") + protocol = MarlinBinaryProtocol.Protocol(upload_port, upload_speed, upload_blocksize, float(upload_error_ratio), int(upload_timeout)) + #echologger = MarlinBinaryProtocol.EchoProtocol(protocol) + protocol.connect() + filetransfer = MarlinBinaryProtocol.FileTransferProtocol(protocol) + filetransfer.copy(upload_firmware_source_name, upload_firmware_target_name, upload_compression, upload_test) + protocol.disconnect() + + # Notify upload completed + protocol.send_ascii('M117 Firmware uploaded') + + # Remount SD card + print('Wait for SD card release...') + time.sleep(1) + print('Remount SD card') + protocol.send_ascii('M21') + + # Trigger firmware update + if upload_reset: + print('Trigger firmware update...') + protocol.send_ascii('M997', True) + + protocol: protocol.shutdown() + print('Firmware update completed') + + except KeyboardInterrupt: + if port: port.close() + if filetransfer: filetransfer.abort() + if protocol: protocol.shutdown() + raise + + except serial.SerialException as se: + if port: port.close() + print(f'Serial excepion: {se}') + raise Exception(se) + + except MarlinBinaryProtocol.FatalError: + if port: port.close() + if protocol: protocol.shutdown() + print('Too many retries, Abort') + raise + + except: + if port: port.close() + if protocol: protocol.shutdown() + print('Firmware not updated') + raise + +# Attach custom upload callback +env.Replace(UPLOADCMD=Upload) diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 939f51ffbf691..a0957dbaece3d 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -100,7 +100,6 @@ build_flags = ${common_STM32F103RC_variant.build_flags} -DTIMER_SERVO=TIM5 -DDEFAULT_SPI=3 build_unflags = ${common_STM32F103RC_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC -monitor_speed = 115200 debug_tool = stlink # @@ -124,6 +123,12 @@ monitor_speed = 115200 debug_tool = jlink upload_protocol = jlink +[env:STM32F103RET6_creality_xfer] +extends = env:STM32F103RET6_creality +extra_scripts = ${env:STM32F103RET6_creality.extra_scripts} + pre:buildroot/share/scripts/upload.py +upload_protocol = custom + # # BigTree SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) # From 0026430835eb4d707cc3d14e44c887e0ad9f39ed Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Sun, 9 Jan 2022 02:24:56 -0500 Subject: [PATCH 260/273] =?UTF-8?q?=F0=9F=A9=B9=20Reset=20DWIN=20CrealityU?= =?UTF-8?q?I=20print=20progress=20on=20start=20(#23481)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/e3v2/creality/dwin.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 3eed9650c1e76..03f08ac184352 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -1754,7 +1754,7 @@ void update_variable() { if (_new_hotend_target) Draw_Stat_Int(25 + 4 * STAT_CHR_W + 6, 384, _hotendtarget); - static int16_t _flow = planner.flow_percentage[0]; + static int16_t _flow = 0; if (_flow != planner.flow_percentage[0]) { _flow = planner.flow_percentage[0]; Draw_Stat_Int(116 + 2 * STAT_CHR_W, 417, _flow); @@ -1768,7 +1768,7 @@ void update_variable() { Draw_Stat_Int(25 + 4 * STAT_CHR_W + 6, 417, _bedtarget); #endif - static int16_t _feedrate = 100; + static int16_t _feedrate = 0; if (_feedrate != feedrate_percentage) { _feedrate = feedrate_percentage; Draw_Stat_Int(116 + 2 * STAT_CHR_W, 384, _feedrate); @@ -2269,6 +2269,8 @@ void HMI_SelectFile() { // thermalManager.fan_speed[i] = 255; #endif + _card_percent = 0; + _remain_time = 0; Goto_PrintProcess(); } } @@ -4176,10 +4178,7 @@ void EachMomentUpdate() { } #if ENABLED(POWER_LOSS_RECOVERY) else if (DWIN_lcd_sd_status && recovery.dwin_flag) { // resume print before power off - static bool recovery_flag = false; - recovery.dwin_flag = false; - recovery_flag = true; auto update_selection = [&](const bool sel) { HMI_flag.select_flag = sel; @@ -4199,6 +4198,7 @@ void EachMomentUpdate() { DWIN_Draw_String(true, font8x16, Popup_Text_Color, Color_Bg_Window, npos, 252, name); DWIN_UpdateLCD(); + bool recovery_flag = true; while (recovery_flag) { EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { From e0d19f9f419bd6150324672872a2314e98ee5e6b Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Sun, 9 Jan 2022 02:29:36 -0500 Subject: [PATCH 261/273] =?UTF-8?q?=F0=9F=90=9B=20Fix=20EEPROM=5FINIT=5FNO?= =?UTF-8?q?W=20build=20hash=20test=20(#23479)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/settings.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index a1525754549f0..750aab74fda78 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -1584,7 +1584,7 @@ void MarlinSettings::postprocess() { #if ENABLED(EEPROM_INIT_NOW) uint32_t stored_hash; EEPROM_READ_ALWAYS(stored_hash); - if (stored_hash != build_hash) { EEPROM_FINISH(); return true; } + if (stored_hash != build_hash) { EEPROM_FINISH(); return false; } #endif uint16_t stored_crc; From 6ce0c682bb0ab96dcb3e1d6720c5cc0ff66dad9a Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Sun, 9 Jan 2022 03:37:09 -0500 Subject: [PATCH 262/273] =?UTF-8?q?=F0=9F=9A=B8=20BLTouch=20HS=20menu=20it?= =?UTF-8?q?em=20for=20DWIN=20Enhanced=20UI=20(#23480)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/e3v2/enhanced/dwin.cpp | 391 ++++++++++++++------------ Marlin/src/lcd/e3v2/enhanced/dwinui.h | 5 +- 2 files changed, 208 insertions(+), 188 deletions(-) diff --git a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp index 294d09956ab0d..f12f981b72895 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwin.cpp +++ b/Marlin/src/lcd/e3v2/enhanced/dwin.cpp @@ -71,6 +71,10 @@ #include "../../../module/probe.h" #endif +#ifdef BLTOUCH_HS_MODE + #include "../../../feature/bltouch.h" +#endif + #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) #include "../../../feature/babystep.h" #endif @@ -2300,6 +2304,14 @@ void SetPID(celsius_t t, heater_id_t h) { } void ProbeStow() { probe.stow(); } void ProbeDeploy() { probe.deploy(); } + + #ifdef BLTOUCH_HS_MODE + void SetHSMode() { + bltouch.high_speed_mode = !bltouch.high_speed_mode; + Draw_Chkb_Line(CurrentMenu->line(), bltouch.high_speed_mode); + DWIN_UpdateLCD(); + } + #endif #endif #if HAS_FILAMENT_SENSOR @@ -2757,6 +2769,10 @@ void onDrawLanguage(MenuItemClass* menuitem, int8_t line) { void onDrawEnableSound(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, ui.buzzer_enabled); } #endif +#ifdef BLTOUCH_HS_MODE + void onDrawHSMode(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, bltouch.high_speed_mode); } +#endif + void onDrawSelColorItem(MenuItemClass* menuitem, int8_t line) { const uint16_t color = *(uint16_t*)static_cast(menuitem)->value; DWIN_Draw_Rectangle(0, HMI_data.Highlight_Color, ICOX + 1, MBASE(line) - 1 + 1, ICOX + 18, MBASE(line) - 1 + 18); @@ -3177,41 +3193,41 @@ void Draw_Prepare_Menu() { CurrentMenu = PrepareMenu; SetMenuTitle({133, 1, 28, 13}, GET_TEXT_F(MSG_PREPARE)); DWINUI::MenuItemsPrepare(13); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); #if ENABLED(ADVANCED_PAUSE_FEATURE) - ADDMENUITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENT_MAN), onDrawSubMenu, Draw_FilamentMan_Menu); + MENU_ITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENT_MAN), onDrawSubMenu, Draw_FilamentMan_Menu); #endif - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_MOVE_AXIS), onDrawMoveSubMenu, Goto_Move_Menu); - ADDMENUITEM(ICON_Tram, GET_TEXT_F(MSG_BED_TRAMMING), onDrawSubMenu, Draw_Tramming_Menu); - ADDMENUITEM(ICON_CloseMotor, GET_TEXT_F(MSG_DISABLE_STEPPERS), onDrawDisableMotors, DisableMotors); + MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_MOVE_AXIS), onDrawMoveSubMenu, Goto_Move_Menu); + MENU_ITEM(ICON_Tram, GET_TEXT_F(MSG_BED_TRAMMING), onDrawSubMenu, Draw_Tramming_Menu); + MENU_ITEM(ICON_CloseMotor, GET_TEXT_F(MSG_DISABLE_STEPPERS), onDrawDisableMotors, DisableMotors); #if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) - ADDMENUITEM(ICON_Homing, GET_TEXT_F(MSG_HOMING), onDrawSubMenu, Draw_Homing_Menu); + MENU_ITEM(ICON_Homing, GET_TEXT_F(MSG_HOMING), onDrawSubMenu, Draw_Homing_Menu); #else - ADDMENUITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawAutoHome, AutoHome); + MENU_ITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawAutoHome, AutoHome); #endif #if ENABLED(MESH_BED_LEVELING) - ADDMENUITEM(ICON_ManualMesh, GET_TEXT_F(MSG_MANUAL_MESH), onDrawSubMenu, Draw_ManualMesh_Menu); + MENU_ITEM(ICON_ManualMesh, GET_TEXT_F(MSG_MANUAL_MESH), onDrawSubMenu, Draw_ManualMesh_Menu); #endif #if HAS_ZOFFSET_ITEM #if HAS_BED_PROBE - ADDMENUITEM(ICON_SetZOffset, GET_TEXT_F(MSG_PROBE_WIZARD), onDrawSubMenu, Draw_ZOffsetWiz_Menu); + MENU_ITEM(ICON_SetZOffset, GET_TEXT_F(MSG_PROBE_WIZARD), onDrawSubMenu, Draw_ZOffsetWiz_Menu); #elif ENABLED(BABYSTEPPING) - ADDMENUITEM_P(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); + EDIT_ITEM(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); #else - ADDMENUITEM(ICON_SetHome, GET_TEXT_F(MSG_SET_HOME_OFFSETS), onDrawHomeOffset, SetHome); + MENU_ITEM(ICON_SetHome, GET_TEXT_F(MSG_SET_HOME_OFFSETS), onDrawHomeOffset, SetHome); #endif #endif #if HAS_PREHEAT - ADDMENUITEM(ICON_PLAPreheat, GET_TEXT_F(MSG_PREHEAT_1), onDrawPreheat1, DoPreheat0); + MENU_ITEM(ICON_PLAPreheat, GET_TEXT_F(MSG_PREHEAT_1), onDrawPreheat1, DoPreheat0); #if PREHEAT_COUNT > 1 - ADDMENUITEM(ICON_ABSPreheat, PSTR("Preheat " PREHEAT_2_LABEL), onDrawPreheat2, DoPreheat1); + MENU_ITEM(ICON_ABSPreheat, PSTR("Preheat " PREHEAT_2_LABEL), onDrawPreheat2, DoPreheat1); #endif #if PREHEAT_COUNT > 2 - ADDMENUITEM(ICON_CustomPreheat, GET_TEXT_F(MSG_PREHEAT_CUSTOM), onDrawMenuItem, DoPreheat2); + MENU_ITEM(ICON_CustomPreheat, GET_TEXT_F(MSG_PREHEAT_CUSTOM), onDrawMenuItem, DoPreheat2); #endif #endif - ADDMENUITEM(ICON_Cool, GET_TEXT_F(MSG_COOLDOWN), onDrawCooldown, DoCoolDown); - ADDMENUITEM(ICON_Language, PSTR(GET_TEXT_F(MSG_UI_LANGUAGE)), onDrawLanguage, SetLanguage); + MENU_ITEM(ICON_Cool, GET_TEXT_F(MSG_COOLDOWN), onDrawCooldown, DoCoolDown); + MENU_ITEM(ICON_Language, PSTR(GET_TEXT_F(MSG_UI_LANGUAGE)), onDrawLanguage, SetLanguage); } CurrentMenu->draw(); } @@ -3224,12 +3240,12 @@ void Draw_Tramming_Menu() { CurrentMenu = TrammingMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_BED_TRAMMING)); // TODO: Chinese, English "Bed Tramming" JPG DWINUI::MenuItemsPrepare(6); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FL), onDrawMenuItem, TramFL); - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FR), onDrawMenuItem, TramFR); - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BR), onDrawMenuItem, TramBR); - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BL), onDrawMenuItem, TramBL); - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_C ), onDrawMenuItem, TramC ); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); + MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FL), onDrawMenuItem, TramFL); + MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FR), onDrawMenuItem, TramFR); + MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BR), onDrawMenuItem, TramBR); + MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BL), onDrawMenuItem, TramBL); + MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_C ), onDrawMenuItem, TramC ); } CurrentMenu->draw(); } @@ -3241,17 +3257,17 @@ void Draw_Control_Menu() { CurrentMenu = ControlMenu; SetMenuTitle({103, 1, 28, 14}, GET_TEXT_F(MSG_CONTROL)); DWINUI::MenuItemsPrepare(9); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); - ADDMENUITEM(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawTempSubMenu, Draw_Temperature_Menu); - ADDMENUITEM(ICON_Motion, GET_TEXT_F(MSG_MOTION), onDrawMotionSubMenu, Draw_Motion_Menu); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); + MENU_ITEM(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawTempSubMenu, Draw_Temperature_Menu); + MENU_ITEM(ICON_Motion, GET_TEXT_F(MSG_MOTION), onDrawMotionSubMenu, Draw_Motion_Menu); #if ENABLED(EEPROM_SETTINGS) - ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); - ADDMENUITEM(ICON_ReadEEPROM, GET_TEXT_F(MSG_LOAD_EEPROM), onDrawReadEeprom, ReadEeprom); - ADDMENUITEM(ICON_ResumeEEPROM, GET_TEXT_F(MSG_RESTORE_DEFAULTS), onDrawResetEeprom, ResetEeprom); + MENU_ITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); + MENU_ITEM(ICON_ReadEEPROM, GET_TEXT_F(MSG_LOAD_EEPROM), onDrawReadEeprom, ReadEeprom); + MENU_ITEM(ICON_ResumeEEPROM, GET_TEXT_F(MSG_RESTORE_DEFAULTS), onDrawResetEeprom, ResetEeprom); #endif - ADDMENUITEM(ICON_Reboot, GET_TEXT_F(MSG_RESET_PRINTER), onDrawMenuItem, RebootPrinter); - ADDMENUITEM(ICON_AdvSet, GET_TEXT_F(MSG_ADVANCED_SETTINGS), onDrawSubMenu, Draw_AdvancedSettings_Menu); - ADDMENUITEM(ICON_Info, GET_TEXT_F(MSG_INFO_SCREEN), onDrawInfoSubMenu, Goto_Info_Menu); + MENU_ITEM(ICON_Reboot, GET_TEXT_F(MSG_RESET_PRINTER), onDrawMenuItem, RebootPrinter); + MENU_ITEM(ICON_AdvSet, GET_TEXT_F(MSG_ADVANCED_SETTINGS), onDrawSubMenu, Draw_AdvancedSettings_Menu); + MENU_ITEM(ICON_Info, GET_TEXT_F(MSG_INFO_SCREEN), onDrawInfoSubMenu, Goto_Info_Menu); } CurrentMenu->draw(); } @@ -3263,43 +3279,43 @@ void Draw_AdvancedSettings_Menu() { CurrentMenu = AdvancedSettings; SetMenuTitle({0}, GET_TEXT_F(MSG_ADVANCED_SETTINGS)); // TODO: Chinese, English "Advanced Settings" JPG DWINUI::MenuItemsPrepare(15); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); #if HAS_HOME_OFFSET - ADDMENUITEM(ICON_HomeOffset, GET_TEXT_F(MSG_SET_HOME_OFFSETS), onDrawSubMenu, Draw_HomeOffset_Menu); + MENU_ITEM(ICON_HomeOffset, GET_TEXT_F(MSG_SET_HOME_OFFSETS), onDrawSubMenu, Draw_HomeOffset_Menu); #endif #if HAS_BED_PROBE - ADDMENUITEM(ICON_ProbeSet, GET_TEXT_F(MSG_ZPROBE_SETTINGS), onDrawSubMenu, Draw_ProbeSet_Menu); + MENU_ITEM(ICON_ProbeSet, GET_TEXT_F(MSG_ZPROBE_SETTINGS), onDrawSubMenu, Draw_ProbeSet_Menu); #endif #if HAS_HOTEND - ADDMENUITEM(ICON_PIDNozzle, F("Hotend PID Settings"), onDrawSubMenu, Draw_HotendPID_Menu); + MENU_ITEM(ICON_PIDNozzle, F("Hotend PID Settings"), onDrawSubMenu, Draw_HotendPID_Menu); #endif #if HAS_HEATED_BED - ADDMENUITEM(ICON_PIDbed, F("Bed PID Settings"), onDrawSubMenu, Draw_BedPID_Menu); + MENU_ITEM(ICON_PIDbed, F("Bed PID Settings"), onDrawSubMenu, Draw_BedPID_Menu); #endif #if HAS_FILAMENT_SENSOR - ADDMENUITEM(ICON_FilSet, GET_TEXT_F(MSG_FILAMENT_SET), onDrawSubMenu, Draw_FilSet_Menu); + MENU_ITEM(ICON_FilSet, GET_TEXT_F(MSG_FILAMENT_SET), onDrawSubMenu, Draw_FilSet_Menu); #endif #if ENABLED(POWER_LOSS_RECOVERY) - ADDMENUITEM(ICON_Pwrlossr, GET_TEXT_F(MSG_OUTAGE_RECOVERY), onDrawPwrLossR, SetPwrLossr); + MENU_ITEM(ICON_Pwrlossr, GET_TEXT_F(MSG_OUTAGE_RECOVERY), onDrawPwrLossR, SetPwrLossr); #endif #if HAS_LCD_BRIGHTNESS - ADDMENUITEM_P(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS), onDrawPInt8Menu, SetBrightness, &ui.brightness); + EDIT_ITEM(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS), onDrawPInt8Menu, SetBrightness, &ui.brightness); #endif - ADDMENUITEM(ICON_Scolor, GET_TEXT_F(MSG_COLORS_SELECT), onDrawSubMenu, Draw_SelectColors_Menu); + MENU_ITEM(ICON_Scolor, GET_TEXT_F(MSG_COLORS_SELECT), onDrawSubMenu, Draw_SelectColors_Menu); #if ENABLED(SOUND_MENU_ITEM) - ADDMENUITEM(ICON_Sound, GET_TEXT_F(MSG_SOUND_ENABLE), onDrawEnableSound, SetEnableSound); + MENU_ITEM(ICON_Sound, GET_TEXT_F(MSG_SOUND_ENABLE), onDrawEnableSound, SetEnableSound); #endif #if HAS_MESH - ADDMENUITEM(ICON_MeshViewer, GET_TEXT_F(MSG_MESH_VIEW), onDrawSubMenu, DWIN_MeshViewer); + MENU_ITEM(ICON_MeshViewer, GET_TEXT_F(MSG_MESH_VIEW), onDrawSubMenu, DWIN_MeshViewer); #endif #if HAS_ESDIAG - ADDMENUITEM(ICON_ESDiag, F("End-stops diag."), onDrawSubMenu, Draw_EndStopDiag); + MENU_ITEM(ICON_ESDiag, F("End-stops diag."), onDrawSubMenu, Draw_EndStopDiag); #endif #if ENABLED(PRINTCOUNTER) - ADDMENUITEM(ICON_PrintStats, GET_TEXT_F(MSG_INFO_STATS_MENU), onDrawSubMenu, Draw_PrintStats); - ADDMENUITEM(ICON_PrintStatsReset, GET_TEXT_F(MSG_INFO_PRINT_COUNT_RESET), onDrawSubMenu, PrintStats.Reset); + MENU_ITEM(ICON_PrintStats, GET_TEXT_F(MSG_INFO_STATS_MENU), onDrawSubMenu, Draw_PrintStats); + MENU_ITEM(ICON_PrintStatsReset, GET_TEXT_F(MSG_INFO_PRINT_COUNT_RESET), onDrawSubMenu, PrintStats.Reset); #endif - ADDMENUITEM(ICON_Lock, GET_TEXT_F(MSG_LOCKSCREEN), onDrawMenuItem, DWIN_LockScreen); + MENU_ITEM(ICON_Lock, GET_TEXT_F(MSG_LOCKSCREEN), onDrawMenuItem, DWIN_LockScreen); } CurrentMenu->draw(); } @@ -3311,12 +3327,12 @@ void Draw_Move_Menu() { CurrentMenu = MoveMenu; SetMenuTitle({192, 1, 42, 14}, GET_TEXT_F(MSG_MOVE_AXIS)); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - ADDMENUITEM_P(ICON_MoveX, GET_TEXT_F(MSG_MOVE_X), onDrawMoveX, SetMoveX, ¤t_position.x); - ADDMENUITEM_P(ICON_MoveY, GET_TEXT_F(MSG_MOVE_Y), onDrawMoveY, SetMoveY, ¤t_position.y); - ADDMENUITEM_P(ICON_MoveZ, GET_TEXT_F(MSG_MOVE_Z), onDrawMoveZ, SetMoveZ, ¤t_position.z); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); + EDIT_ITEM(ICON_MoveX, GET_TEXT_F(MSG_MOVE_X), onDrawMoveX, SetMoveX, ¤t_position.x); + EDIT_ITEM(ICON_MoveY, GET_TEXT_F(MSG_MOVE_Y), onDrawMoveY, SetMoveY, ¤t_position.y); + EDIT_ITEM(ICON_MoveZ, GET_TEXT_F(MSG_MOVE_Z), onDrawMoveZ, SetMoveZ, ¤t_position.z); #if HAS_HOTEND - ADDMENUITEM_P(ICON_Extruder, GET_TEXT_F(MSG_MOVE_E), onDrawMoveE, SetMoveE, ¤t_position.e); + EDIT_ITEM(ICON_Extruder, GET_TEXT_F(MSG_MOVE_E), onDrawMoveE, SetMoveE, ¤t_position.e); #endif } CurrentMenu->draw(); @@ -3331,10 +3347,10 @@ void Draw_Move_Menu() { CurrentMenu = HomeOffMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_SET_HOME_OFFSETS)); // TODO: Chinese, English "Set Home Offsets" JPG DWINUI::MenuItemsPrepare(4); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); - ADDMENUITEM_P(ICON_HomeOffsetX, GET_TEXT_F(MSG_HOME_OFFSET_X), onDrawPFloatMenu, SetHomeOffsetX, &home_offset[X_AXIS]); - ADDMENUITEM_P(ICON_HomeOffsetY, GET_TEXT_F(MSG_HOME_OFFSET_Y), onDrawPFloatMenu, SetHomeOffsetY, &home_offset[Y_AXIS]); - ADDMENUITEM_P(ICON_HomeOffsetZ, GET_TEXT_F(MSG_HOME_OFFSET_Z), onDrawPFloatMenu, SetHomeOffsetZ, &home_offset[Z_AXIS]); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); + EDIT_ITEM(ICON_HomeOffsetX, GET_TEXT_F(MSG_HOME_OFFSET_X), onDrawPFloatMenu, SetHomeOffsetX, &home_offset[X_AXIS]); + EDIT_ITEM(ICON_HomeOffsetY, GET_TEXT_F(MSG_HOME_OFFSET_Y), onDrawPFloatMenu, SetHomeOffsetY, &home_offset[Y_AXIS]); + EDIT_ITEM(ICON_HomeOffsetZ, GET_TEXT_F(MSG_HOME_OFFSET_Z), onDrawPFloatMenu, SetHomeOffsetZ, &home_offset[Z_AXIS]); } CurrentMenu->draw(); } @@ -3347,14 +3363,17 @@ void Draw_Move_Menu() { if (CurrentMenu != ProbeSetMenu) { CurrentMenu = ProbeSetMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_ZPROBE_SETTINGS)); // TODO: Chinese, English "Probe Settings" JPG - DWINUI::MenuItemsPrepare(7); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); - ADDMENUITEM_P(ICON_ProbeOffsetX, GET_TEXT_F(MSG_ZPROBE_XOFFSET), onDrawPFloatMenu, SetProbeOffsetX, &probe.offset.x); - ADDMENUITEM_P(ICON_ProbeOffsetY, GET_TEXT_F(MSG_ZPROBE_YOFFSET), onDrawPFloatMenu, SetProbeOffsetY, &probe.offset.y); - ADDMENUITEM_P(ICON_ProbeOffsetZ, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetProbeOffsetZ, &probe.offset.z); - ADDMENUITEM(ICON_ProbeTest, GET_TEXT_F(MSG_M48_TEST), onDrawMenuItem, ProbeTest); - ADDMENUITEM(ICON_ProbeStow, GET_TEXT_F(MSG_MANUAL_STOW), onDrawMenuItem, ProbeStow); - ADDMENUITEM(ICON_ProbeDeploy, GET_TEXT_F(MSG_MANUAL_DEPLOY), onDrawMenuItem, ProbeDeploy); + DWINUI::MenuItemsPrepare(8); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); + EDIT_ITEM(ICON_ProbeOffsetX, GET_TEXT_F(MSG_ZPROBE_XOFFSET), onDrawPFloatMenu, SetProbeOffsetX, &probe.offset.x); + EDIT_ITEM(ICON_ProbeOffsetY, GET_TEXT_F(MSG_ZPROBE_YOFFSET), onDrawPFloatMenu, SetProbeOffsetY, &probe.offset.y); + EDIT_ITEM(ICON_ProbeOffsetZ, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetProbeOffsetZ, &probe.offset.z); + #ifdef BLTOUCH_HS_MODE + MENU_ITEM(ICON_HSMode, F("Enable HS mode"), onDrawHSMode, SetHSMode); + #endif + MENU_ITEM(ICON_ProbeTest, GET_TEXT_F(MSG_M48_TEST), onDrawMenuItem, ProbeTest); + MENU_ITEM(ICON_ProbeStow, GET_TEXT_F(MSG_MANUAL_STOW), onDrawMenuItem, ProbeStow); + MENU_ITEM(ICON_ProbeDeploy, GET_TEXT_F(MSG_MANUAL_DEPLOY), onDrawMenuItem, ProbeDeploy); } CurrentMenu->draw(); } @@ -3368,25 +3387,25 @@ void Draw_Move_Menu() { CurrentMenu = FilSetMenu; CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_FILAMENT_SET)); DWINUI::MenuItemsPrepare(10); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); #if HAS_FILAMENT_SENSOR - ADDMENUITEM(ICON_Runout, GET_TEXT_F(MSG_RUNOUT_ENABLE), onDrawRunoutEnable, SetRunoutEnable); + MENU_ITEM(ICON_Runout, GET_TEXT_F(MSG_RUNOUT_ENABLE), onDrawRunoutEnable, SetRunoutEnable); #endif #if HAS_FILAMENT_RUNOUT_DISTANCE - ADDMENUITEM_P(ICON_Runout, F("Runout Distance"), onDrawPFloatMenu, SetRunoutDistance, &runout.runout_distance()); + EDIT_ITEM(ICON_Runout, F("Runout Distance"), onDrawPFloatMenu, SetRunoutDistance, &runout.runout_distance()); #endif #if ENABLED(PREVENT_COLD_EXTRUSION) - ADDMENUITEM_P(ICON_ExtrudeMinT, F("Extrude Min Temp."), onDrawPIntMenu, SetExtMinT, &HMI_data.ExtMinT); + EDIT_ITEM(ICON_ExtrudeMinT, F("Extrude Min Temp."), onDrawPIntMenu, SetExtMinT, &HMI_data.ExtMinT); #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) - ADDMENUITEM_P(ICON_FilLoad, GET_TEXT_F(MSG_FILAMENT_LOAD), onDrawPFloatMenu, SetFilLoad, &fc_settings[0].load_length); - ADDMENUITEM_P(ICON_FilUnload, GET_TEXT_F(MSG_FILAMENT_UNLOAD), onDrawPFloatMenu, SetFilUnload, &fc_settings[0].unload_length); + EDIT_ITEM(ICON_FilLoad, GET_TEXT_F(MSG_FILAMENT_LOAD), onDrawPFloatMenu, SetFilLoad, &fc_settings[0].load_length); + EDIT_ITEM(ICON_FilUnload, GET_TEXT_F(MSG_FILAMENT_UNLOAD), onDrawPFloatMenu, SetFilUnload, &fc_settings[0].unload_length); #endif #if ENABLED(FWRETRACT) - ADDMENUITEM_P(ICON_FWRetLength, GET_TEXT_F(MSG_CONTROL_RETRACT), onDrawPFloatMenu, SetRetractLength, &fwretract.settings.retract_length); - ADDMENUITEM_P(ICON_FWRetSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_RETRACT_SPEED), onDrawPFloatMenu, SetRetractSpeed, &fwretract.settings.retract_feedrate_mm_s); - ADDMENUITEM_P(ICON_FWRetZRaise, GET_TEXT_F(MSG_CONTROL_RETRACT_ZHOP), onDrawPFloat2Menu, SetZRaise, &fwretract.settings.retract_zraise); - ADDMENUITEM_P(ICON_FWRecSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_UNRETRACT_SPEED), onDrawPFloatMenu, SetRecoverSpeed, &fwretract.settings.retract_recover_feedrate_mm_s); + EDIT_ITEM(ICON_FWRetLength, GET_TEXT_F(MSG_CONTROL_RETRACT), onDrawPFloatMenu, SetRetractLength, &fwretract.settings.retract_length); + EDIT_ITEM(ICON_FWRetSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_RETRACT_SPEED), onDrawPFloatMenu, SetRetractSpeed, &fwretract.settings.retract_feedrate_mm_s); + EDIT_ITEM(ICON_FWRetZRaise, GET_TEXT_F(MSG_CONTROL_RETRACT_ZHOP), onDrawPFloat2Menu, SetZRaise, &fwretract.settings.retract_zraise); + EDIT_ITEM(ICON_FWRecSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_UNRETRACT_SPEED), onDrawPFloatMenu, SetRecoverSpeed, &fwretract.settings.retract_recover_feedrate_mm_s); #endif } CurrentMenu->draw(); @@ -3400,26 +3419,26 @@ void Draw_SelectColors_Menu() { CurrentMenu = SelectColorMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_COLORS_SELECT)); // TODO: Chinese, English "Select Color" JPG DWINUI::MenuItemsPrepare(20); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); - ADDMENUITEM(ICON_StockConfiguration, GET_TEXT_F(MSG_RESTORE_DEFAULTS), onDrawMenuItem, RestoreDefaultsColors); - ADDMENUITEM_P(0, "Screen Background", onDrawSelColorItem, SelColor, &HMI_data.Background_Color); - ADDMENUITEM_P(0, "Cursor", onDrawSelColorItem, SelColor, &HMI_data.Cursor_color); - ADDMENUITEM_P(0, "Title Background", onDrawSelColorItem, SelColor, &HMI_data.TitleBg_color); - ADDMENUITEM_P(0, "Title Text", onDrawSelColorItem, SelColor, &HMI_data.TitleTxt_color); - ADDMENUITEM_P(0, "Text", onDrawSelColorItem, SelColor, &HMI_data.Text_Color); - ADDMENUITEM_P(0, "Selected", onDrawSelColorItem, SelColor, &HMI_data.Selected_Color); - ADDMENUITEM_P(0, "Split Line", onDrawSelColorItem, SelColor, &HMI_data.SplitLine_Color); - ADDMENUITEM_P(0, "Highlight", onDrawSelColorItem, SelColor, &HMI_data.Highlight_Color); - ADDMENUITEM_P(0, "Status Background", onDrawSelColorItem, SelColor, &HMI_data.StatusBg_Color); - ADDMENUITEM_P(0, "Status Text", onDrawSelColorItem, SelColor, &HMI_data.StatusTxt_Color); - ADDMENUITEM_P(0, "Popup Background", onDrawSelColorItem, SelColor, &HMI_data.PopupBg_color); - ADDMENUITEM_P(0, "Popup Text", onDrawSelColorItem, SelColor, &HMI_data.PopupTxt_Color); - ADDMENUITEM_P(0, "Alert Background", onDrawSelColorItem, SelColor, &HMI_data.AlertBg_Color); - ADDMENUITEM_P(0, "Alert Text", onDrawSelColorItem, SelColor, &HMI_data.AlertTxt_Color); - ADDMENUITEM_P(0, "Percent Text", onDrawSelColorItem, SelColor, &HMI_data.PercentTxt_Color); - ADDMENUITEM_P(0, "Bar Fill", onDrawSelColorItem, SelColor, &HMI_data.Barfill_Color); - ADDMENUITEM_P(0, "Indicator value", onDrawSelColorItem, SelColor, &HMI_data.Indicator_Color); - ADDMENUITEM_P(0, "Coordinate value", onDrawSelColorItem, SelColor, &HMI_data.Coordinate_Color); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); + MENU_ITEM(ICON_StockConfiguration, GET_TEXT_F(MSG_RESTORE_DEFAULTS), onDrawMenuItem, RestoreDefaultsColors); + EDIT_ITEM(0, "Screen Background", onDrawSelColorItem, SelColor, &HMI_data.Background_Color); + EDIT_ITEM(0, "Cursor", onDrawSelColorItem, SelColor, &HMI_data.Cursor_color); + EDIT_ITEM(0, "Title Background", onDrawSelColorItem, SelColor, &HMI_data.TitleBg_color); + EDIT_ITEM(0, "Title Text", onDrawSelColorItem, SelColor, &HMI_data.TitleTxt_color); + EDIT_ITEM(0, "Text", onDrawSelColorItem, SelColor, &HMI_data.Text_Color); + EDIT_ITEM(0, "Selected", onDrawSelColorItem, SelColor, &HMI_data.Selected_Color); + EDIT_ITEM(0, "Split Line", onDrawSelColorItem, SelColor, &HMI_data.SplitLine_Color); + EDIT_ITEM(0, "Highlight", onDrawSelColorItem, SelColor, &HMI_data.Highlight_Color); + EDIT_ITEM(0, "Status Background", onDrawSelColorItem, SelColor, &HMI_data.StatusBg_Color); + EDIT_ITEM(0, "Status Text", onDrawSelColorItem, SelColor, &HMI_data.StatusTxt_Color); + EDIT_ITEM(0, "Popup Background", onDrawSelColorItem, SelColor, &HMI_data.PopupBg_color); + EDIT_ITEM(0, "Popup Text", onDrawSelColorItem, SelColor, &HMI_data.PopupTxt_Color); + EDIT_ITEM(0, "Alert Background", onDrawSelColorItem, SelColor, &HMI_data.AlertBg_Color); + EDIT_ITEM(0, "Alert Text", onDrawSelColorItem, SelColor, &HMI_data.AlertTxt_Color); + EDIT_ITEM(0, "Percent Text", onDrawSelColorItem, SelColor, &HMI_data.PercentTxt_Color); + EDIT_ITEM(0, "Bar Fill", onDrawSelColorItem, SelColor, &HMI_data.Barfill_Color); + EDIT_ITEM(0, "Indicator value", onDrawSelColorItem, SelColor, &HMI_data.Indicator_Color); + EDIT_ITEM(0, "Coordinate value", onDrawSelColorItem, SelColor, &HMI_data.Coordinate_Color); } CurrentMenu->draw(); } @@ -3431,11 +3450,11 @@ void Draw_GetColor_Menu() { CurrentMenu = GetColorMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_COLORS_GET)); // TODO: Chinese, English "Get Color" JPG DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, DWIN_ApplyColor); - ADDMENUITEM(ICON_Cancel, GET_TEXT_F(MSG_BUTTON_CANCEL), onDrawMenuItem, Draw_SelectColors_Menu); - ADDMENUITEM(0, GET_TEXT_F(MSG_COLORS_RED), onDrawGetColorItem, SetRGBColor); - ADDMENUITEM(1, GET_TEXT_F(MSG_COLORS_GREEN), onDrawGetColorItem, SetRGBColor); - ADDMENUITEM(2, GET_TEXT_F(MSG_COLORS_BLUE), onDrawGetColorItem, SetRGBColor); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, DWIN_ApplyColor); + MENU_ITEM(ICON_Cancel, GET_TEXT_F(MSG_BUTTON_CANCEL), onDrawMenuItem, Draw_SelectColors_Menu); + MENU_ITEM(0, GET_TEXT_F(MSG_COLORS_RED), onDrawGetColorItem, SetRGBColor); + MENU_ITEM(1, GET_TEXT_F(MSG_COLORS_GREEN), onDrawGetColorItem, SetRGBColor); + MENU_ITEM(2, GET_TEXT_F(MSG_COLORS_BLUE), onDrawGetColorItem, SetRGBColor); } CurrentMenu->draw(); DWIN_Draw_Rectangle(1, *HMI_value.P_Int, 20, 315, DWIN_WIDTH - 20, 335); @@ -3448,33 +3467,33 @@ void Draw_Tune_Menu() { CurrentMenu = TuneMenu; SetMenuTitle({73, 2, 28, 12}, GET_TEXT_F(MSG_TUNE)); // TODO: Chinese, English "Tune" JPG DWINUI::MenuItemsPrepare(14); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_PrintProcess); - ADDMENUITEM_P(ICON_Speed, GET_TEXT_F(MSG_SPEED), onDrawSpeedItem, SetSpeed, &feedrate_percentage); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_PrintProcess); + EDIT_ITEM(ICON_Speed, GET_TEXT_F(MSG_SPEED), onDrawSpeedItem, SetSpeed, &feedrate_percentage); #if HAS_HOTEND - HotendTargetItem = ADDMENUITEM_P(ICON_HotendTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); + HotendTargetItem = EDIT_ITEM(ICON_HotendTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); #endif #if HAS_HEATED_BED - BedTargetItem = ADDMENUITEM_P(ICON_BedTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); + BedTargetItem = EDIT_ITEM(ICON_BedTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); #endif #if HAS_FAN - FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT_F(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); + FanSpeedItem = EDIT_ITEM(ICON_FanSpeed, GET_TEXT_F(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); #endif #if HAS_ZOFFSET_ITEM && EITHER(HAS_BED_PROBE, BABYSTEPPING) - ADDMENUITEM_P(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawZOffset, SetZOffset, &BABY_Z_VAR); + EDIT_ITEM(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawZOffset, SetZOffset, &BABY_Z_VAR); #endif #if ENABLED(FWRETRACT) - ADDMENUITEM_P(ICON_FWRetLength, GET_TEXT_F(MSG_CONTROL_RETRACT), onDrawPFloatMenu, SetRetractLength, &fwretract.settings.retract_length); - ADDMENUITEM_P(ICON_FWRetSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_RETRACT_SPEED), onDrawPFloatMenu, SetRetractSpeed, &fwretract.settings.retract_feedrate_mm_s); - ADDMENUITEM_P(ICON_FWRetZRaise, GET_TEXT_F(MSG_CONTROL_RETRACT_ZHOP), onDrawPFloat2Menu, SetZRaise, &fwretract.settings.retract_zraise); - ADDMENUITEM_P(ICON_FWRecSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_UNRETRACT_SPEED), onDrawPFloatMenu, SetRecoverSpeed, &fwretract.settings.retract_recover_feedrate_mm_s); + EDIT_ITEM(ICON_FWRetLength, GET_TEXT_F(MSG_CONTROL_RETRACT), onDrawPFloatMenu, SetRetractLength, &fwretract.settings.retract_length); + EDIT_ITEM(ICON_FWRetSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_RETRACT_SPEED), onDrawPFloatMenu, SetRetractSpeed, &fwretract.settings.retract_feedrate_mm_s); + EDIT_ITEM(ICON_FWRetZRaise, GET_TEXT_F(MSG_CONTROL_RETRACT_ZHOP), onDrawPFloat2Menu, SetZRaise, &fwretract.settings.retract_zraise); + EDIT_ITEM(ICON_FWRecSpeed, GET_TEXT_F(MSG_SINGLENOZZLE_UNRETRACT_SPEED), onDrawPFloatMenu, SetRecoverSpeed, &fwretract.settings.retract_recover_feedrate_mm_s); #endif - ADDMENUITEM_P(ICON_Flow, GET_TEXT_F(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); + EDIT_ITEM(ICON_Flow, GET_TEXT_F(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); #if ENABLED(ADVANCED_PAUSE_FEATURE) - ADDMENUITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); + MENU_ITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); #endif - ADDMENUITEM(ICON_Lock, GET_TEXT_F(MSG_LOCKSCREEN), onDrawMenuItem, DWIN_LockScreen); + MENU_ITEM(ICON_Lock, GET_TEXT_F(MSG_LOCKSCREEN), onDrawMenuItem, DWIN_LockScreen); #if HAS_LCD_BRIGHTNESS - ADDMENUITEM_P(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS), onDrawPInt8Menu, SetBrightness, &ui.brightness); + EDIT_ITEM(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS), onDrawPInt8Menu, SetBrightness, &ui.brightness); #endif } CurrentMenu->draw(); @@ -3487,14 +3506,14 @@ void Draw_Motion_Menu() { CurrentMenu = MotionMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_MOTION)); // TODO: Chinese, English "Motion" JPG DWINUI::MenuItemsPrepare(6); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); - ADDMENUITEM(ICON_MaxSpeed, GET_TEXT_F(MSG_SPEED), onDrawSpeed, Draw_MaxSpeed_Menu); - ADDMENUITEM(ICON_MaxAccelerated, GET_TEXT_F(MSG_ACCELERATION), onDrawAcc, Draw_MaxAccel_Menu); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); + MENU_ITEM(ICON_MaxSpeed, GET_TEXT_F(MSG_SPEED), onDrawSpeed, Draw_MaxSpeed_Menu); + MENU_ITEM(ICON_MaxAccelerated, GET_TEXT_F(MSG_ACCELERATION), onDrawAcc, Draw_MaxAccel_Menu); #if HAS_CLASSIC_JERK - ADDMENUITEM(ICON_MaxJerk, GET_TEXT_F(MSG_JERK), onDrawJerk, Draw_MaxJerk_Menu); + MENU_ITEM(ICON_MaxJerk, GET_TEXT_F(MSG_JERK), onDrawJerk, Draw_MaxJerk_Menu); #endif - ADDMENUITEM(ICON_Step, GET_TEXT_F(MSG_STEPS_PER_MM), onDrawSteps, Draw_Steps_Menu); - ADDMENUITEM_P(ICON_Flow, GET_TEXT_F(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); + MENU_ITEM(ICON_Step, GET_TEXT_F(MSG_STEPS_PER_MM), onDrawSteps, Draw_Steps_Menu); + EDIT_ITEM(ICON_Flow, GET_TEXT_F(MSG_FLOW), onDrawPIntMenu, SetFlow, &planner.flow_percentage[0]); } CurrentMenu->draw(); } @@ -3507,12 +3526,12 @@ void Draw_Motion_Menu() { CurrentMenu = FilamentMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_FILAMENT_MAN)); // TODO: Chinese, English "Filament Management" JPG DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - ADDMENUITEM(ICON_Park, GET_TEXT_F(MSG_FILAMENT_PARK_ENABLED), onDrawMenuItem, ParkHead); - ADDMENUITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); + MENU_ITEM(ICON_Park, GET_TEXT_F(MSG_FILAMENT_PARK_ENABLED), onDrawMenuItem, ParkHead); + MENU_ITEM(ICON_FilMan, GET_TEXT_F(MSG_FILAMENTCHANGE), onDrawMenuItem, ChangeFilament); #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - ADDMENUITEM(ICON_FilUnload, GET_TEXT_F(MSG_FILAMENTUNLOAD), onDrawMenuItem, UnloadFilament); - ADDMENUITEM(ICON_FilLoad, GET_TEXT_F(MSG_FILAMENTLOAD), onDrawMenuItem, LoadFilament); + MENU_ITEM(ICON_FilUnload, GET_TEXT_F(MSG_FILAMENTUNLOAD), onDrawMenuItem, UnloadFilament); + MENU_ITEM(ICON_FilLoad, GET_TEXT_F(MSG_FILAMENTLOAD), onDrawMenuItem, LoadFilament); #endif } CurrentMenu->draw(); @@ -3527,12 +3546,12 @@ void Draw_Motion_Menu() { CurrentMenu = ManualMesh; SetMenuTitle({0}, GET_TEXT_F(MSG_MANUAL_MESH)); // TODO: Chinese, English "Manual Mesh Leveling" JPG DWINUI::MenuItemsPrepare(6); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); - ADDMENUITEM(ICON_ManualMesh, GET_TEXT_F(MSG_LEVEL_BED), onDrawMenuItem, ManualMeshStart); - MMeshMoveZItem = ADDMENUITEM_P(ICON_Zoffset, GET_TEXT_F(MSG_MOVE_Z), onDrawMMeshMoveZ, SetMMeshMoveZ, ¤t_position.z); - ADDMENUITEM(ICON_Axis, GET_TEXT_F(MSG_UBL_CONTINUE_MESH), onDrawMenuItem, ManualMeshContinue); - ADDMENUITEM(ICON_MeshViewer, GET_TEXT_F(MSG_MESH_VIEW), onDrawSubMenu, DWIN_MeshViewer); - ADDMENUITEM(ICON_MeshSave, GET_TEXT_F(MSG_UBL_SAVE_MESH), onDrawMenuItem, ManualMeshSave); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); + MENU_ITEM(ICON_ManualMesh, GET_TEXT_F(MSG_LEVEL_BED), onDrawMenuItem, ManualMeshStart); + MMeshMoveZItem = EDIT_ITEM(ICON_Zoffset, GET_TEXT_F(MSG_MOVE_Z), onDrawMMeshMoveZ, SetMMeshMoveZ, ¤t_position.z); + MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_UBL_CONTINUE_MESH), onDrawMenuItem, ManualMeshContinue); + MENU_ITEM(ICON_MeshViewer, GET_TEXT_F(MSG_MESH_VIEW), onDrawSubMenu, DWIN_MeshViewer); + MENU_ITEM(ICON_MeshSave, GET_TEXT_F(MSG_UBL_SAVE_MESH), onDrawMenuItem, ManualMeshSave); } CurrentMenu->draw(); } @@ -3546,18 +3565,18 @@ void Draw_Motion_Menu() { CurrentMenu = PreheatMenu; SetMenuTitle(cn, fstr); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Temperature_Menu); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Temperature_Menu); #if HAS_HOTEND - ADDMENUITEM_P(ICON_SetEndTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND), onDrawSetPreheatHotend, SetPreheatEndTemp, &ui.material_preset[HMI_value.Preheat].hotend_temp); + EDIT_ITEM(ICON_SetEndTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND), onDrawSetPreheatHotend, SetPreheatEndTemp, &ui.material_preset[HMI_value.Preheat].hotend_temp); #endif #if HAS_HEATED_BED - ADDMENUITEM_P(ICON_SetBedTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawSetPreheatBed, SetPreheatBedTemp, &ui.material_preset[HMI_value.Preheat].bed_temp); + EDIT_ITEM(ICON_SetBedTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawSetPreheatBed, SetPreheatBedTemp, &ui.material_preset[HMI_value.Preheat].bed_temp); #endif #if HAS_FAN - ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT_F(MSG_FAN_SPEED), onDrawSetPreheatFan, SetPreheatFanSpeed, &ui.material_preset[HMI_value.Preheat].fan_speed); + EDIT_ITEM(ICON_FanSpeed, GET_TEXT_F(MSG_FAN_SPEED), onDrawSetPreheatFan, SetPreheatFanSpeed, &ui.material_preset[HMI_value.Preheat].fan_speed); #endif #if ENABLED(EEPROM_SETTINGS) - ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); + MENU_ITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawWriteEeprom, WriteEeprom); #endif } CurrentMenu->draw(); @@ -3593,21 +3612,21 @@ void Draw_Temperature_Menu() { CurrentMenu = TemperatureMenu; SetMenuTitle({236, 2, 28, 12}, GET_TEXT_F(MSG_TEMPERATURE)); DWINUI::MenuItemsPrepare(7); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Control_Menu); #if HAS_HOTEND - HotendTargetItem = ADDMENUITEM_P(ICON_SetEndTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); + HotendTargetItem = EDIT_ITEM(ICON_SetEndTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND), onDrawHotendTemp, SetHotendTemp, &thermalManager.temp_hotend[0].target); #endif #if HAS_HEATED_BED - BedTargetItem = ADDMENUITEM_P(ICON_SetBedTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); + BedTargetItem = EDIT_ITEM(ICON_SetBedTemp, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawBedTemp, SetBedTemp, &thermalManager.temp_bed.target); #endif #if HAS_FAN - FanSpeedItem = ADDMENUITEM_P(ICON_FanSpeed, GET_TEXT_F(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); + FanSpeedItem = EDIT_ITEM(ICON_FanSpeed, GET_TEXT_F(MSG_FAN_SPEED), onDrawFanSpeed, SetFanSpeed, &thermalManager.fan_speed[0]); #endif #if HAS_HOTEND - ADDMENUITEM(ICON_SetPLAPreheat, F(PREHEAT_1_LABEL " Preheat Settings"), onDrawPLAPreheatSubMenu, Draw_Preheat1_Menu); - ADDMENUITEM(ICON_SetABSPreheat, F(PREHEAT_2_LABEL " Preheat Settings"), onDrawABSPreheatSubMenu, Draw_Preheat2_Menu); + MENU_ITEM(ICON_SetPLAPreheat, F(PREHEAT_1_LABEL " Preheat Settings"), onDrawPLAPreheatSubMenu, Draw_Preheat1_Menu); + MENU_ITEM(ICON_SetABSPreheat, F(PREHEAT_2_LABEL " Preheat Settings"), onDrawABSPreheatSubMenu, Draw_Preheat2_Menu); #ifdef PREHEAT_3_LABEL - ADDMENUITEM(ICON_SetCustomPreheat, PREHEAT_3_TITLE, onDrawSubMenu, Draw_Preheat3_Menu); + MENU_ITEM(ICON_SetCustomPreheat, PREHEAT_3_TITLE, onDrawSubMenu, Draw_Preheat3_Menu); #endif #endif } @@ -3621,12 +3640,12 @@ void Draw_MaxSpeed_Menu() { CurrentMenu = MaxSpeedMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_MAXSPEED)); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); - ADDMENUITEM_P(ICON_MaxSpeedX, GET_TEXT_F(MSG_MAXSPEED_X), onDrawMaxSpeedX, SetMaxSpeedX, &planner.settings.max_feedrate_mm_s[X_AXIS]); - ADDMENUITEM_P(ICON_MaxSpeedY, GET_TEXT_F(MSG_MAXSPEED_Y), onDrawMaxSpeedY, SetMaxSpeedY, &planner.settings.max_feedrate_mm_s[Y_AXIS]); - ADDMENUITEM_P(ICON_MaxSpeedZ, GET_TEXT_F(MSG_MAXSPEED_Z), onDrawMaxSpeedZ, SetMaxSpeedZ, &planner.settings.max_feedrate_mm_s[Z_AXIS]); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); + EDIT_ITEM(ICON_MaxSpeedX, GET_TEXT_F(MSG_MAXSPEED_X), onDrawMaxSpeedX, SetMaxSpeedX, &planner.settings.max_feedrate_mm_s[X_AXIS]); + EDIT_ITEM(ICON_MaxSpeedY, GET_TEXT_F(MSG_MAXSPEED_Y), onDrawMaxSpeedY, SetMaxSpeedY, &planner.settings.max_feedrate_mm_s[Y_AXIS]); + EDIT_ITEM(ICON_MaxSpeedZ, GET_TEXT_F(MSG_MAXSPEED_Z), onDrawMaxSpeedZ, SetMaxSpeedZ, &planner.settings.max_feedrate_mm_s[Z_AXIS]); #if HAS_HOTEND - ADDMENUITEM_P(ICON_MaxSpeedE, GET_TEXT_F(MSG_MAXSPEED_E), onDrawMaxSpeedE, SetMaxSpeedE, &planner.settings.max_feedrate_mm_s[E_AXIS]); + EDIT_ITEM(ICON_MaxSpeedE, GET_TEXT_F(MSG_MAXSPEED_E), onDrawMaxSpeedE, SetMaxSpeedE, &planner.settings.max_feedrate_mm_s[E_AXIS]); #endif } CurrentMenu->draw(); @@ -3639,12 +3658,12 @@ void Draw_MaxAccel_Menu() { CurrentMenu = MaxAccelMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_ACCELERATION)); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); - ADDMENUITEM_P(ICON_MaxAccX, GET_TEXT_F(MSG_AMAX_A), onDrawMaxAccelX, SetMaxAccelX, &planner.settings.max_acceleration_mm_per_s2[X_AXIS]); - ADDMENUITEM_P(ICON_MaxAccY, GET_TEXT_F(MSG_AMAX_B), onDrawMaxAccelY, SetMaxAccelY, &planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); - ADDMENUITEM_P(ICON_MaxAccZ, GET_TEXT_F(MSG_AMAX_C), onDrawMaxAccelZ, SetMaxAccelZ, &planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); + EDIT_ITEM(ICON_MaxAccX, GET_TEXT_F(MSG_AMAX_A), onDrawMaxAccelX, SetMaxAccelX, &planner.settings.max_acceleration_mm_per_s2[X_AXIS]); + EDIT_ITEM(ICON_MaxAccY, GET_TEXT_F(MSG_AMAX_B), onDrawMaxAccelY, SetMaxAccelY, &planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); + EDIT_ITEM(ICON_MaxAccZ, GET_TEXT_F(MSG_AMAX_C), onDrawMaxAccelZ, SetMaxAccelZ, &planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); #if HAS_HOTEND - ADDMENUITEM_P(ICON_MaxAccE, GET_TEXT_F(MSG_AMAX_E), onDrawMaxAccelE, SetMaxAccelE, &planner.settings.max_acceleration_mm_per_s2[E_AXIS]); + EDIT_ITEM(ICON_MaxAccE, GET_TEXT_F(MSG_AMAX_E), onDrawMaxAccelE, SetMaxAccelE, &planner.settings.max_acceleration_mm_per_s2[E_AXIS]); #endif } CurrentMenu->draw(); @@ -3658,12 +3677,12 @@ void Draw_MaxAccel_Menu() { CurrentMenu = MaxJerkMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_JERK)); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); - ADDMENUITEM_P(ICON_MaxSpeedJerkX, GET_TEXT_F(MSG_VA_JERK), onDrawMaxJerkX, SetMaxJerkX, &planner.max_jerk[X_AXIS]); - ADDMENUITEM_P(ICON_MaxSpeedJerkY, GET_TEXT_F(MSG_VB_JERK), onDrawMaxJerkY, SetMaxJerkY, &planner.max_jerk[Y_AXIS]); - ADDMENUITEM_P(ICON_MaxSpeedJerkZ, GET_TEXT_F(MSG_VC_JERK), onDrawMaxJerkZ, SetMaxJerkZ, &planner.max_jerk[Z_AXIS]); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); + EDIT_ITEM(ICON_MaxSpeedJerkX, GET_TEXT_F(MSG_VA_JERK), onDrawMaxJerkX, SetMaxJerkX, &planner.max_jerk[X_AXIS]); + EDIT_ITEM(ICON_MaxSpeedJerkY, GET_TEXT_F(MSG_VB_JERK), onDrawMaxJerkY, SetMaxJerkY, &planner.max_jerk[Y_AXIS]); + EDIT_ITEM(ICON_MaxSpeedJerkZ, GET_TEXT_F(MSG_VC_JERK), onDrawMaxJerkZ, SetMaxJerkZ, &planner.max_jerk[Z_AXIS]); #if HAS_HOTEND - ADDMENUITEM_P(ICON_MaxSpeedJerkE, GET_TEXT_F(MSG_VE_JERK), onDrawMaxJerkE, SetMaxJerkE, &planner.max_jerk[E_AXIS]); + EDIT_ITEM(ICON_MaxSpeedJerkE, GET_TEXT_F(MSG_VE_JERK), onDrawMaxJerkE, SetMaxJerkE, &planner.max_jerk[E_AXIS]); #endif } CurrentMenu->draw(); @@ -3677,12 +3696,12 @@ void Draw_Steps_Menu() { CurrentMenu = StepsMenu; SetMenuTitle({1, 16, 28, 13}, GET_TEXT_F(MSG_STEPS_PER_MM)); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); - ADDMENUITEM_P(ICON_StepX, GET_TEXT_F(MSG_A_STEPS), onDrawStepsX, SetStepsX, &planner.settings.axis_steps_per_mm[X_AXIS]); - ADDMENUITEM_P(ICON_StepY, GET_TEXT_F(MSG_B_STEPS), onDrawStepsY, SetStepsY, &planner.settings.axis_steps_per_mm[Y_AXIS]); - ADDMENUITEM_P(ICON_StepZ, GET_TEXT_F(MSG_C_STEPS), onDrawStepsZ, SetStepsZ, &planner.settings.axis_steps_per_mm[Z_AXIS]); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Motion_Menu); + EDIT_ITEM(ICON_StepX, GET_TEXT_F(MSG_A_STEPS), onDrawStepsX, SetStepsX, &planner.settings.axis_steps_per_mm[X_AXIS]); + EDIT_ITEM(ICON_StepY, GET_TEXT_F(MSG_B_STEPS), onDrawStepsY, SetStepsY, &planner.settings.axis_steps_per_mm[Y_AXIS]); + EDIT_ITEM(ICON_StepZ, GET_TEXT_F(MSG_C_STEPS), onDrawStepsZ, SetStepsZ, &planner.settings.axis_steps_per_mm[Z_AXIS]); #if HAS_HOTEND - ADDMENUITEM_P(ICON_StepE, GET_TEXT_F(MSG_E_STEPS), onDrawStepsE, SetStepsE, &planner.settings.axis_steps_per_mm[E_AXIS]); + EDIT_ITEM(ICON_StepE, GET_TEXT_F(MSG_E_STEPS), onDrawStepsE, SetStepsE, &planner.settings.axis_steps_per_mm[E_AXIS]); #endif } CurrentMenu->draw(); @@ -3696,15 +3715,15 @@ void Draw_Steps_Menu() { CurrentMenu = HotendPIDMenu; CurrentMenu->MenuTitle.SetCaption(F("Hotend PID Settings")); DWINUI::MenuItemsPrepare(8); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); - ADDMENUITEM(ICON_PIDNozzle, F("Hotend PID"), onDrawMenuItem, HotendPID); - ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_hotend[0].pid.Kp); - ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_hotend[0].pid.Ki); - ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_hotend[0].pid.Kd); - ADDMENUITEM_P(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawPIntMenu, SetHotendPidT, &HMI_data.HotendPidT); - ADDMENUITEM_P(ICON_PIDcycles, GET_TEXT_F(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); + MENU_ITEM(ICON_PIDNozzle, F("Hotend PID"), onDrawMenuItem, HotendPID); + EDIT_ITEM(ICON_PIDValue, F("Set" STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_hotend[0].pid.Kp); + EDIT_ITEM(ICON_PIDValue, F("Set" STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_hotend[0].pid.Ki); + EDIT_ITEM(ICON_PIDValue, F("Set" STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_hotend[0].pid.Kd); + EDIT_ITEM(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawPIntMenu, SetHotendPidT, &HMI_data.HotendPidT); + EDIT_ITEM(ICON_PIDcycles, GET_TEXT_F(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); #if ENABLED(EEPROM_SETTINGS) - ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); + MENU_ITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); #endif } CurrentMenu->draw(); @@ -3719,15 +3738,15 @@ void Draw_Steps_Menu() { CurrentMenu = BedPIDMenu; CurrentMenu->MenuTitle.SetCaption(F("Bed PID Settings")); DWINUI::MenuItemsPrepare(8); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); - ADDMENUITEM(ICON_PIDNozzle, F("Bed PID"), onDrawMenuItem,BedPID); - ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_bed.pid.Kp); - ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_bed.pid.Ki); - ADDMENUITEM_P(ICON_PIDValue, F("Set" STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_bed.pid.Kd); - ADDMENUITEM_P(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawPIntMenu, SetBedPidT, &HMI_data.BedPidT); - ADDMENUITEM_P(ICON_PIDcycles, GET_TEXT_F(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_AdvancedSettings_Menu); + MENU_ITEM(ICON_PIDNozzle, F("Bed PID"), onDrawMenuItem,BedPID); + EDIT_ITEM(ICON_PIDValue, F("Set" STR_KP), onDrawPFloat2Menu, SetKp, &thermalManager.temp_bed.pid.Kp); + EDIT_ITEM(ICON_PIDValue, F("Set" STR_KI), onDrawPIDi, SetKi, &thermalManager.temp_bed.pid.Ki); + EDIT_ITEM(ICON_PIDValue, F("Set" STR_KD), onDrawPIDd, SetKd, &thermalManager.temp_bed.pid.Kd); + EDIT_ITEM(ICON_Temperature, GET_TEXT_F(MSG_TEMPERATURE), onDrawPIntMenu, SetBedPidT, &HMI_data.BedPidT); + EDIT_ITEM(ICON_PIDcycles, GET_TEXT_F(MSG_PID_CYCLE), onDrawPIntMenu, SetPidCycles, &HMI_data.PidCycles); #if ENABLED(EEPROM_SETTINGS) - ADDMENUITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); + MENU_ITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); #endif } CurrentMenu->draw(); @@ -3742,10 +3761,10 @@ void Draw_Steps_Menu() { CurrentMenu = ZOffsetWizMenu; CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_PROBE_WIZARD)); DWINUI::MenuItemsPrepare(4); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_Prepare_Menu); - ADDMENUITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawMenuItem, AutoHome); - ADDMENUITEM(ICON_MoveZ0, F("Move Z to Home"), onDrawMenuItem, SetMoveZto0); - ADDMENUITEM_P(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_Prepare_Menu); + MENU_ITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawMenuItem, AutoHome); + MENU_ITEM(ICON_MoveZ0, F("Move Z to Home"), onDrawMenuItem, SetMoveZto0); + EDIT_ITEM(ICON_Zoffset, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetZOffset, &BABY_Z_VAR); } CurrentMenu->draw(); if (!axis_is_trusted(Z_AXIS)) LCD_MESSAGE_F("WARNING: Z position unknown, move Z to home"); @@ -3760,11 +3779,11 @@ void Draw_Steps_Menu() { CurrentMenu = HomingMenu; CurrentMenu->MenuTitle.SetCaption(GET_TEXT_F(MSG_HOMING)); DWINUI::MenuItemsPrepare(5); - ADDMENUITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_Prepare_Menu); - ADDMENUITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawMenuItem, AutoHome); - ADDMENUITEM(ICON_HomeX, GET_TEXT_F(MSG_AUTO_HOME_X), onDrawMenuItem, HomeX); - ADDMENUITEM(ICON_HomeY, GET_TEXT_F(MSG_AUTO_HOME_Y), onDrawMenuItem, HomeY); - ADDMENUITEM(ICON_HomeZ, GET_TEXT_F(MSG_AUTO_HOME_Z), onDrawMenuItem, HomeZ); + MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawMenuItem, Draw_Prepare_Menu); + MENU_ITEM(ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME), onDrawMenuItem, AutoHome); + MENU_ITEM(ICON_HomeX, GET_TEXT_F(MSG_AUTO_HOME_X), onDrawMenuItem, HomeX); + MENU_ITEM(ICON_HomeY, GET_TEXT_F(MSG_AUTO_HOME_Y), onDrawMenuItem, HomeY); + MENU_ITEM(ICON_HomeZ, GET_TEXT_F(MSG_AUTO_HOME_Z), onDrawMenuItem, HomeZ); } CurrentMenu->draw(); } diff --git a/Marlin/src/lcd/e3v2/enhanced/dwinui.h b/Marlin/src/lcd/e3v2/enhanced/dwinui.h index c92014e84ffc6..cb7720834c2c8 100644 --- a/Marlin/src/lcd/e3v2/enhanced/dwinui.h +++ b/Marlin/src/lcd/e3v2/enhanced/dwinui.h @@ -52,6 +52,7 @@ #define ICON_HomeX ICON_MoveX #define ICON_HomeY ICON_MoveY #define ICON_HomeZ ICON_MoveZ +#define ICON_HSMode ICON_StockConfiguration #define ICON_Tram ICON_SetEndTemp #define ICON_Lock ICON_Cool #define ICON_ManualMesh ICON_HotendTemp @@ -110,8 +111,8 @@ constexpr uint16_t TITLE_HEIGHT = 30, // Title bar heig #define MBASE(L) (MYPOS(L) + CAPOFF) // Create and add a MenuItem object to the menu array -#define ADDMENUITEM(V...) DWINUI::MenuItemsAdd(new MenuItemClass(V)) -#define ADDMENUITEM_P(V...) DWINUI::MenuItemsAdd(new MenuItemPtrClass(V)) +#define MENU_ITEM(V...) DWINUI::MenuItemsAdd(new MenuItemClass(V)) +#define EDIT_ITEM(V...) DWINUI::MenuItemsAdd(new MenuItemPtrClass(V)) typedef struct { uint16_t left, top, right, bottom; } rect_t; typedef struct { uint16_t x, y, w, h; } frame_rect_t; From 75d1f975a8623f73ddeb194dffd81ae257c70b35 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 9 Jan 2022 03:48:17 -0600 Subject: [PATCH 263/273] =?UTF-8?q?=F0=9F=94=A8=20Rename=20(not=20copy)=20?= =?UTF-8?q?with=20board=5Fbuild.rename?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/PlatformIO/scripts/offset_and_rename.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/buildroot/share/PlatformIO/scripts/offset_and_rename.py b/buildroot/share/PlatformIO/scripts/offset_and_rename.py index 00803b722efff..581a06e91e7ff 100644 --- a/buildroot/share/PlatformIO/scripts/offset_and_rename.py +++ b/buildroot/share/PlatformIO/scripts/offset_and_rename.py @@ -57,7 +57,6 @@ def encrypt(source, target, env): def rename_target(source, target, env): firmware = os.path.join(target[0].dir.path, board.get("build.rename")) - import shutil - shutil.copy(target[0].path, firmware) + os.rename(target[0].path, firmware) marlin.add_post_action(rename_target) From 27d252c80b679c98e429d0250af51727a1768f55 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Sun, 9 Jan 2022 10:49:39 +0100 Subject: [PATCH 264/273] =?UTF-8?q?=F0=9F=93=8C=20Improve=20Longer3D=20fan?= =?UTF-8?q?=20PWM=20(#23477)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h | 23 +++++++++++----------- 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index ca5ae45b3b75a..59fdc4a3c9141 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -89,20 +89,19 @@ #define HEATER_BED_PIN PA8 // pin 67 (Hot Bed Mosfet) #define FAN_PIN PA15 // pin 77 (4cm Fan) -#ifdef MAPLE_STM32F1 + +#if TERN(MAPLE_STM32F1, ENABLED(FAN_SOFT_PWM), ENABLED(FAST_PWM_FAN)) && FAN_MIN_PWM < 5 // Required to avoid issues with heating or STLink + #error "FAN_MIN_PWM must be 5 or higher." // Fan will not start in 1-30 range +#endif + +#if defined(MAPLE_STM32F1) || DISABLED(FAST_PWM_FAN) // STM32 HAL required to allow TIMER2 Hardware PWM #define FAN_SOFT_PWM_REQUIRED - #if ENABLED(FAN_SOFT_PWM) && FAN_MIN_PWM < 35 // Required to avoid issues with heating or STLink - #error "FAN_MIN_PWM must be 35 or higher." // Fan will not start in 1-30 range - #endif -#elif ENABLED(FAST_PWM_FAN) - #if FAST_PWM_FAN_FREQUENCY != 31400 // Default 1000 is noisy, max 65K (uint16) - #error "FAST_PWM_FAN_FREQUENCY must be set to 31400." - #endif - #if FAN_MIN_PWM < 5 - #error "FAN_MIN_PWM must be 5 or higher." - #endif #else - #error "FAST_PWM_FAN required to allow TIMER2 Hardware PWM." + #if FAST_PWM_FAN_FREQUENCY <= 1000 // Default 1000 is noisy, max 65K (uint16) + #error "FAST_PWM_FAN_FREQUENCY must be greater than 1000." + #elif FAST_PWM_FAN_FREQUENCY > 65535 + #error "FAST_PWM_FAN_FREQUENCY must be less than 65536." + #endif #endif //#define BEEPER_PIN PD13 // pin 60 (Servo PWM output 5V/GND on Board V0G+) made for BL-Touch sensor From 797859cf55cac781c8bb4b04eeeb4dd484b75ec6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Roman=20Morav=C4=8D=C3=ADk?= Date: Sun, 9 Jan 2022 10:51:16 +0100 Subject: [PATCH 265/273] =?UTF-8?q?=F0=9F=8C=90=20Update=20Slovak=20langua?= =?UTF-8?q?ge=20(#23475)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_sk.h | 49 ++++++++++++++++++++++++--- 1 file changed, 44 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 275fea3081708..db694e224271d 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -72,12 +72,10 @@ namespace Language_sk { LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test uk. priebehu"); LSTR MSG_HOMING = _UxGT("Parkovanie"); LSTR MSG_AUTO_HOME = _UxGT("Domovská pozícia"); + LSTR MSG_AUTO_HOME_A = _UxGT("Domov os @"); LSTR MSG_AUTO_HOME_X = _UxGT("Domov os X"); LSTR MSG_AUTO_HOME_Y = _UxGT("Domov os Y"); LSTR MSG_AUTO_HOME_Z = _UxGT("Domov os Z"); - LSTR MSG_AUTO_HOME_I = _UxGT("Domov os ") LCD_STR_I; - LSTR MSG_AUTO_HOME_J = _UxGT("Domov os ") LCD_STR_J; - LSTR MSG_AUTO_HOME_K = _UxGT("Domov os ") LCD_STR_K; LSTR MSG_FILAMENT_SET = _UxGT("Nastav. filamentu"); LSTR MSG_FILAMENT_MAN = _UxGT("Správa filamentu"); LSTR MSG_LEVBED_FL = _UxGT("Ľavý predný"); @@ -86,6 +84,7 @@ namespace Language_sk { LSTR MSG_LEVBED_BL = _UxGT("Ľavý zadný"); LSTR MSG_LEVBED_BR = _UxGT("Pravý zadný"); LSTR MSG_MANUAL_MESH = _UxGT("Ručná mriežka"); + LSTR MSG_AUTO_MESH = _UxGT("Automat. mriežka"); LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto-zarovn. Z"); LSTR MSG_ITERATION = _UxGT("Iterácia G34: %i"); LSTR MSG_DECREASING_ACCURACY = _UxGT("Klesajúca presnosť!"); @@ -156,8 +155,11 @@ namespace Language_sk { LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Posl. Z: "); LSTR MSG_NEXT_CORNER = _UxGT("Ďalší roh"); LSTR MSG_MESH_EDITOR = _UxGT("Editor sieťe bodov"); + LSTR MSG_MESH_VIEWER = _UxGT("Zobraz. sieťe bodov"); LSTR MSG_EDIT_MESH = _UxGT("Upraviť sieť bodov"); + LSTR MSG_MESH_VIEW = _UxGT("Zobraz. sieť bodov"); LSTR MSG_EDITING_STOPPED = _UxGT("Koniec úprav siete"); + LSTR MSG_NO_VALID_MESH = _UxGT("Neplatná sieť bodov"); LSTR MSG_PROBING_POINT = _UxGT("Skúšam bod"); LSTR MSG_MESH_X = _UxGT("Index X"); LSTR MSG_MESH_Y = _UxGT("Index Y"); @@ -397,6 +399,7 @@ namespace Language_sk { LSTR MSG_ADVANCE_K = _UxGT("K pre posun"); LSTR MSG_ADVANCE_K_E = _UxGT("K pre posun *"); LSTR MSG_CONTRAST = _UxGT("Kontrast LCD"); + LSTR MSG_BRIGHTNESS = _UxGT("Jas LCD"); LSTR MSG_STORE_EEPROM = _UxGT("Uložiť nastavenie"); LSTR MSG_LOAD_EEPROM = _UxGT("Načítať nastavenie"); LSTR MSG_RESTORE_DEFAULTS = _UxGT("Obnoviť nastavenie"); @@ -427,8 +430,14 @@ namespace Language_sk { LSTR MSG_BUTTON_BACK = _UxGT("Naspäť"); LSTR MSG_BUTTON_PROCEED = _UxGT("Pokračovať"); LSTR MSG_BUTTON_SKIP = _UxGT("Preskočiť"); + LSTR MSG_BUTTON_INFO = _UxGT("Informácie"); + LSTR MSG_BUTTON_LEVEL = _UxGT("Vyrovnať"); + LSTR MSG_BUTTON_PAUSE = _UxGT("Pauza"); + LSTR MSG_BUTTON_RESUME = _UxGT("Obnoviť"); + LSTR MSG_BUTTON_ADVANCED = _UxGT("Pokročilé"); LSTR MSG_PAUSING = _UxGT("Pozastavujem..."); LSTR MSG_PAUSE_PRINT = _UxGT("Pozastaviť tlač"); + LSTR MSG_ADVANCED_PAUSE = _UxGT("Pokročil. pauza"); LSTR MSG_RESUME_PRINT = _UxGT("Obnoviť tlač"); LSTR MSG_HOST_START_PRINT = _UxGT("Spustiť z hosta"); LSTR MSG_STOP_PRINT = _UxGT("Zastaviť tlač"); @@ -437,12 +446,14 @@ namespace Language_sk { LSTR MSG_CANCEL_OBJECT = _UxGT("Zrušiť objekt"); LSTR MSG_CANCEL_OBJECT_N = _UxGT("Zrušiť objekt ="); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Obnova po výp. nap."); + LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Pokračovať v úlohe"); LSTR MSG_MEDIA_MENU = _UxGT("Tlačiť z SD"); LSTR MSG_NO_MEDIA = _UxGT("Žiadna SD karta"); LSTR MSG_DWELL = _UxGT("Spím..."); LSTR MSG_USERWAIT = _UxGT("Pokrač. kliknutím..."); LSTR MSG_PRINT_PAUSED = _UxGT("Tlač pozastavená"); LSTR MSG_PRINTING = _UxGT("Tlačím..."); + LSTR MSG_STOPPING = _UxGT("Zastavujem..."); LSTR MSG_PRINT_ABORTED = _UxGT("Tlač zrušená"); LSTR MSG_PRINT_DONE = _UxGT("Tlač dokončená"); LSTR MSG_NO_MOVE = _UxGT("Žiadny pohyb."); @@ -492,6 +503,7 @@ namespace Language_sk { LSTR MSG_BLTOUCH_STOW = _UxGT("Zasunúť"); LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Vysunúť"); LSTR MSG_BLTOUCH_SW_MODE = _UxGT("Režim SW"); + LSTR MSG_BLTOUCH_SPEED_MODE = _UxGT("Vysoká rýchl."); LSTR MSG_BLTOUCH_5V_MODE = _UxGT("Režim 5V"); LSTR MSG_BLTOUCH_OD_MODE = _UxGT("Režim OD"); LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Ulož. režim"); @@ -524,6 +536,7 @@ namespace Language_sk { LSTR MSG_HEATING_FAILED_LCD = _UxGT("Chyba ohrevu"); LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Chyba: REDUND. TEP."); LSTR MSG_THERMAL_RUNAWAY = _UxGT("TEPLOTNÝ SKOK"); + LSTR MSG_TEMP_MALFUNCTION = _UxGT("TEPLOTNÁ PORUCHA"); LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("TEPLOTNÝ SKOK PODL."); LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("TEPLOTNÝ SKOK KOMO."); LSTR MSG_THERMAL_RUNAWAY_COOLER = _UxGT("TEPLOTNÝ SKOK CHLAD."); @@ -531,7 +544,9 @@ namespace Language_sk { LSTR MSG_ERR_MAXTEMP = _UxGT("Chyba: MAXTEMP"); LSTR MSG_ERR_MINTEMP = _UxGT("Chyba: MINTEMP"); LSTR MSG_HALTED = _UxGT("TLAČIAREŇ ZASTAVENÁ"); + LSTR MSG_PLEASE_WAIT = _UxGT("Čakajte prosím..."); LSTR MSG_PLEASE_RESET = _UxGT("Reštartuje ju"); + LSTR MSG_PREHEATING = _UxGT("Zahrievanie..."); LSTR MSG_HEATING = _UxGT("Ohrev..."); LSTR MSG_COOLING = _UxGT("Ochladzovanie..."); LSTR MSG_BED_HEATING = _UxGT("Ohrev podložky..."); @@ -570,25 +585,42 @@ namespace Language_sk { LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Tepl. ochrana: VYP"); LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Tepl. ochrana: ZAP"); LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Vypr.čas nečinnosti"); + LSTR MSG_FAN_SPEED_FAULT = _UxGT("Chyba rýchl. vent."); LSTR MSG_CASE_LIGHT = _UxGT("Osvetlenie"); LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jas svetla"); LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Nesprávna tlačiareň"); #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 + LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("Nie je vložená karta."); + LSTR MSG_REMAINING_TIME = _UxGT("Zostávajúci čas"); + LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Prosím čakajte do reštartu. "); + LSTR MSG_PLEASE_PREHEAT = _UxGT("Prosím zahrejte hotend."); + LSTR MSG_INFO_PRINT_COUNT_RESET = _UxGT("Vynulovať počítadlo"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Počet tlačí"); - LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Dokončené"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Celkový čas"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Najdlhšia tlač"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Celkom vytlačené"); + LSTR MSG_COLORS_GET = _UxGT("Zvoliť farbu"); + LSTR MSG_COLORS_SELECT = _UxGT("Zvoliť farby"); + LSTR MSG_COLORS_APPLIED = _UxGT("Farby aplikované"); + LSTR MSG_COLORS_RED = _UxGT("Červená"); + LSTR MSG_COLORS_GREEN = _UxGT("Zelená"); + LSTR MSG_COLORS_BLUE = _UxGT("Modrá"); + LSTR MSG_UI_LANGUAGE = _UxGT("Jazyk rozhrania"); + LSTR MSG_SOUND_ENABLE = _UxGT("Povoliť zvuky"); + LSTR MSG_LOCKSCREEN = _UxGT("Uzamknúť obrazovku"); #else + LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("Žiadna karta"); + LSTR MSG_PLEASE_PREHEAT = _UxGT("Prosím zahrejte"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Tlače"); - LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Hotovo"); + LSTR MSG_REMAINING_TIME = _UxGT("Zostávajúci"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Čas"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Najdlhšia"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Vytlačené"); #endif + LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Dokončené"); LSTR MSG_INFO_MIN_TEMP = _UxGT("Teplota min"); LSTR MSG_INFO_MAX_TEMP = _UxGT("Teplota max"); LSTR MSG_INFO_PSU = _UxGT("Nap. zdroj"); @@ -613,6 +645,7 @@ namespace Language_sk { LSTR MSG_RUNOUT_SENSOR = _UxGT("Senzor filamentu"); LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Vzd. mm fil. senz."); LSTR MSG_RUNOUT_ENABLE = _UxGT("Zapnúť senzor"); + LSTR MSG_FANCHECK = _UxGT("Kontrola rýchl."); LSTR MSG_KILL_HOMING_FAILED = _UxGT("Parkovanie zlyhalo"); LSTR MSG_LCD_PROBING_FAILED = _UxGT("Kalibrácia zlyhala"); @@ -732,6 +765,10 @@ namespace Language_sk { LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Referencia Z"); LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Presúvam na pozíciu"); + LSTR MSG_XATC = _UxGT("Sprievodca X-Twist"); + LSTR MSG_XATC_DONE = _UxGT("Spriev. X-Twist dokonč.!"); + LSTR MSG_XATC_UPDATE_Z_OFFSET = _UxGT("Aktual. ofset sondy Z na "); + LSTR MSG_SOUND = _UxGT("Zvuk"); LSTR MSG_TOP_LEFT = _UxGT("Ľavý horný"); @@ -745,4 +782,6 @@ namespace Language_sk { LSTR MSG_SD_CARD = _UxGT("SD karta"); LSTR MSG_USB_DISK = _UxGT("USB disk"); + + LSTR MSG_HOST_SHUTDOWN = _UxGT("Vypnúť hosta"); } From 13adcd5c08b7065a32f59d00c17c9bc3a351429c Mon Sep 17 00:00:00 2001 From: David Ross Smith <5095074+DragRedSim@users.noreply.github.com> Date: Fri, 7 Jan 2022 22:44:44 +1100 Subject: [PATCH 266/273] =?UTF-8?q?=F0=9F=9A=91=EF=B8=8F=20Fix=20preheat?= =?UTF-8?q?=20target=20bug?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes Jyers/Marlin#1651 --- Marlin/src/lcd/marlinui.cpp | 8 ++++---- Marlin/src/lcd/marlinui.h | 18 ++++++++---------- 2 files changed, 12 insertions(+), 14 deletions(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 5cf3e668260b4..7b3e267310fb2 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -150,10 +150,10 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; void MarlinUI::apply_preheat(const uint8_t m, const uint8_t pmask, const uint8_t e/*=active_extruder*/) { const preheat_t &pre = material_preset[m]; - TERN_(HAS_HOTEND, if (TEST(pmask, PM_HOTEND)) thermalManager.setTargetHotend(pre.hotend_temp, e)); - TERN_(HAS_HEATED_BED, if (TEST(pmask, PM_BED)) thermalManager.setTargetBed(pre.bed_temp)); - //TERN_(HAS_HEATED_CHAMBER, if (TEST(pmask, PM_CHAMBER)) thermalManager.setTargetBed(pre.chamber_temp)); - TERN_(HAS_FAN, if (TEST(pmask, PM_FAN)) thermalManager.set_fan_speed(0, pre.fan_speed)); + TERN_(HAS_HOTEND, if (TEST(pmask, PT_HOTEND)) thermalManager.setTargetHotend(pre.hotend_temp, e)); + TERN_(HAS_HEATED_BED, if (TEST(pmask, PT_BED)) thermalManager.setTargetBed(pre.bed_temp)); + //TERN_(HAS_HEATED_CHAMBER, if (TEST(pmask, PT_CHAMBER)) thermalManager.setTargetBed(pre.chamber_temp)); + TERN_(HAS_FAN, if (TEST(pmask, PT_FAN)) thermalManager.set_fan_speed(0, pre.fan_speed)); } #endif diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index e9aa0a6da543a..f409970e42a79 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -496,22 +496,20 @@ class MarlinUI { #endif #if HAS_PREHEAT - enum PreheatMask : uint8_t { PM_HOTEND = _BV(0), PM_BED = _BV(1), PM_FAN = _BV(2), PM_CHAMBER = _BV(3) }; + enum PreheatTarget : uint8_t { PT_HOTEND, PT_BED, PT_FAN, PT_CHAMBER, PT_ALL = 0xFF }; static preheat_t material_preset[PREHEAT_COUNT]; static PGM_P get_preheat_label(const uint8_t m); static void apply_preheat(const uint8_t m, const uint8_t pmask, const uint8_t e=active_extruder); - static void preheat_set_fan(const uint8_t m) { TERN_(HAS_FAN, apply_preheat(m, PM_FAN)); } - static void preheat_hotend(const uint8_t m, const uint8_t e=active_extruder) { TERN_(HAS_HOTEND, apply_preheat(m, PM_HOTEND)); } + static void preheat_set_fan(const uint8_t m) { TERN_(HAS_FAN, apply_preheat(m, _BV(PT_FAN))); } + static void preheat_hotend(const uint8_t m, const uint8_t e=active_extruder) { TERN_(HAS_HOTEND, apply_preheat(m, _BV(PT_HOTEND))); } static void preheat_hotend_and_fan(const uint8_t m, const uint8_t e=active_extruder) { preheat_hotend(m, e); preheat_set_fan(m); } - static void preheat_bed(const uint8_t m) { TERN_(HAS_HEATED_BED, apply_preheat(m, PM_BED)); } - static void preheat_all(const uint8_t m) { apply_preheat(m, 0xFF); } + static void preheat_bed(const uint8_t m) { TERN_(HAS_HEATED_BED, apply_preheat(m, _BV(PT_BED))); } + static void preheat_all(const uint8_t m) { apply_preheat(m, PT_ALL); } #endif - #if SCREENS_CAN_TIME_OUT - static void reset_status_timeout(const millis_t ms) { return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS; } - #else - static void reset_status_timeout(const millis_t) {} - #endif + static void reset_status_timeout(const millis_t ms) { + TERN(SCREENS_CAN_TIME_OUT, return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS, UNUSED(ms)); + } #if HAS_LCD_MENU From 80128ae456318cde87e1c6374215b14b8b6c0879 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 9 Jan 2022 04:39:15 -0600 Subject: [PATCH 267/273] =?UTF-8?q?=F0=9F=8C=90=20Update=20auto=20home=20a?= =?UTF-8?q?xis=20strings?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_fr.h | 4 +--- Marlin/src/lcd/language/language_hu.h | 4 +--- Marlin/src/lcd/language/language_it.h | 4 +--- Marlin/src/lcd/language/language_ru.h | 4 +--- Marlin/src/lcd/language/language_uk.h | 4 +--- 5 files changed, 5 insertions(+), 15 deletions(-) diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index d72578d8d629a..41ab9ebaf15d7 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -58,12 +58,10 @@ namespace Language_fr { LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test barre progress."); LSTR MSG_HOMING = _UxGT("Origine"); LSTR MSG_AUTO_HOME = _UxGT("Origine auto"); + LSTR MSG_AUTO_HOME_A = _UxGT("Origine @ auto"); LSTR MSG_AUTO_HOME_X = _UxGT("Origine X auto"); LSTR MSG_AUTO_HOME_Y = _UxGT("Origine Y auto"); LSTR MSG_AUTO_HOME_Z = _UxGT("Origine Z auto"); - LSTR MSG_AUTO_HOME_I = _UxGT("Origine ") LCD_STR_I _UxGT(" auto"); - LSTR MSG_AUTO_HOME_J = _UxGT("Origine ") LCD_STR_J _UxGT(" auto"); - LSTR MSG_AUTO_HOME_K = _UxGT("Origine ") LCD_STR_K _UxGT(" auto"); LSTR MSG_AUTO_Z_ALIGN = _UxGT("Align. Z auto"); LSTR MSG_LEVEL_BED_HOMING = _UxGT("Origine XYZ..."); LSTR MSG_LEVEL_BED_WAITING = _UxGT("Clic pour commencer"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index cfe7af58974c6..8b5e7863030b3 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -62,12 +62,10 @@ namespace Language_hu { LSTR MSG_DEBUG_MENU = _UxGT("Hiba Menü"); LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Haladás sáv teszt"); LSTR MSG_AUTO_HOME = _UxGT("X-Y-Z auto kezdöpont"); + LSTR MSG_AUTO_HOME_A = _UxGT("Kezdö @"); LSTR MSG_AUTO_HOME_X = _UxGT("X kezdöpont"); LSTR MSG_AUTO_HOME_Y = _UxGT("Y kezdöpont"); LSTR MSG_AUTO_HOME_Z = _UxGT("Z kezdöpont"); - LSTR MSG_AUTO_HOME_I = _UxGT("Kezdö ") LCD_STR_I; - LSTR MSG_AUTO_HOME_J = _UxGT("Kezdö ") LCD_STR_J; - LSTR MSG_AUTO_HOME_K = _UxGT("Kezdö ") LCD_STR_K; LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-igazítás"); LSTR MSG_ITERATION = _UxGT("G34 Ismétlés: %i"); LSTR MSG_DECREASING_ACCURACY = _UxGT("Pontosság csökken!"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index e0ae0e62a489e..1c36a5de2152d 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -68,12 +68,10 @@ namespace Language_it { LSTR MSG_DEBUG_MENU = _UxGT("Menu di debug"); LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Test barra avanzam."); LSTR MSG_AUTO_HOME = _UxGT("Auto Home"); + LSTR MSG_AUTO_HOME_A = _UxGT("Home @"); LSTR MSG_AUTO_HOME_X = _UxGT("Home X"); LSTR MSG_AUTO_HOME_Y = _UxGT("Home Y"); LSTR MSG_AUTO_HOME_Z = _UxGT("Home Z"); - LSTR MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; - LSTR MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; - LSTR MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; LSTR MSG_AUTO_Z_ALIGN = _UxGT("Allineam.automat. Z"); LSTR MSG_ITERATION = _UxGT("Iterazione G34: %i"); LSTR MSG_DECREASING_ACCURACY = _UxGT("Precisione in calo!"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 774636f1ed10b..5e3d0f2fac348 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -66,12 +66,10 @@ namespace Language_ru { LSTR MSG_DEBUG_MENU = _UxGT("Меню отладки"); LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Тест индикатора"); LSTR MSG_AUTO_HOME = _UxGT("Парковка XYZ"); + LSTR MSG_AUTO_HOME_A = _UxGT("Парковка @"); LSTR MSG_AUTO_HOME_X = _UxGT("Парковка X"); LSTR MSG_AUTO_HOME_Y = _UxGT("Парковка Y"); LSTR MSG_AUTO_HOME_Z = _UxGT("Парковка Z"); - LSTR MSG_AUTO_HOME_I = _UxGT("Парковка ") LCD_STR_I; - LSTR MSG_AUTO_HOME_J = _UxGT("Парковка ") LCD_STR_J; - LSTR MSG_AUTO_HOME_K = _UxGT("Парковка ") LCD_STR_K; LSTR MSG_AUTO_Z_ALIGN = _UxGT("Авто Z-выравнивание"); LSTR MSG_ITERATION = _UxGT("G34 Итерация: %i"); LSTR MSG_DECREASING_ACCURACY = _UxGT("Уменьшение точности!"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 798351c67e22b..028e48bb41bc6 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -68,12 +68,10 @@ namespace Language_uk { LSTR MSG_DEBUG_MENU = _UxGT("Меню Debug"); LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Тест лінії прогр."); LSTR MSG_AUTO_HOME = _UxGT("Авто паркування"); + LSTR MSG_AUTO_HOME_A = _UxGT("Паркування @"); LSTR MSG_AUTO_HOME_X = _UxGT("Паркування X"); LSTR MSG_AUTO_HOME_Y = _UxGT("Паркування Y"); LSTR MSG_AUTO_HOME_Z = _UxGT("Паркування Z"); - LSTR MSG_AUTO_HOME_I = _UxGT("Паркування ") LCD_STR_I; - LSTR MSG_AUTO_HOME_J = _UxGT("Паркування ") LCD_STR_J; - LSTR MSG_AUTO_HOME_K = _UxGT("Паркування ") LCD_STR_K; LSTR MSG_AUTO_Z_ALIGN = _UxGT("Авто Z-вирівнювання"); LSTR MSG_ITERATION = _UxGT("G34 Ітерація: %i"); LSTR MSG_DECREASING_ACCURACY = _UxGT("Зменьшення точності!"); From 0dfc17ca607640c62f4e53ed7bf39d3782773fe6 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 10 Jan 2022 01:06:10 +0000 Subject: [PATCH 268/273] [cron] Bump distribution date (2022-01-10) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 8d302652092d8..8feb7385b8ce4 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2022-01-09" +//#define STRING_DISTRIBUTION_DATE "2022-01-10" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e571b342a0523..75ffed65330f1 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2022-01-09" + #define STRING_DISTRIBUTION_DATE "2022-01-10" #endif /** From a719020348e121245ba2ec6c5e60149c661241a0 Mon Sep 17 00:00:00 2001 From: DerAndere <26200979+DerAndere1@users.noreply.github.com> Date: Mon, 10 Jan 2022 09:44:16 +0100 Subject: [PATCH 269/273] =?UTF-8?q?=F0=9F=9A=B8=20Include=20extra=20axes?= =?UTF-8?q?=20in=20position=20report=20(#23490)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/motion.cpp | 32 +++++++++++++------------------- 1 file changed, 13 insertions(+), 19 deletions(-) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index a77f395fb4c2b..23084c48fbcb3 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -217,9 +217,7 @@ void report_real_position() { xyze_pos_t npos = LOGICAL_AXIS_ARRAY( planner.get_axis_position_mm(E_AXIS), cartes.x, cartes.y, cartes.z, - planner.get_axis_position_mm(I_AXIS), - planner.get_axis_position_mm(J_AXIS), - planner.get_axis_position_mm(K_AXIS) + cartes.i, cartes.j, cartes.k ); TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(npos, true)); @@ -263,27 +261,23 @@ void report_current_position_projected() { * Output the current position (processed) to serial while moving */ void report_current_position_moving() { - get_cartesian_from_steppers(); const xyz_pos_t lpos = cartes.asLogical(); - SERIAL_ECHOPGM( - "X:", lpos.x - #if HAS_Y_AXIS - , " Y:", lpos.y - #endif - #if HAS_Z_AXIS - , " Z:", lpos.z - #endif - #if HAS_EXTRUDERS - , " E:", current_position.e - #endif + + SERIAL_ECHOPGM_P( + LIST_N(DOUBLE(LOGICAL_AXES), + SP_E_LBL, current_position.e, + X_LBL, lpos.x, + SP_Y_LBL, lpos.y, + SP_Z_LBL, lpos.z, + SP_I_LBL, lpos.i, + SP_J_LBL, lpos.j, + SP_K_LBL, lpos.k + ) ); stepper.report_positions(); - #if IS_SCARA - scara_report_positions(); - #endif - + TERN_(IS_SCARA, scara_report_positions()); report_current_grblstate_moving(); } From 9665a4434cee0386fa2a63a058b6f2598943ee98 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 10 Jan 2022 02:51:34 -0600 Subject: [PATCH 270/273] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Few?= =?UTF-8?q?er=20string=20macros?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/language.h | 107 ++++++++---------- Marlin/src/core/serial.cpp | 8 +- Marlin/src/core/types.h | 2 +- Marlin/src/gcode/calibrate/G28.cpp | 6 +- Marlin/src/gcode/feature/pause/G61.cpp | 2 +- Marlin/src/gcode/motion/G0_G1.cpp | 2 +- Marlin/src/gcode/motion/M290.cpp | 2 +- .../generic/max_acceleration_screen.cpp | 8 +- .../generic/max_velocity_screen.cpp | 8 +- .../generic/temperature_screen.cpp | 8 +- Marlin/src/lcd/language/language_an.h | 26 ++--- Marlin/src/lcd/language/language_bg.h | 12 +- Marlin/src/lcd/language/language_ca.h | 12 +- Marlin/src/lcd/language/language_cz.h | 64 +++++------ Marlin/src/lcd/language/language_da.h | 12 +- Marlin/src/lcd/language/language_de.h | 66 +++++------ Marlin/src/lcd/language/language_el.h | 52 ++++----- Marlin/src/lcd/language/language_el_gr.h | 52 ++++----- Marlin/src/lcd/language/language_en.h | 102 ++++++++--------- Marlin/src/lcd/language/language_es.h | 64 +++++------ Marlin/src/lcd/language/language_eu.h | 36 +++--- Marlin/src/lcd/language/language_fr.h | 82 +++++++------- Marlin/src/lcd/language/language_gl.h | 64 +++++------ Marlin/src/lcd/language/language_hu.h | 82 +++++++------- Marlin/src/lcd/language/language_it.h | 82 +++++++------- Marlin/src/lcd/language/language_jp_kana.h | 44 +++---- Marlin/src/lcd/language/language_pl.h | 36 +++--- Marlin/src/lcd/language/language_pt.h | 12 +- Marlin/src/lcd/language/language_pt_br.h | 24 ++-- Marlin/src/lcd/language/language_ro.h | 64 +++++------ Marlin/src/lcd/language/language_ru.h | 88 +++++++------- Marlin/src/lcd/language/language_sk.h | 90 +++++++-------- Marlin/src/lcd/language/language_sv.h | 64 +++++------ Marlin/src/lcd/language/language_tr.h | 64 +++++------ Marlin/src/lcd/language/language_uk.h | 88 +++++++------- Marlin/src/lcd/language/language_vi.h | 64 +++++------ Marlin/src/lcd/language/language_zh_CN.h | 64 +++++------ Marlin/src/lcd/language/language_zh_TW.h | 64 +++++------ Marlin/src/lcd/menu/menu_advanced.cpp | 4 +- Marlin/src/lcd/menu/menu_info.cpp | 16 +-- Marlin/src/lcd/menu/menu_motion.cpp | 12 +- Marlin/src/lcd/menu/menu_tmc.cpp | 54 ++++----- Marlin/src/libs/L64XX/L64XX_Marlin.cpp | 2 +- Marlin/src/module/motion.cpp | 6 +- Marlin/src/module/planner.cpp | 6 +- Marlin/src/module/temperature.cpp | 4 +- 46 files changed, 910 insertions(+), 921 deletions(-) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index c1f2e7e31c4d0..a540c9c771252 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -341,9 +341,6 @@ #define STR_X "X" #define STR_Y "Y" #define STR_Z "Z" -#define STR_I AXIS4_STR -#define STR_J AXIS5_STR -#define STR_K AXIS6_STR #define STR_E "E" #if IS_KINEMATIC #define STR_A "A" @@ -360,115 +357,107 @@ #define STR_Z3 "Z3" #define STR_Z4 "Z4" -#define LCD_STR_A STR_A -#define LCD_STR_B STR_B -#define LCD_STR_C STR_C -#define LCD_STR_I STR_I -#define LCD_STR_J STR_J -#define LCD_STR_K STR_K -#define LCD_STR_E STR_E - // Extra Axis and Endstop Names #if HAS_I_AXIS #if AXIS4_NAME == 'A' - #define AXIS4_STR "A" + #define STR_I "A" #define STR_I_MIN "a_min" #define STR_I_MAX "a_max" #elif AXIS4_NAME == 'B' - #define AXIS4_STR "B" + #define STR_I "B" #define STR_I_MIN "b_min" #define STR_I_MAX "b_max" #elif AXIS4_NAME == 'C' - #define AXIS4_STR "C" + #define STR_I "C" #define STR_I_MIN "c_min" #define STR_I_MAX "c_max" #elif AXIS4_NAME == 'U' - #define AXIS4_STR "U" + #define STR_I "U" #define STR_I_MIN "u_min" #define STR_I_MAX "u_max" #elif AXIS4_NAME == 'V' - #define AXIS4_STR "V" + #define STR_I "V" #define STR_I_MIN "v_min" #define STR_I_MAX "v_max" #elif AXIS4_NAME == 'W' - #define AXIS4_STR "W" + #define STR_I "W" #define STR_I_MIN "w_min" #define STR_I_MAX "w_max" #else - #define AXIS4_STR "A" + #define STR_I "A" #define STR_I_MIN "a_min" #define STR_I_MAX "a_max" #endif #else - #define AXIS4_STR "" + #define STR_I "" #endif #if HAS_J_AXIS #if AXIS5_NAME == 'A' - #define AXIS5_STR "A" + #define STR_J "A" #define STR_J_MIN "a_min" #define STR_J_MAX "a_max" #elif AXIS5_NAME == 'B' - #define AXIS5_STR "B" + #define STR_J "B" #define STR_J_MIN "b_min" #define STR_J_MAX "b_max" #elif AXIS5_NAME == 'C' - #define AXIS5_STR "C" + #define STR_J "C" #define STR_J_MIN "c_min" #define STR_J_MAX "c_max" #elif AXIS5_NAME == 'U' - #define AXIS5_STR "U" + #define STR_J "U" #define STR_J_MIN "u_min" #define STR_J_MAX "u_max" #elif AXIS5_NAME == 'V' - #define AXIS5_STR "V" + #define STR_J "V" #define STR_J_MIN "v_min" #define STR_J_MAX "v_max" #elif AXIS5_NAME == 'W' - #define AXIS5_STR "W" + #define STR_J "W" #define STR_J_MIN "w_min" #define STR_J_MAX "w_max" #else - #define AXIS5_STR "B" + #define STR_J "B" #define STR_J_MIN "b_min" #define STR_J_MAX "b_max" #endif #else - #define AXIS5_STR "" + #define STR_J "" #endif #if HAS_K_AXIS #if AXIS6_NAME == 'A' - #define AXIS6_STR "A" + #define STR_K "A" #define STR_K_MIN "a_min" #define STR_K_MAX "a_max" #elif AXIS6_NAME == 'B' - #define AXIS6_STR "B" + #define STR_K "B" #define STR_K_MIN "b_min" #define STR_K_MAX "b_max" #elif AXIS6_NAME == 'C' - #define AXIS6_STR "C" + #define STR_K "C" #define STR_K_MIN "c_min" #define STR_K_MAX "c_max" #elif AXIS6_NAME == 'U' - #define AXIS6_STR "U" + #define STR_K "U" #define STR_K_MIN "u_min" #define STR_K_MAX "u_max" #elif AXIS6_NAME == 'V' - #define AXIS6_STR "V" + #define STR_K "V" #define STR_K_MIN "v_min" #define STR_K_MAX "v_max" #elif AXIS6_NAME == 'W' - #define AXIS6_STR "W" + #define STR_K "W" #define STR_K_MIN "w_min" #define STR_K_MAX "w_max" #else - #define AXIS6_STR "C" + #define STR_K "C" #define STR_K_MIN "c_min" #define STR_K_MAX "c_max" #endif #else - #define AXIS6_STR "" + #define STR_K "" #endif #if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) @@ -519,34 +508,34 @@ */ #if ENABLED(NUMBER_TOOLS_FROM_0) #define LCD_FIRST_TOOL 0 - #define LCD_STR_N0 "0" - #define LCD_STR_N1 "1" - #define LCD_STR_N2 "2" - #define LCD_STR_N3 "3" - #define LCD_STR_N4 "4" - #define LCD_STR_N5 "5" - #define LCD_STR_N6 "6" - #define LCD_STR_N7 "7" + #define STR_N0 "0" + #define STR_N1 "1" + #define STR_N2 "2" + #define STR_N3 "3" + #define STR_N4 "4" + #define STR_N5 "5" + #define STR_N6 "6" + #define STR_N7 "7" #else #define LCD_FIRST_TOOL 1 - #define LCD_STR_N0 "1" - #define LCD_STR_N1 "2" - #define LCD_STR_N2 "3" - #define LCD_STR_N3 "4" - #define LCD_STR_N4 "5" - #define LCD_STR_N5 "6" - #define LCD_STR_N6 "7" - #define LCD_STR_N7 "8" + #define STR_N0 "1" + #define STR_N1 "2" + #define STR_N2 "3" + #define STR_N3 "4" + #define STR_N4 "5" + #define STR_N5 "6" + #define STR_N6 "7" + #define STR_N7 "8" #endif -#define LCD_STR_E0 "E" LCD_STR_N0 -#define LCD_STR_E1 "E" LCD_STR_N1 -#define LCD_STR_E2 "E" LCD_STR_N2 -#define LCD_STR_E3 "E" LCD_STR_N3 -#define LCD_STR_E4 "E" LCD_STR_N4 -#define LCD_STR_E5 "E" LCD_STR_N5 -#define LCD_STR_E6 "E" LCD_STR_N6 -#define LCD_STR_E7 "E" LCD_STR_N7 +#define STR_E0 STR_E STR_N0 +#define STR_E1 STR_E STR_N1 +#define STR_E2 STR_E STR_N2 +#define STR_E3 STR_E STR_N3 +#define STR_E4 STR_E STR_N4 +#define STR_E5 STR_E STR_N5 +#define STR_E6 STR_E STR_N6 +#define STR_E7 STR_E STR_N7 // Include localized LCD Menu Messages diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 9cd862df702c7..2b1ae1f1fe006 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -36,10 +36,10 @@ PGMSTR(X_LBL, "X:"); PGMSTR(Y_LBL, "Y:"); PGMSTR(Z_LBL, "Z:"); PGMST PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C"); PGMSTR(SP_X_STR, " X"); PGMSTR(SP_Y_STR, " Y"); PGMSTR(SP_Z_STR, " Z"); PGMSTR(SP_E_STR, " E"); PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMSTR(SP_E_LBL, " E:"); -PGMSTR(I_STR, AXIS4_STR); PGMSTR(J_STR, AXIS5_STR); PGMSTR(K_STR, AXIS6_STR); -PGMSTR(I_LBL, AXIS4_STR ":"); PGMSTR(J_LBL, AXIS5_STR ":"); PGMSTR(K_LBL, AXIS6_STR ":"); -PGMSTR(SP_I_STR, " " AXIS4_STR); PGMSTR(SP_J_STR, " " AXIS5_STR); PGMSTR(SP_K_STR, " " AXIS6_STR); -PGMSTR(SP_I_LBL, " " AXIS4_STR ":"); PGMSTR(SP_J_LBL, " " AXIS5_STR ":"); PGMSTR(SP_K_LBL, " " AXIS6_STR ":"); +PGMSTR(I_STR, STR_I); PGMSTR(J_STR, STR_J); PGMSTR(K_STR, STR_K); +PGMSTR(I_LBL, STR_I ":"); PGMSTR(J_LBL, STR_J ":"); PGMSTR(K_LBL, STR_K ":"); +PGMSTR(SP_I_STR, " " STR_I); PGMSTR(SP_J_STR, " " STR_J); PGMSTR(SP_K_STR, " " STR_K); +PGMSTR(SP_I_LBL, " " STR_I ":"); PGMSTR(SP_J_LBL, " " STR_J ":"); PGMSTR(SP_K_LBL, " " STR_K ":"); // Hook Meatpack if it's enabled on the first leaf #if ENABLED(MEATPACK_ON_SERIAL_PORT_1) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index e5d95d81ec798..aee25a0dfff44 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -52,7 +52,7 @@ struct IF { typedef L type; }; #define LOGICAL_AXIS_ELEM(O) LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k) #define LOGICAL_AXIS_DECL(T,V) LOGICAL_AXIS_LIST(T e=V, T x=V, T y=V, T z=V, T i=V, T j=V, T k=V) -#define LOGICAL_AXES_STRING LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR) +#define LOGICAL_AXES_STRING LOGICAL_AXIS_GANG("E", "X", "Y", "Z", STR_I, STR_J, STR_K) #if HAS_EXTRUDERS #define LIST_ITEM_E(N) , N diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 421220e4106ab..bd651cd7d8304 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -293,17 +293,17 @@ void GcodeSuite::G28() { #if HAS_CURRENT_HOME(I) const int16_t tmc_save_current_I = stepperI.getMilliamps(); stepperI.rms_current(I_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(AXIS4_STR), tmc_save_current_I, I_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(F(STR_I), tmc_save_current_I, I_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(J) const int16_t tmc_save_current_J = stepperJ.getMilliamps(); stepperJ.rms_current(J_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(AXIS5_STR), tmc_save_current_J, J_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(F(STR_J), tmc_save_current_J, J_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(K) const int16_t tmc_save_current_K = stepperK.getMilliamps(); stepperK.rms_current(K_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current(F(AXIS6_STR), tmc_save_current_K, K_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(F(STR_K), tmc_save_current_K, K_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(Z) && ENABLED(DELTA) const int16_t tmc_save_current_Z = stepperZ.getMilliamps(); diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index f3e5a2ab387a0..18667501e4aae 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -68,7 +68,7 @@ void GcodeSuite::G61(void) { SYNC_E(stored_position[slot].e); } else { - if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { + if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K))) { DEBUG_ECHOPGM(STR_RESTORING_POS " S", slot); LOOP_LINEAR_AXES(i) { destination[i] = parser.seen(AXIS_CHAR(i)) diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index cc6979b74c12a..493fd00da187e 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -89,7 +89,7 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { if (MIN_AUTORETRACT <= MAX_AUTORETRACT) { // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves if (fwretract.autoretract_enabled && parser.seen_test('E') - && !parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)) + && !parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K)) ) { const float echange = destination.e - current_position.e; // Is this a retract or recover move? diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 747ddd64de19a..f3d7b7c8dca21 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/Marlin/src/gcode/motion/M290.cpp @@ -87,7 +87,7 @@ void GcodeSuite::M290() { } #endif - if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)) || parser.seen('R')) { + if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K)) || parser.seen('R')) { SERIAL_ECHO_START(); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp index be3a244380180..228bc5f96b47e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp @@ -41,13 +41,13 @@ void MaxAccelerationScreen::onRedraw(draw_mode_t what) { w.color(e_axis).adjuster( 8, GET_TEXT_F(MSG_AMAX_E), getAxisMaxAcceleration_mm_s2(E0) ); #elif DISTINCT_E > 1 w.heading(GET_TEXT_F(MSG_AMAX_E)); - w.color(e_axis).adjuster( 8, F(LCD_STR_E0), getAxisMaxAcceleration_mm_s2(E0) ); - w.color(e_axis).adjuster(10, F(LCD_STR_E1), getAxisMaxAcceleration_mm_s2(E1) ); + w.color(e_axis).adjuster( 8, F(STR_E0), getAxisMaxAcceleration_mm_s2(E0) ); + w.color(e_axis).adjuster(10, F(STR_E1), getAxisMaxAcceleration_mm_s2(E1) ); #if DISTINCT_E > 2 - w.color(e_axis).adjuster(12, F(LCD_STR_E2), getAxisMaxAcceleration_mm_s2(E2) ); + w.color(e_axis).adjuster(12, F(STR_E2), getAxisMaxAcceleration_mm_s2(E2) ); #endif #if DISTINCT_E > 3 - w.color(e_axis).adjuster(14, F(LCD_STR_E3), getAxisMaxAcceleration_mm_s2(E3) ); + w.color(e_axis).adjuster(14, F(STR_E3), getAxisMaxAcceleration_mm_s2(E3) ); #endif #endif w.increments(); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp index bca533c94f195..65dc947b7b485 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp @@ -42,13 +42,13 @@ void MaxVelocityScreen::onRedraw(draw_mode_t what) { w.color(e_axis) .adjuster( 8, GET_TEXT_F(MSG_VMAX_E), getAxisMaxFeedrate_mm_s(E0) ); #elif HAS_MULTI_EXTRUDER w.heading(GET_TEXT_F(MSG_VMAX_E)); - w.color(e_axis) .adjuster( 8, F(LCD_STR_E0), getAxisMaxFeedrate_mm_s(E0) ); - w.color(e_axis) .adjuster( 10, F(LCD_STR_E1), getAxisMaxFeedrate_mm_s(E1) ); + w.color(e_axis) .adjuster( 8, F(STR_E0), getAxisMaxFeedrate_mm_s(E0) ); + w.color(e_axis) .adjuster( 10, F(STR_E1), getAxisMaxFeedrate_mm_s(E1) ); #if EXTRUDERS > 2 - w.color(e_axis).adjuster( 12, F(LCD_STR_E2), getAxisMaxFeedrate_mm_s(E2) ); + w.color(e_axis).adjuster( 12, F(STR_E2), getAxisMaxFeedrate_mm_s(E2) ); #endif #if EXTRUDERS > 3 - w.color(e_axis).adjuster( 14, F(LCD_STR_E3), getAxisMaxFeedrate_mm_s(E3) ); + w.color(e_axis).adjuster( 14, F(STR_E3), getAxisMaxFeedrate_mm_s(E3) ); #endif #endif w.increments(); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.cpp index ee53a82bee181..2dbf2d9f06a7e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/temperature_screen.cpp @@ -50,13 +50,13 @@ void TemperatureScreen::onRedraw(draw_mode_t what) { #elif HOTENDS == 1 w.adjuster( 2, GET_TEXT_F(MSG_NOZZLE), getTargetTemp_celsius(E0)); #else - w.adjuster( 2, F(LCD_STR_E0), getTargetTemp_celsius(E0)); - w.adjuster( 4, F(LCD_STR_E1), getTargetTemp_celsius(E1)); + w.adjuster( 2, F(STR_E0), getTargetTemp_celsius(E0)); + w.adjuster( 4, F(STR_E1), getTargetTemp_celsius(E1)); #if HOTENDS > 2 - w.adjuster( 6, F(LCD_STR_E2), getTargetTemp_celsius(E2)); + w.adjuster( 6, F(STR_E2), getTargetTemp_celsius(E2)); #endif #if HOTENDS > 3 - w.adjuster( 8, F(LCD_STR_E3), getTargetTemp_celsius(E3)); + w.adjuster( 8, F(STR_E3), getTargetTemp_celsius(E3)); #endif #endif #endif diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index 02d4455331d04..1ebe138687173 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -107,23 +107,23 @@ namespace Language_an { LSTR MSG_ACC = _UxGT("Aceleracion"); LSTR MSG_VTRAV_MIN = _UxGT("Vel. viache min"); LSTR MSG_ACCELERATION = _UxGT("Accel"); - LSTR MSG_AMAX_A = _UxGT("Acel. max ") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("Acel. max ") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Acel. max ") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Acel. max ") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("Acel. max ") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Acel. max ") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Acel. max ") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Acel. max ") STR_A; + LSTR MSG_AMAX_B = _UxGT("Acel. max ") STR_B; + LSTR MSG_AMAX_C = _UxGT("Acel. max ") STR_C; + LSTR MSG_AMAX_I = _UxGT("Acel. max ") STR_I; + LSTR MSG_AMAX_J = _UxGT("Acel. max ") STR_J; + LSTR MSG_AMAX_K = _UxGT("Acel. max ") STR_K; + LSTR MSG_AMAX_E = _UxGT("Acel. max ") STR_E; LSTR MSG_AMAX_EN = _UxGT("Acel. max *"); LSTR MSG_A_RETRACT = _UxGT("Acel. retrac."); LSTR MSG_A_TRAVEL = _UxGT("Acel. Viaje"); LSTR MSG_STEPS_PER_MM = _UxGT("Trangos/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" trangos/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" trangos/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" trangos/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" trangos/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" trangos/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" trangos/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" trangos/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" trangos/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" trangos/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" trangos/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" trangos/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" trangos/mm"); LSTR MSG_E_STEPS = _UxGT("E trangos/mm"); LSTR MSG_EN_STEPS = _UxGT("* trangos/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); diff --git a/Marlin/src/lcd/language/language_bg.h b/Marlin/src/lcd/language/language_bg.h index 05209f7718089..3137228c2d290 100644 --- a/Marlin/src/lcd/language/language_bg.h +++ b/Marlin/src/lcd/language/language_bg.h @@ -99,12 +99,12 @@ namespace Language_bg { LSTR MSG_A_RETRACT = _UxGT("A-откат"); LSTR MSG_A_TRAVEL = _UxGT("A-travel"); LSTR MSG_STEPS_PER_MM = _UxGT("Стъпки/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" стъпки/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" стъпки/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" стъпки/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" стъпки/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" стъпки/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" стъпки/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" стъпки/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" стъпки/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" стъпки/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" стъпки/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" стъпки/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" стъпки/mm"); LSTR MSG_E_STEPS = _UxGT("E стъпки/mm"); LSTR MSG_EN_STEPS = _UxGT("* стъпки/mm"); LSTR MSG_TEMPERATURE = _UxGT("Температура"); diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index d70e6051b5db6..0e16c1a1fa470 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -105,12 +105,12 @@ namespace Language_ca { LSTR MSG_A_RETRACT = _UxGT("Accel. retracc"); LSTR MSG_A_TRAVEL = _UxGT("Accel. Viatge"); LSTR MSG_STEPS_PER_MM = _UxGT("Passos/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" passos/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" passos/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" passos/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" passos/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" passos/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" passos/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" passos/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" passos/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" passos/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" passos/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" passos/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" passos/mm"); LSTR MSG_E_STEPS = _UxGT("Epassos/mm"); LSTR MSG_EN_STEPS = _UxGT("*passos/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index 20c8686a24870..6f5d8445af828 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -267,43 +267,43 @@ namespace Language_cz { LSTR MSG_SELECT_E = _UxGT("Vybrat *"); LSTR MSG_ACC = _UxGT("Zrychl"); LSTR MSG_JERK = _UxGT("Jerk"); - LSTR MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); - LSTR MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); - LSTR MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); - LSTR MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); - LSTR MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); - LSTR MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + LSTR MSG_VA_JERK = _UxGT("Max ") STR_A _UxGT(" Jerk"); + LSTR MSG_VB_JERK = _UxGT("Max ") STR_B _UxGT(" Jerk"); + LSTR MSG_VC_JERK = _UxGT("Max ") STR_C _UxGT(" Jerk"); + LSTR MSG_VI_JERK = _UxGT("Max ") STR_I _UxGT(" Jerk"); + LSTR MSG_VJ_JERK = _UxGT("Max ") STR_J _UxGT(" Jerk"); + LSTR MSG_VK_JERK = _UxGT("Max ") STR_K _UxGT(" Jerk"); LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Odchylka spoje"); LSTR MSG_VELOCITY = _UxGT("Rychlost"); - LSTR MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Rychlost"); - LSTR MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Rychlost"); - LSTR MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Rychlost"); - LSTR MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Rychlost"); - LSTR MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Rychlost"); - LSTR MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Rychlost"); - LSTR MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Rychlost"); + LSTR MSG_VMAX_A = _UxGT("Max ") STR_A _UxGT(" Rychlost"); + LSTR MSG_VMAX_B = _UxGT("Max ") STR_B _UxGT(" Rychlost"); + LSTR MSG_VMAX_C = _UxGT("Max ") STR_C _UxGT(" Rychlost"); + LSTR MSG_VMAX_I = _UxGT("Max ") STR_I _UxGT(" Rychlost"); + LSTR MSG_VMAX_J = _UxGT("Max ") STR_J _UxGT(" Rychlost"); + LSTR MSG_VMAX_K = _UxGT("Max ") STR_K _UxGT(" Rychlost"); + LSTR MSG_VMAX_E = _UxGT("Max ") STR_E _UxGT(" Rychlost"); LSTR MSG_VMAX_EN = _UxGT("Max * Rychlost"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("VTrav Min"); LSTR MSG_ACCELERATION = _UxGT("Akcelerace"); - LSTR MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Akcel"); - LSTR MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Akcel"); - LSTR MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Akcel"); - LSTR MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Akcel"); - LSTR MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Akcel"); - LSTR MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Akcel"); - LSTR MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Akcel"); + LSTR MSG_AMAX_A = _UxGT("Max ") STR_A _UxGT(" Akcel"); + LSTR MSG_AMAX_B = _UxGT("Max ") STR_B _UxGT(" Akcel"); + LSTR MSG_AMAX_C = _UxGT("Max ") STR_C _UxGT(" Akcel"); + LSTR MSG_AMAX_I = _UxGT("Max ") STR_I _UxGT(" Akcel"); + LSTR MSG_AMAX_J = _UxGT("Max ") STR_J _UxGT(" Akcel"); + LSTR MSG_AMAX_K = _UxGT("Max ") STR_K _UxGT(" Akcel"); + LSTR MSG_AMAX_E = _UxGT("Max ") STR_E _UxGT(" Akcel"); LSTR MSG_AMAX_EN = _UxGT("Max * Akcel"); LSTR MSG_A_RETRACT = _UxGT("A-retrakt"); LSTR MSG_A_TRAVEL = _UxGT("A-přejezd"); LSTR MSG_STEPS_PER_MM = _UxGT("Kroků/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" kroků/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" kroků/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" kroků/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" kroků/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" kroků/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" kroků/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" kroků/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" kroků/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" kroků/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" kroků/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" kroků/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" kroků/mm"); LSTR MSG_E_STEPS = _UxGT("E kroků/mm"); LSTR MSG_EN_STEPS = _UxGT("* kroků/mm"); LSTR MSG_TEMPERATURE = _UxGT("Teplota"); @@ -483,12 +483,12 @@ namespace Language_cz { LSTR MSG_INFO_MAX_TEMP = _UxGT("Teplota max"); LSTR MSG_INFO_PSU = _UxGT("Nap. zdroj"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Buzení motorů"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Motor %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Motor %"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC uložit EEPROM"); LSTR MSG_ERROR_TMC = _UxGT("TMC CHYBA SPOJENÍ"); diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index b3644a754c4d8..b022720b5cae5 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -173,12 +173,12 @@ namespace Language_da { LSTR MSG_INFO_PSU = _UxGT("Strømfors."); LSTR MSG_DRIVE_STRENGTH = _UxGT("Driv Styrke"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driv %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driv %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driv %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driv %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driv %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driv %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driv %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driv %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driv %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driv %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driv %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driv %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Driv %"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Skriv"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 5ac0f1487b201..6a5f504e911d9 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -269,47 +269,47 @@ namespace Language_de { LSTR MSG_SELECT_E = _UxGT("Auswählen *"); LSTR MSG_ACC = _UxGT("Beschleunigung"); LSTR MSG_JERK = _UxGT("Jerk"); - LSTR MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); - LSTR MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); - LSTR MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); - LSTR MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); - LSTR MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); - LSTR MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + LSTR MSG_VA_JERK = _UxGT("Max ") STR_A _UxGT(" Jerk"); + LSTR MSG_VB_JERK = _UxGT("Max ") STR_B _UxGT(" Jerk"); + LSTR MSG_VC_JERK = _UxGT("Max ") STR_C _UxGT(" Jerk"); + LSTR MSG_VI_JERK = _UxGT("Max ") STR_I _UxGT(" Jerk"); + LSTR MSG_VJ_JERK = _UxGT("Max ") STR_J _UxGT(" Jerk"); + LSTR MSG_VK_JERK = _UxGT("Max ") STR_K _UxGT(" Jerk"); LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); LSTR MSG_VELOCITY = _UxGT("Geschwindigkeit"); - LSTR MSG_VMAX_A = _UxGT("V max ") LCD_STR_A; - LSTR MSG_VMAX_B = _UxGT("V max ") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("V max ") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("V max ") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("V max ") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("V max ") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("V max ") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("V max ") STR_A; + LSTR MSG_VMAX_B = _UxGT("V max ") STR_B; + LSTR MSG_VMAX_C = _UxGT("V max ") STR_C; + LSTR MSG_VMAX_I = _UxGT("V max ") STR_I; + LSTR MSG_VMAX_J = _UxGT("V max ") STR_J; + LSTR MSG_VMAX_K = _UxGT("V max ") STR_K; + LSTR MSG_VMAX_E = _UxGT("V max ") STR_E; LSTR MSG_VMAX_EN = _UxGT("V max *"); LSTR MSG_VMIN = _UxGT("V min "); LSTR MSG_VTRAV_MIN = _UxGT("V min Leerfahrt"); LSTR MSG_ACCELERATION = _UxGT("Beschleunigung"); LSTR MSG_AMAX = _UxGT("A max "); // space intentional - LSTR MSG_AMAX_A = _UxGT("A max ") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("A max ") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("A max ") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("A max ") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("A max ") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("A max ") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("A max ") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("A max ") STR_A; + LSTR MSG_AMAX_B = _UxGT("A max ") STR_B; + LSTR MSG_AMAX_C = _UxGT("A max ") STR_C; + LSTR MSG_AMAX_I = _UxGT("A max ") STR_I; + LSTR MSG_AMAX_J = _UxGT("A max ") STR_J; + LSTR MSG_AMAX_K = _UxGT("A max ") STR_K; + LSTR MSG_AMAX_E = _UxGT("A max ") STR_E; LSTR MSG_AMAX_EN = _UxGT("A max *"); LSTR MSG_A_RETRACT = _UxGT("A Einzug"); LSTR MSG_A_TRAVEL = _UxGT("A Leerfahrt"); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("max. Frequenz"); LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("min. Vorschub"); LSTR MSG_STEPS_PER_MM = _UxGT("Steps/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" Steps/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" Steps/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" Steps/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" Steps/mm"); - LSTR MSG_E_STEPS = LCD_STR_E _UxGT(" Steps/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" Steps/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" Steps/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" Steps/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" Steps/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" Steps/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" Steps/mm"); + LSTR MSG_E_STEPS = STR_E _UxGT(" Steps/mm"); LSTR MSG_EN_STEPS = _UxGT("* Steps/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatur"); LSTR MSG_MOTION = _UxGT("Bewegung"); @@ -509,12 +509,12 @@ namespace Language_de { LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); LSTR MSG_INFO_PSU = _UxGT("Netzteil"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Motorleistung"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Treiber %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Treiber %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Treiber %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Treiber %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Treiber %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Treiber %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Treiber %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Treiber %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Treiber %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Treiber %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Treiber %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Treiber %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Treiber %"); LSTR MSG_ERROR_TMC = _UxGT("TMC Verbindungsfehler"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Werte speichern"); diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index 265e02c0ef0aa..f3cd7ef278983 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -117,41 +117,41 @@ namespace Language_el { LSTR MSG_LCD_ON = _UxGT("Ενεργοποιημένο"); LSTR MSG_LCD_OFF = _UxGT("Απενεργοποιημένο"); LSTR MSG_ACC = _UxGT("Επιτάχυνση"); - LSTR MSG_VA_JERK = _UxGT("Vαντίδραση ") LCD_STR_A; - LSTR MSG_VB_JERK = _UxGT("Vαντίδραση ") LCD_STR_B; - LSTR MSG_VC_JERK = _UxGT("Vαντίδραση ") LCD_STR_C; - LSTR MSG_VI_JERK = _UxGT("Vαντίδραση ") LCD_STR_I; - LSTR MSG_VJ_JERK = _UxGT("Vαντίδραση ") LCD_STR_J; - LSTR MSG_VK_JERK = _UxGT("Vαντίδραση ") LCD_STR_K; + LSTR MSG_VA_JERK = _UxGT("Vαντίδραση ") STR_A; + LSTR MSG_VB_JERK = _UxGT("Vαντίδραση ") STR_B; + LSTR MSG_VC_JERK = _UxGT("Vαντίδραση ") STR_C; + LSTR MSG_VI_JERK = _UxGT("Vαντίδραση ") STR_I; + LSTR MSG_VJ_JERK = _UxGT("Vαντίδραση ") STR_J; + LSTR MSG_VK_JERK = _UxGT("Vαντίδραση ") STR_K; LSTR MSG_VE_JERK = _UxGT("Vαντίδραση E"); - LSTR MSG_VMAX_A = _UxGT("V Μέγιστο") LCD_STR_A; - LSTR MSG_VMAX_B = _UxGT("V Μέγιστο") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("V Μέγιστο") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("V Μέγιστο") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("V Μέγιστο") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("V Μέγιστο") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("V Μέγιστο") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("V Μέγιστο") STR_A; + LSTR MSG_VMAX_B = _UxGT("V Μέγιστο") STR_B; + LSTR MSG_VMAX_C = _UxGT("V Μέγιστο") STR_C; + LSTR MSG_VMAX_I = _UxGT("V Μέγιστο") STR_I; + LSTR MSG_VMAX_J = _UxGT("V Μέγιστο") STR_J; + LSTR MSG_VMAX_K = _UxGT("V Μέγιστο") STR_K; + LSTR MSG_VMAX_E = _UxGT("V Μέγιστο") STR_E; LSTR MSG_VMAX_EN = _UxGT("V Μέγιστο *"); LSTR MSG_VMIN = _UxGT("V Ελάχιστο"); LSTR MSG_VTRAV_MIN = _UxGT("Vελάχ. μετατόπιση"); LSTR MSG_ACCELERATION = _UxGT("Accel"); - LSTR MSG_AMAX_A = _UxGT("Aμεγ ") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("Aμεγ ") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Aμεγ ") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Aμεγ ") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("Aμεγ ") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Aμεγ ") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Aμεγ ") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Aμεγ ") STR_A; + LSTR MSG_AMAX_B = _UxGT("Aμεγ ") STR_B; + LSTR MSG_AMAX_C = _UxGT("Aμεγ ") STR_C; + LSTR MSG_AMAX_I = _UxGT("Aμεγ ") STR_I; + LSTR MSG_AMAX_J = _UxGT("Aμεγ ") STR_J; + LSTR MSG_AMAX_K = _UxGT("Aμεγ ") STR_K; + LSTR MSG_AMAX_E = _UxGT("Aμεγ ") STR_E; LSTR MSG_AMAX_EN = _UxGT("Aμεγ *"); LSTR MSG_A_RETRACT = _UxGT("Α-ανάσυρση"); LSTR MSG_A_TRAVEL = _UxGT("Α-μετατόπιση"); LSTR MSG_STEPS_PER_MM = _UxGT("Bήματα ανά μμ"); - LSTR MSG_A_STEPS = _UxGT("Bήματα ") LCD_STR_A _UxGT(" ανά μμ"); - LSTR MSG_B_STEPS = _UxGT("Bήματα ") LCD_STR_B _UxGT(" ανά μμ"); - LSTR MSG_C_STEPS = _UxGT("Bήματα ") LCD_STR_C _UxGT(" ανά μμ"); - LSTR MSG_I_STEPS = _UxGT("Bήματα ") LCD_STR_I _UxGT(" ανά μμ"); - LSTR MSG_J_STEPS = _UxGT("Bήματα ") LCD_STR_J _UxGT(" ανά μμ"); - LSTR MSG_K_STEPS = _UxGT("Bήματα ") LCD_STR_K _UxGT(" ανά μμ"); + LSTR MSG_A_STEPS = _UxGT("Bήματα ") STR_A _UxGT(" ανά μμ"); + LSTR MSG_B_STEPS = _UxGT("Bήματα ") STR_B _UxGT(" ανά μμ"); + LSTR MSG_C_STEPS = _UxGT("Bήματα ") STR_C _UxGT(" ανά μμ"); + LSTR MSG_I_STEPS = _UxGT("Bήματα ") STR_I _UxGT(" ανά μμ"); + LSTR MSG_J_STEPS = _UxGT("Bήματα ") STR_J _UxGT(" ανά μμ"); + LSTR MSG_K_STEPS = _UxGT("Bήματα ") STR_K _UxGT(" ανά μμ"); LSTR MSG_E_STEPS = _UxGT("Bήματα Ε ανά μμ"); LSTR MSG_EN_STEPS = _UxGT("Bήματα * ανά μμ"); LSTR MSG_TEMPERATURE = _UxGT("Θερμοκρασία"); diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index 53e3ee3b948bd..d8c7cae38d684 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -107,41 +107,41 @@ namespace Language_el_gr { LSTR MSG_LCD_OFF = _UxGT("Απενεργοποιημένο"); LSTR MSG_ACC = _UxGT("Επιτάχυνση"); LSTR MSG_JERK = _UxGT("Vαντίδραση"); - LSTR MSG_VA_JERK = _UxGT("Vαντίδραση ") LCD_STR_A; - LSTR MSG_VB_JERK = _UxGT("Vαντίδραση ") LCD_STR_B; - LSTR MSG_VC_JERK = _UxGT("Vαντίδραση ") LCD_STR_C; - LSTR MSG_VI_JERK = _UxGT("Vαντίδραση ") LCD_STR_I; - LSTR MSG_VJ_JERK = _UxGT("Vαντίδραση ") LCD_STR_J; - LSTR MSG_VK_JERK = _UxGT("Vαντίδραση ") LCD_STR_K; + LSTR MSG_VA_JERK = _UxGT("Vαντίδραση ") STR_A; + LSTR MSG_VB_JERK = _UxGT("Vαντίδραση ") STR_B; + LSTR MSG_VC_JERK = _UxGT("Vαντίδραση ") STR_C; + LSTR MSG_VI_JERK = _UxGT("Vαντίδραση ") STR_I; + LSTR MSG_VJ_JERK = _UxGT("Vαντίδραση ") STR_J; + LSTR MSG_VK_JERK = _UxGT("Vαντίδραση ") STR_K; LSTR MSG_VE_JERK = _UxGT("Vαντίδραση E"); - LSTR MSG_VMAX_A = _UxGT("Vμεγ ") LCD_STR_A; - LSTR MSG_VMAX_B = _UxGT("Vμεγ ") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("Vμεγ ") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("Vμεγ ") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("Vμεγ ") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("Vμεγ ") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("Vμεγ ") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("Vμεγ ") STR_A; + LSTR MSG_VMAX_B = _UxGT("Vμεγ ") STR_B; + LSTR MSG_VMAX_C = _UxGT("Vμεγ ") STR_C; + LSTR MSG_VMAX_I = _UxGT("Vμεγ ") STR_I; + LSTR MSG_VMAX_J = _UxGT("Vμεγ ") STR_J; + LSTR MSG_VMAX_K = _UxGT("Vμεγ ") STR_K; + LSTR MSG_VMAX_E = _UxGT("Vμεγ ") STR_E; LSTR MSG_VMAX_EN = _UxGT("Vμεγ *"); LSTR MSG_VMIN = _UxGT("Vελαχ"); LSTR MSG_VTRAV_MIN = _UxGT("Vελάχ. μετατόπιση"); LSTR MSG_ACCELERATION = _UxGT("Accel"); - LSTR MSG_AMAX_A = _UxGT("Aμεγ ") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("Aμεγ ") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Aμεγ ") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Aμεγ ") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("Aμεγ ") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Aμεγ ") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Aμεγ ") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Aμεγ ") STR_A; + LSTR MSG_AMAX_B = _UxGT("Aμεγ ") STR_B; + LSTR MSG_AMAX_C = _UxGT("Aμεγ ") STR_C; + LSTR MSG_AMAX_I = _UxGT("Aμεγ ") STR_I; + LSTR MSG_AMAX_J = _UxGT("Aμεγ ") STR_J; + LSTR MSG_AMAX_K = _UxGT("Aμεγ ") STR_K; + LSTR MSG_AMAX_E = _UxGT("Aμεγ ") STR_E; LSTR MSG_AMAX_EN = _UxGT("Aμεγ *"); LSTR MSG_A_RETRACT = _UxGT("Α-ανάσυρση"); LSTR MSG_A_TRAVEL = _UxGT("Α-μετατόπιση"); LSTR MSG_STEPS_PER_MM = _UxGT("Bήματα ανά μμ"); - LSTR MSG_A_STEPS = _UxGT("Bήματα ") LCD_STR_A _UxGT(" ανά μμ"); - LSTR MSG_B_STEPS = _UxGT("Bήματα ") LCD_STR_B _UxGT(" ανά μμ"); - LSTR MSG_C_STEPS = _UxGT("Bήματα ") LCD_STR_C _UxGT(" ανά μμ"); - LSTR MSG_I_STEPS = _UxGT("Bήματα ") LCD_STR_I _UxGT(" ανά μμ"); - LSTR MSG_J_STEPS = _UxGT("Bήματα ") LCD_STR_J _UxGT(" ανά μμ"); - LSTR MSG_K_STEPS = _UxGT("Bήματα ") LCD_STR_K _UxGT(" ανά μμ"); + LSTR MSG_A_STEPS = _UxGT("Bήματα ") STR_A _UxGT(" ανά μμ"); + LSTR MSG_B_STEPS = _UxGT("Bήματα ") STR_B _UxGT(" ανά μμ"); + LSTR MSG_C_STEPS = _UxGT("Bήματα ") STR_C _UxGT(" ανά μμ"); + LSTR MSG_I_STEPS = _UxGT("Bήματα ") STR_I _UxGT(" ανά μμ"); + LSTR MSG_J_STEPS = _UxGT("Bήματα ") STR_J _UxGT(" ανά μμ"); + LSTR MSG_K_STEPS = _UxGT("Bήματα ") STR_K _UxGT(" ανά μμ"); LSTR MSG_E_STEPS = _UxGT("Bήματα Ε ανά μμ"); LSTR MSG_EN_STEPS = _UxGT("Bήματα * ανά μμ"); LSTR MSG_TEMPERATURE = _UxGT("Θερμοκρασία"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 08370d3a2fb55..12430ed4c0af8 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -100,9 +100,9 @@ namespace Language_en { LSTR MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Home Offset ") LCD_STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Home Offset ") LCD_STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Home Offset ") LCD_STR_K; + LSTR MSG_HOME_OFFSET_I = _UxGT("Home Offset ") STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Home Offset ") STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Home Offset ") STR_K; LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets Applied"); LSTR MSG_SET_ORIGIN = _UxGT("Set Origin"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); @@ -284,9 +284,9 @@ namespace Language_en { LSTR MSG_MOVE_X = _UxGT("Move X"); // Used by draw_edit_screen LSTR MSG_MOVE_Y = _UxGT("Move Y"); LSTR MSG_MOVE_Z = _UxGT("Move Z"); - LSTR MSG_MOVE_I = _UxGT("Move ") LCD_STR_I; - LSTR MSG_MOVE_J = _UxGT("Move ") LCD_STR_J; - LSTR MSG_MOVE_K = _UxGT("Move ") LCD_STR_K; + LSTR MSG_MOVE_I = _UxGT("Move ") STR_I; + LSTR MSG_MOVE_J = _UxGT("Move ") STR_J; + LSTR MSG_MOVE_K = _UxGT("Move ") STR_K; LSTR MSG_MOVE_E = _UxGT("Move Extruder"); LSTR MSG_MOVE_EN = _UxGT("Move E*"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend too cold"); @@ -301,10 +301,10 @@ namespace Language_en { LSTR MSG_MOVE_1IN = _UxGT("Move 1.0in"); LSTR MSG_SPEED = _UxGT("Speed"); LSTR MSG_MAXSPEED = _UxGT("Max Speed (mm/s)"); - LSTR MSG_MAXSPEED_X = _UxGT("Max ") LCD_STR_A _UxGT(" Speed"); - LSTR MSG_MAXSPEED_Y = _UxGT("Max ") LCD_STR_B _UxGT(" Speed"); - LSTR MSG_MAXSPEED_Z = _UxGT("Max ") LCD_STR_C _UxGT(" Speed"); - LSTR MSG_MAXSPEED_E = _UxGT("Max ") LCD_STR_E _UxGT(" Speed"); + LSTR MSG_MAXSPEED_X = _UxGT("Max ") STR_A _UxGT(" Speed"); + LSTR MSG_MAXSPEED_Y = _UxGT("Max ") STR_B _UxGT(" Speed"); + LSTR MSG_MAXSPEED_Z = _UxGT("Max ") STR_C _UxGT(" Speed"); + LSTR MSG_MAXSPEED_E = _UxGT("Max ") STR_E _UxGT(" Speed"); LSTR MSG_MAXSPEED_A = _UxGT("Max @ Speed"); LSTR MSG_BED_Z = _UxGT("Bed Z"); LSTR MSG_NOZZLE = _UxGT("Nozzle"); @@ -347,45 +347,45 @@ namespace Language_en { LSTR MSG_SELECT_E = _UxGT("Select *"); LSTR MSG_ACC = _UxGT("Accel"); LSTR MSG_JERK = _UxGT("Jerk"); - LSTR MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); - LSTR MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); - LSTR MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); - LSTR MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); - LSTR MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); - LSTR MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + LSTR MSG_VA_JERK = _UxGT("Max ") STR_A _UxGT(" Jerk"); + LSTR MSG_VB_JERK = _UxGT("Max ") STR_B _UxGT(" Jerk"); + LSTR MSG_VC_JERK = _UxGT("Max ") STR_C _UxGT(" Jerk"); + LSTR MSG_VI_JERK = _UxGT("Max ") STR_I _UxGT(" Jerk"); + LSTR MSG_VJ_JERK = _UxGT("Max ") STR_J _UxGT(" Jerk"); + LSTR MSG_VK_JERK = _UxGT("Max ") STR_K _UxGT(" Jerk"); LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); LSTR MSG_VELOCITY = _UxGT("Velocity"); - LSTR MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Vel"); - LSTR MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Vel"); - LSTR MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Vel"); - LSTR MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Vel"); - LSTR MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Vel"); - LSTR MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Vel"); - LSTR MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Vel"); + LSTR MSG_VMAX_A = _UxGT("Max ") STR_A _UxGT(" Vel"); + LSTR MSG_VMAX_B = _UxGT("Max ") STR_B _UxGT(" Vel"); + LSTR MSG_VMAX_C = _UxGT("Max ") STR_C _UxGT(" Vel"); + LSTR MSG_VMAX_I = _UxGT("Max ") STR_I _UxGT(" Vel"); + LSTR MSG_VMAX_J = _UxGT("Max ") STR_J _UxGT(" Vel"); + LSTR MSG_VMAX_K = _UxGT("Max ") STR_K _UxGT(" Vel"); + LSTR MSG_VMAX_E = _UxGT("Max ") STR_E _UxGT(" Vel"); LSTR MSG_VMAX_EN = _UxGT("Max * Vel"); LSTR MSG_VMIN = _UxGT("Min Velocity"); LSTR MSG_VTRAV_MIN = _UxGT("Min Travel Vel"); LSTR MSG_ACCELERATION = _UxGT("Acceleration"); - LSTR MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Accel"); - LSTR MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Accel"); - LSTR MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Accel"); - LSTR MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Accel"); - LSTR MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Accel"); - LSTR MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Accel"); - LSTR MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Accel"); + LSTR MSG_AMAX_A = _UxGT("Max ") STR_A _UxGT(" Accel"); + LSTR MSG_AMAX_B = _UxGT("Max ") STR_B _UxGT(" Accel"); + LSTR MSG_AMAX_C = _UxGT("Max ") STR_C _UxGT(" Accel"); + LSTR MSG_AMAX_I = _UxGT("Max ") STR_I _UxGT(" Accel"); + LSTR MSG_AMAX_J = _UxGT("Max ") STR_J _UxGT(" Accel"); + LSTR MSG_AMAX_K = _UxGT("Max ") STR_K _UxGT(" Accel"); + LSTR MSG_AMAX_E = _UxGT("Max ") STR_E _UxGT(" Accel"); LSTR MSG_AMAX_EN = _UxGT("Max * Accel"); LSTR MSG_A_RETRACT = _UxGT("Retract Accel"); LSTR MSG_A_TRAVEL = _UxGT("Travel Accel"); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("XY Freq Limit"); LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min FR Factor"); LSTR MSG_STEPS_PER_MM = _UxGT("Steps/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" Steps/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" Steps/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" Steps/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" Steps/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" Steps/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" Steps/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" Steps/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" Steps/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" Steps/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" Steps/mm"); LSTR MSG_E_STEPS = _UxGT("E steps/mm"); LSTR MSG_EN_STEPS = _UxGT("* Steps/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperature"); @@ -530,9 +530,9 @@ namespace Language_en { LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; + LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") STR_K; LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Endstop Abort"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Heating Failed"); @@ -627,12 +627,12 @@ namespace Language_en { LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); LSTR MSG_INFO_PSU = _UxGT("PSU"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Drive Strength"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driver %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); LSTR MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); @@ -802,12 +802,12 @@ namespace Language_en { LSTR MSG_PID_C_E = _UxGT("PID-C *"); LSTR MSG_PID_F = _UxGT("PID-F"); LSTR MSG_PID_F_E = _UxGT("PID-F *"); - LSTR MSG_BACKLASH_A = LCD_STR_A; - LSTR MSG_BACKLASH_B = LCD_STR_B; - LSTR MSG_BACKLASH_C = LCD_STR_C; - LSTR MSG_BACKLASH_I = LCD_STR_I; - LSTR MSG_BACKLASH_J = LCD_STR_J; - LSTR MSG_BACKLASH_K = LCD_STR_K; + LSTR MSG_BACKLASH_A = STR_A; + LSTR MSG_BACKLASH_B = STR_B; + LSTR MSG_BACKLASH_C = STR_C; + LSTR MSG_BACKLASH_I = STR_I; + LSTR MSG_BACKLASH_J = STR_J; + LSTR MSG_BACKLASH_K = STR_K; } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 1dbc7faf70006..6e2c82533e6fb 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -268,43 +268,43 @@ namespace Language_es { LSTR MSG_SELECT_E = _UxGT("Seleccionar *"); LSTR MSG_ACC = _UxGT("Aceleración"); LSTR MSG_JERK = _UxGT("Jerk"); - LSTR MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); - LSTR MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); - LSTR MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); - LSTR MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); - LSTR MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); - LSTR MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + LSTR MSG_VA_JERK = _UxGT("Max ") STR_A _UxGT(" Jerk"); + LSTR MSG_VB_JERK = _UxGT("Max ") STR_B _UxGT(" Jerk"); + LSTR MSG_VC_JERK = _UxGT("Max ") STR_C _UxGT(" Jerk"); + LSTR MSG_VI_JERK = _UxGT("Max ") STR_I _UxGT(" Jerk"); + LSTR MSG_VJ_JERK = _UxGT("Max ") STR_J _UxGT(" Jerk"); + LSTR MSG_VK_JERK = _UxGT("Max ") STR_K _UxGT(" Jerk"); LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Desvi. Unión"); LSTR MSG_VELOCITY = _UxGT("Velocidad"); - LSTR MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Vel"); - LSTR MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Vel"); - LSTR MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Vel"); - LSTR MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Vel"); - LSTR MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Vel"); - LSTR MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Vel"); - LSTR MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Vel"); + LSTR MSG_VMAX_A = _UxGT("Max ") STR_A _UxGT(" Vel"); + LSTR MSG_VMAX_B = _UxGT("Max ") STR_B _UxGT(" Vel"); + LSTR MSG_VMAX_C = _UxGT("Max ") STR_C _UxGT(" Vel"); + LSTR MSG_VMAX_I = _UxGT("Max ") STR_I _UxGT(" Vel"); + LSTR MSG_VMAX_J = _UxGT("Max ") STR_J _UxGT(" Vel"); + LSTR MSG_VMAX_K = _UxGT("Max ") STR_K _UxGT(" Vel"); + LSTR MSG_VMAX_E = _UxGT("Max ") STR_E _UxGT(" Vel"); LSTR MSG_VMAX_EN = _UxGT("Max * Vel"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("Vel. viaje min"); LSTR MSG_ACCELERATION = _UxGT("Acceleración"); - LSTR MSG_AMAX_A = _UxGT("Acel. max") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("Acel. max") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Acel. max") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Acel. max") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("Acel. max") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Acel. max") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Acel. max") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Acel. max") STR_A; + LSTR MSG_AMAX_B = _UxGT("Acel. max") STR_B; + LSTR MSG_AMAX_C = _UxGT("Acel. max") STR_C; + LSTR MSG_AMAX_I = _UxGT("Acel. max") STR_I; + LSTR MSG_AMAX_J = _UxGT("Acel. max") STR_J; + LSTR MSG_AMAX_K = _UxGT("Acel. max") STR_K; + LSTR MSG_AMAX_E = _UxGT("Acel. max") STR_E; LSTR MSG_AMAX_EN = _UxGT("Acel. max *"); LSTR MSG_A_RETRACT = _UxGT("Acel. retrac."); LSTR MSG_A_TRAVEL = _UxGT("Acel. Viaje"); LSTR MSG_STEPS_PER_MM = _UxGT("Pasos/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" pasos/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" pasos/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" pasos/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" pasos/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" pasos/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" pasos/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" pasos/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" pasos/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" pasos/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" pasos/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" pasos/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" pasos/mm"); LSTR MSG_E_STEPS = _UxGT("E pasos/mm"); LSTR MSG_EN_STEPS = _UxGT("* pasos/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -481,12 +481,12 @@ namespace Language_es { LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp. Máxima"); LSTR MSG_INFO_PSU = _UxGT("F. Aliment."); LSTR MSG_DRIVE_STRENGTH = _UxGT("Fuerza de empuje"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driver %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); LSTR MSG_ERROR_TMC = _UxGT("ERROR CONEX. TMC"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Escribe DAC EEPROM"); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index ad6a4f3071761..5742fa8f6f974 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -164,23 +164,23 @@ namespace Language_eu { LSTR MSG_SELECT_E = _UxGT("Aukeratu *"); LSTR MSG_ACC = _UxGT("Azelerazioa"); LSTR MSG_JERK = _UxGT("Astindua"); - LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-astindua"); - LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-astindua"); - LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-astindua"); - LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-astindua"); - LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-astindua"); - LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-astindua"); + LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-astindua"); + LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-astindua"); + LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-astindua"); + LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-astindua"); + LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-astindua"); + LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-astindua"); LSTR MSG_VE_JERK = _UxGT("Ve-astindua"); LSTR MSG_VTRAV_MIN = _UxGT("VBidaia min"); LSTR MSG_A_RETRACT = _UxGT("A-retrakt"); LSTR MSG_A_TRAVEL = _UxGT("A-bidaia"); LSTR MSG_STEPS_PER_MM = _UxGT("Pausoak/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" pausoak/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" pausoak/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" pausoak/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" pausoak/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" pausoak/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" pausoak/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" pausoak/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" pausoak/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" pausoak/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" pausoak/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" pausoak/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" pausoak/mm"); LSTR MSG_E_STEPS = _UxGT("E pausoak/mm"); LSTR MSG_EN_STEPS = _UxGT("* pausoak/mm"); LSTR MSG_TEMPERATURE = _UxGT("Tenperatura"); @@ -297,12 +297,12 @@ namespace Language_eu { LSTR MSG_INFO_MAX_TEMP = _UxGT("Tenp. Maximoa"); LSTR MSG_INFO_PSU = _UxGT("Elikadura-iturria"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Driver-aren potentzia"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driver %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Idatzi DAC EEPROM"); LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("HARIZPIA ALDATU"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 41ab9ebaf15d7..6b2d56b1bfcde 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -72,9 +72,9 @@ namespace Language_fr { LSTR MSG_HOME_OFFSET_X = _UxGT("Décal. origine X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Décal. origine Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Décal. origine Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Décal. origine ") LCD_STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Décal. origine ") LCD_STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Décal. origine ") LCD_STR_K; + LSTR MSG_HOME_OFFSET_I = _UxGT("Décal. origine ") STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Décal. origine ") STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Décal. origine ") STR_K; LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Décalages appliqués"); LSTR MSG_SET_ORIGIN = _UxGT("Régler origine"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Assistant Molettes"); @@ -234,9 +234,9 @@ namespace Language_fr { LSTR MSG_MOVE_X = _UxGT("Déplacer X"); LSTR MSG_MOVE_Y = _UxGT("Déplacer Y"); LSTR MSG_MOVE_Z = _UxGT("Déplacer Z"); - LSTR MSG_MOVE_I = _UxGT("Déplacer ") LCD_STR_I; - LSTR MSG_MOVE_J = _UxGT("Déplacer ") LCD_STR_J; - LSTR MSG_MOVE_K = _UxGT("Déplacer ") LCD_STR_K; + LSTR MSG_MOVE_I = _UxGT("Déplacer ") STR_I; + LSTR MSG_MOVE_J = _UxGT("Déplacer ") STR_J; + LSTR MSG_MOVE_K = _UxGT("Déplacer ") STR_K; LSTR MSG_MOVE_E = _UxGT("Extruder"); LSTR MSG_MOVE_EN = _UxGT("Extruder *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Buse trop froide"); @@ -280,45 +280,45 @@ namespace Language_fr { LSTR MSG_SELECT_E = _UxGT("Sélectionner *"); LSTR MSG_ACC = _UxGT("Accélération"); LSTR MSG_JERK = _UxGT("Jerk"); - LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT(" jerk"); - LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT(" jerk"); - LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT(" jerk"); - LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT(" jerk"); - LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT(" jerk"); - LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT(" jerk"); + LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT(" jerk"); + LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT(" jerk"); + LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT(" jerk"); + LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT(" jerk"); + LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT(" jerk"); + LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT(" jerk"); LSTR MSG_VE_JERK = _UxGT("Ve jerk"); LSTR MSG_VELOCITY = _UxGT("Vélocité"); - LSTR MSG_VMAX_A = _UxGT("Vit. Max ") LCD_STR_A; - LSTR MSG_VMAX_B = _UxGT("Vit. Max ") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("Vit. Max ") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("Vit. Max ") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("Vit. Max ") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("Vit. Max ") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("Vit. Max ") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("Vit. Max ") STR_A; + LSTR MSG_VMAX_B = _UxGT("Vit. Max ") STR_B; + LSTR MSG_VMAX_C = _UxGT("Vit. Max ") STR_C; + LSTR MSG_VMAX_I = _UxGT("Vit. Max ") STR_I; + LSTR MSG_VMAX_J = _UxGT("Vit. Max ") STR_J; + LSTR MSG_VMAX_K = _UxGT("Vit. Max ") STR_K; + LSTR MSG_VMAX_E = _UxGT("Vit. Max ") STR_E; LSTR MSG_VMAX_EN = _UxGT("Vit. Max *"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Déviat. jonct."); LSTR MSG_VMIN = _UxGT("Vit. Min"); LSTR MSG_VTRAV_MIN = _UxGT("Vmin course"); LSTR MSG_ACCELERATION = _UxGT("Accélération"); - LSTR MSG_AMAX_A = _UxGT("Max Accél. ") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("Max Accél. ") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Max Accél. ") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Max Accél. ") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("Max Accél. ") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Max Accél. ") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Max Accél. ") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Max Accél. ") STR_A; + LSTR MSG_AMAX_B = _UxGT("Max Accél. ") STR_B; + LSTR MSG_AMAX_C = _UxGT("Max Accél. ") STR_C; + LSTR MSG_AMAX_I = _UxGT("Max Accél. ") STR_I; + LSTR MSG_AMAX_J = _UxGT("Max Accél. ") STR_J; + LSTR MSG_AMAX_K = _UxGT("Max Accél. ") STR_K; + LSTR MSG_AMAX_E = _UxGT("Max Accél. ") STR_E; LSTR MSG_AMAX_EN = _UxGT("Max Accél. *"); LSTR MSG_A_RETRACT = _UxGT("Acc.rétraction"); LSTR MSG_A_TRAVEL = _UxGT("Acc.course"); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Fréquence max"); LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Vitesse min"); LSTR MSG_STEPS_PER_MM = _UxGT("Pas/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" pas/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" pas/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" pas/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" pas/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" pas/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" pas/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" pas/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" pas/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" pas/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" pas/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" pas/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" pas/mm"); LSTR MSG_E_STEPS = _UxGT("E pas/mm"); LSTR MSG_EN_STEPS = _UxGT("* pas/mm"); LSTR MSG_TEMPERATURE = _UxGT("Température"); @@ -442,9 +442,9 @@ namespace Language_fr { LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; + LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") STR_K; LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Butée abandon"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Err de chauffe"); @@ -520,12 +520,12 @@ namespace Language_fr { LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp Max"); LSTR MSG_INFO_PSU = _UxGT("Alim."); LSTR MSG_DRIVE_STRENGTH = _UxGT("Puiss. moteur "); - LSTR MSG_DAC_PERCENT_A = _UxGT("Driver ") LCD_STR_A _UxGT(" %"); - LSTR MSG_DAC_PERCENT_B = _UxGT("Driver ") LCD_STR_B _UxGT(" %"); - LSTR MSG_DAC_PERCENT_C = _UxGT("Driver ") LCD_STR_C _UxGT(" %"); - LSTR MSG_DAC_PERCENT_I = _UxGT("Driver ") LCD_STR_I _UxGT(" %"); - LSTR MSG_DAC_PERCENT_J = _UxGT("Driver ") LCD_STR_J _UxGT(" %"); - LSTR MSG_DAC_PERCENT_K = _UxGT("Driver ") LCD_STR_K _UxGT(" %"); + LSTR MSG_DAC_PERCENT_A = _UxGT("Driver ") STR_A _UxGT(" %"); + LSTR MSG_DAC_PERCENT_B = _UxGT("Driver ") STR_B _UxGT(" %"); + LSTR MSG_DAC_PERCENT_C = _UxGT("Driver ") STR_C _UxGT(" %"); + LSTR MSG_DAC_PERCENT_I = _UxGT("Driver ") STR_I _UxGT(" %"); + LSTR MSG_DAC_PERCENT_J = _UxGT("Driver ") STR_J _UxGT(" %"); + LSTR MSG_DAC_PERCENT_K = _UxGT("Driver ") STR_K _UxGT(" %"); LSTR MSG_DAC_PERCENT_E = _UxGT("Driver E %"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM sauv."); LSTR MSG_ERROR_TMC = _UxGT("ERREUR CONNEXION TMC"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 3026e761c415e..731f89cad4ddb 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -269,45 +269,45 @@ namespace Language_gl { LSTR MSG_SELECT_E = _UxGT("Escolla *"); LSTR MSG_ACC = _UxGT("Acel"); LSTR MSG_JERK = _UxGT("Jerk"); - LSTR MSG_VA_JERK = _UxGT("Max ") LCD_STR_A _UxGT(" Jerk"); - LSTR MSG_VB_JERK = _UxGT("Max ") LCD_STR_B _UxGT(" Jerk"); - LSTR MSG_VC_JERK = _UxGT("Max ") LCD_STR_C _UxGT(" Jerk"); - LSTR MSG_VI_JERK = _UxGT("Max ") LCD_STR_I _UxGT(" Jerk"); - LSTR MSG_VJ_JERK = _UxGT("Max ") LCD_STR_J _UxGT(" Jerk"); - LSTR MSG_VK_JERK = _UxGT("Max ") LCD_STR_K _UxGT(" Jerk"); + LSTR MSG_VA_JERK = _UxGT("Max ") STR_A _UxGT(" Jerk"); + LSTR MSG_VB_JERK = _UxGT("Max ") STR_B _UxGT(" Jerk"); + LSTR MSG_VC_JERK = _UxGT("Max ") STR_C _UxGT(" Jerk"); + LSTR MSG_VI_JERK = _UxGT("Max ") STR_I _UxGT(" Jerk"); + LSTR MSG_VJ_JERK = _UxGT("Max ") STR_J _UxGT(" Jerk"); + LSTR MSG_VK_JERK = _UxGT("Max ") STR_K _UxGT(" Jerk"); LSTR MSG_VE_JERK = _UxGT("Max E Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Desvío Unión"); LSTR MSG_VELOCITY = _UxGT("Velocidade"); - LSTR MSG_VMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Vel"); - LSTR MSG_VMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Vel"); - LSTR MSG_VMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Vel"); - LSTR MSG_VMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Vel"); - LSTR MSG_VMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Vel"); - LSTR MSG_VMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Vel"); - LSTR MSG_VMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Vel"); + LSTR MSG_VMAX_A = _UxGT("Max ") STR_A _UxGT(" Vel"); + LSTR MSG_VMAX_B = _UxGT("Max ") STR_B _UxGT(" Vel"); + LSTR MSG_VMAX_C = _UxGT("Max ") STR_C _UxGT(" Vel"); + LSTR MSG_VMAX_I = _UxGT("Max ") STR_I _UxGT(" Vel"); + LSTR MSG_VMAX_J = _UxGT("Max ") STR_J _UxGT(" Vel"); + LSTR MSG_VMAX_K = _UxGT("Max ") STR_K _UxGT(" Vel"); + LSTR MSG_VMAX_E = _UxGT("Max ") STR_E _UxGT(" Vel"); LSTR MSG_VMAX_EN = _UxGT("Max * Vel"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("V-viaxe min"); LSTR MSG_ACCELERATION = _UxGT("Aceleración"); - LSTR MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Accel"); - LSTR MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Accel"); - LSTR MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Accel"); - LSTR MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Accel"); - LSTR MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Accel"); - LSTR MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Accel"); - LSTR MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Accel"); + LSTR MSG_AMAX_A = _UxGT("Max ") STR_A _UxGT(" Accel"); + LSTR MSG_AMAX_B = _UxGT("Max ") STR_B _UxGT(" Accel"); + LSTR MSG_AMAX_C = _UxGT("Max ") STR_C _UxGT(" Accel"); + LSTR MSG_AMAX_I = _UxGT("Max ") STR_I _UxGT(" Accel"); + LSTR MSG_AMAX_J = _UxGT("Max ") STR_J _UxGT(" Accel"); + LSTR MSG_AMAX_K = _UxGT("Max ") STR_K _UxGT(" Accel"); + LSTR MSG_AMAX_E = _UxGT("Max ") STR_E _UxGT(" Accel"); LSTR MSG_AMAX_EN = _UxGT("Max * Accel"); LSTR MSG_A_RETRACT = _UxGT("A-retrac."); LSTR MSG_A_TRAVEL = _UxGT("A-viaxe"); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Frecuencia max"); LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Avance min"); LSTR MSG_STEPS_PER_MM = _UxGT("Pasos/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" pasos/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" pasos/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" pasos/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" pasos/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" pasos/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" pasos/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" pasos/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" pasos/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" pasos/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" pasos/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" pasos/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" pasos/mm"); LSTR MSG_E_STEPS = _UxGT("E pasos/mm"); LSTR MSG_EN_STEPS = _UxGT("* pasos/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -497,12 +497,12 @@ namespace Language_gl { LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp Máx"); LSTR MSG_INFO_PSU = _UxGT("Fonte Alimentación"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Forza do Motor"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driver %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); LSTR MSG_ERROR_TMC = _UxGT("ERRO CONEX. TMC"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Escribe DAC EEPROM"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 8b5e7863030b3..341d1b467ddb9 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -79,9 +79,9 @@ namespace Language_hu { LSTR MSG_HOME_OFFSET_X = _UxGT("X Kezdö eltol."); LSTR MSG_HOME_OFFSET_Y = _UxGT("Y Kezdö eltol."); LSTR MSG_HOME_OFFSET_Z = _UxGT("Z Kezdö eltol."); - LSTR MSG_HOME_OFFSET_I = _UxGT("Kezdö eltol. ") LCD_STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Kezdö eltol. ") LCD_STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Kezdö eltol. ") LCD_STR_K; + LSTR MSG_HOME_OFFSET_I = _UxGT("Kezdö eltol. ") STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Kezdö eltol. ") STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Kezdö eltol. ") STR_K; LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Eltolás beállítva."); LSTR MSG_SET_ORIGIN = _UxGT("Eredeti Be"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Elektromos varázsló"); @@ -260,9 +260,9 @@ namespace Language_hu { LSTR MSG_MOVE_X = _UxGT("X mozgás"); LSTR MSG_MOVE_Y = _UxGT("Y mozgás"); LSTR MSG_MOVE_Z = _UxGT("Z mozgás"); - LSTR MSG_MOVE_I = _UxGT("Mozgás ") LCD_STR_I; - LSTR MSG_MOVE_J = _UxGT("Mozgás ") LCD_STR_J; - LSTR MSG_MOVE_K = _UxGT("Mozgás ") LCD_STR_K; + LSTR MSG_MOVE_I = _UxGT("Mozgás ") STR_I; + LSTR MSG_MOVE_J = _UxGT("Mozgás ") STR_J; + LSTR MSG_MOVE_K = _UxGT("Mozgás ") STR_K; LSTR MSG_MOVE_E = _UxGT("Adagoló"); LSTR MSG_MOVE_EN = _UxGT("Adagoló *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("A fej túl hideg"); @@ -317,45 +317,45 @@ namespace Language_hu { LSTR MSG_SELECT_E = _UxGT("Kiválaszt *"); LSTR MSG_ACC = _UxGT("Gyorsítás"); LSTR MSG_JERK = _UxGT("Rántás"); - LSTR MSG_VA_JERK = _UxGT("Seb.") LCD_STR_A _UxGT("-Rántás"); - LSTR MSG_VB_JERK = _UxGT("Seb.") LCD_STR_B _UxGT("-Rántás"); - LSTR MSG_VC_JERK = _UxGT("Seb.") LCD_STR_C _UxGT("-Rántás"); - LSTR MSG_VI_JERK = _UxGT("Seb.") LCD_STR_I _UxGT("-Rántás"); - LSTR MSG_VJ_JERK = _UxGT("Seb.") LCD_STR_J _UxGT("-Rántás"); - LSTR MSG_VK_JERK = _UxGT("Seb.") LCD_STR_K _UxGT("-Rántás"); + LSTR MSG_VA_JERK = _UxGT("Seb.") STR_A _UxGT("-Rántás"); + LSTR MSG_VB_JERK = _UxGT("Seb.") STR_B _UxGT("-Rántás"); + LSTR MSG_VC_JERK = _UxGT("Seb.") STR_C _UxGT("-Rántás"); + LSTR MSG_VI_JERK = _UxGT("Seb.") STR_I _UxGT("-Rántás"); + LSTR MSG_VJ_JERK = _UxGT("Seb.") STR_J _UxGT("-Rántás"); + LSTR MSG_VK_JERK = _UxGT("Seb.") STR_K _UxGT("-Rántás"); LSTR MSG_VE_JERK = _UxGT("E ránt. seb."); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Csomopont eltérés"); LSTR MSG_VELOCITY = _UxGT("Sebesség"); - LSTR MSG_VMAX_A = _UxGT("Max Seb. ") LCD_STR_A; - LSTR MSG_VMAX_B = _UxGT("Max Seb. ") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("Max Seb. ") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("Max Seb. ") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("Max Seb. ") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("Max Seb. ") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("Max Seb. ") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("Max Seb. ") STR_A; + LSTR MSG_VMAX_B = _UxGT("Max Seb. ") STR_B; + LSTR MSG_VMAX_C = _UxGT("Max Seb. ") STR_C; + LSTR MSG_VMAX_I = _UxGT("Max Seb. ") STR_I; + LSTR MSG_VMAX_J = _UxGT("Max Seb. ") STR_J; + LSTR MSG_VMAX_K = _UxGT("Max Seb. ") STR_K; + LSTR MSG_VMAX_E = _UxGT("Max Seb. ") STR_E; LSTR MSG_VMAX_EN = _UxGT("Max sebesség *"); LSTR MSG_VMIN = _UxGT("Min sebesség"); LSTR MSG_VTRAV_MIN = _UxGT("Min utazó.seb."); LSTR MSG_ACCELERATION = _UxGT("Gyorsulás"); - LSTR MSG_AMAX_A = _UxGT("Max gyors. ") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("Max gyors. ") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Max gyors. ") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Max gyors. ") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("Max gyors. ") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Max gyors. ") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Max gyors. ") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Max gyors. ") STR_A; + LSTR MSG_AMAX_B = _UxGT("Max gyors. ") STR_B; + LSTR MSG_AMAX_C = _UxGT("Max gyors. ") STR_C; + LSTR MSG_AMAX_I = _UxGT("Max gyors. ") STR_I; + LSTR MSG_AMAX_J = _UxGT("Max gyors. ") STR_J; + LSTR MSG_AMAX_K = _UxGT("Max gyors. ") STR_K; + LSTR MSG_AMAX_E = _UxGT("Max gyors. ") STR_E; LSTR MSG_AMAX_EN = _UxGT("Max gyorsulás *"); LSTR MSG_A_RETRACT = _UxGT("Visszahúzás"); LSTR MSG_A_TRAVEL = _UxGT("Utazás"); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Max frekvencia"); LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min elötolás"); LSTR MSG_STEPS_PER_MM = _UxGT("Lépés/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" Lépés/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" Lépés/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" Lépés/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" Lépés/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" Lépés/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" Lépés/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" Lépés/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" Lépés/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" Lépés/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" Lépés/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" Lépés/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" Lépés/mm"); LSTR MSG_E_STEPS = _UxGT("E lépés/mm"); LSTR MSG_EN_STEPS = _UxGT("*Lépés/mm"); LSTR MSG_TEMPERATURE = _UxGT("Höfok"); @@ -489,9 +489,9 @@ namespace Language_hu { LSTR MSG_BABYSTEP_X = _UxGT("Mikrolépés X"); LSTR MSG_BABYSTEP_Y = _UxGT("Mikrolépés Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Mikrolépés Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Mikrolépés ") LCD_STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Mikrolépés ") LCD_STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Mikrolépés ") LCD_STR_K; + LSTR MSG_BABYSTEP_I = _UxGT("Mikrolépés ") STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Mikrolépés ") STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Mikrolépés ") STR_K; LSTR MSG_BABYSTEP_TOTAL = _UxGT("Teljes"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Végállás megszakítva!"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Fütés hiba!"); @@ -569,12 +569,12 @@ namespace Language_hu { LSTR MSG_INFO_MAX_TEMP = _UxGT("Max höfok"); LSTR MSG_INFO_PSU = _UxGT("PSU"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Meghajtási erö"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Meghajtó %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Meghajtó %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Meghajtó %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Meghajtó %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Meghajtó %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Meghajtó %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Meghajtó %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Meghajtó %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Meghajtó %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Meghajtó %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Meghajtó %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Meghajtó %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E meghajtó %"); LSTR MSG_ERROR_TMC = _UxGT("TMC CSATLAKOZÁSI HIBA"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM írása"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 1c36a5de2152d..431b1d01b7bea 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -85,9 +85,9 @@ namespace Language_it { LSTR MSG_HOME_OFFSET_X = _UxGT("Offset home X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Offset home Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Offset home Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Offset home ") LCD_STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Offset home ") LCD_STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Offset home ") LCD_STR_K; + LSTR MSG_HOME_OFFSET_I = _UxGT("Offset home ") STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Offset home ") STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Offset home ") STR_K; LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset applicato"); LSTR MSG_SET_ORIGIN = _UxGT("Imposta Origine"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Wizard Tramming"); @@ -268,9 +268,9 @@ namespace Language_it { LSTR MSG_MOVE_X = _UxGT("Muovi X"); LSTR MSG_MOVE_Y = _UxGT("Muovi Y"); LSTR MSG_MOVE_Z = _UxGT("Muovi Z"); - LSTR MSG_MOVE_I = _UxGT("Muovi ") LCD_STR_I; - LSTR MSG_MOVE_J = _UxGT("Muovi ") LCD_STR_J; - LSTR MSG_MOVE_K = _UxGT("Muovi ") LCD_STR_K; + LSTR MSG_MOVE_I = _UxGT("Muovi ") STR_I; + LSTR MSG_MOVE_J = _UxGT("Muovi ") STR_J; + LSTR MSG_MOVE_K = _UxGT("Muovi ") STR_K; LSTR MSG_MOVE_E = _UxGT("Estrusore"); LSTR MSG_MOVE_EN = _UxGT("Estrusore *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Ugello freddo"); @@ -325,45 +325,45 @@ namespace Language_it { LSTR MSG_SELECT_E = _UxGT("Seleziona *"); LSTR MSG_ACC = _UxGT("Accel"); LSTR MSG_JERK = _UxGT("Jerk"); - LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-jerk"); - LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-jerk"); - LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-jerk"); - LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-jerk"); - LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-jerk"); - LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-jerk"); + LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-jerk"); + LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-jerk"); + LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-jerk"); + LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-jerk"); + LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-jerk"); + LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-jerk"); LSTR MSG_VE_JERK = _UxGT("Ve-jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Deviaz. giunzioni"); LSTR MSG_VELOCITY = _UxGT("Velocità"); - LSTR MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - LSTR MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("Vmax ") STR_A; + LSTR MSG_VMAX_B = _UxGT("Vmax ") STR_B; + LSTR MSG_VMAX_C = _UxGT("Vmax ") STR_C; + LSTR MSG_VMAX_I = _UxGT("Vmax ") STR_I; + LSTR MSG_VMAX_J = _UxGT("Vmax ") STR_J; + LSTR MSG_VMAX_K = _UxGT("Vmax ") STR_K; + LSTR MSG_VMAX_E = _UxGT("Vmax ") STR_E; LSTR MSG_VMAX_EN = _UxGT("Vmax *"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("VTrav min"); LSTR MSG_ACCELERATION = _UxGT("Accelerazione"); - LSTR MSG_AMAX_A = _UxGT("Max ") LCD_STR_A _UxGT(" Accel"); - LSTR MSG_AMAX_B = _UxGT("Max ") LCD_STR_B _UxGT(" Accel"); - LSTR MSG_AMAX_C = _UxGT("Max ") LCD_STR_C _UxGT(" Accel"); - LSTR MSG_AMAX_I = _UxGT("Max ") LCD_STR_I _UxGT(" Accel"); - LSTR MSG_AMAX_J = _UxGT("Max ") LCD_STR_J _UxGT(" Accel"); - LSTR MSG_AMAX_K = _UxGT("Max ") LCD_STR_K _UxGT(" Accel"); - LSTR MSG_AMAX_E = _UxGT("Max ") LCD_STR_E _UxGT(" Accel"); + LSTR MSG_AMAX_A = _UxGT("Max ") STR_A _UxGT(" Accel"); + LSTR MSG_AMAX_B = _UxGT("Max ") STR_B _UxGT(" Accel"); + LSTR MSG_AMAX_C = _UxGT("Max ") STR_C _UxGT(" Accel"); + LSTR MSG_AMAX_I = _UxGT("Max ") STR_I _UxGT(" Accel"); + LSTR MSG_AMAX_J = _UxGT("Max ") STR_J _UxGT(" Accel"); + LSTR MSG_AMAX_K = _UxGT("Max ") STR_K _UxGT(" Accel"); + LSTR MSG_AMAX_E = _UxGT("Max ") STR_E _UxGT(" Accel"); LSTR MSG_AMAX_EN = _UxGT("Max * Accel"); LSTR MSG_A_RETRACT = _UxGT("A-Ritrazione"); LSTR MSG_A_TRAVEL = _UxGT("A-Spostamento"); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequenza max"); LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); LSTR MSG_STEPS_PER_MM = _UxGT("Passi/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" passi/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" passi/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" passi/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" passi/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" passi/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" passi/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" passi/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" passi/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" passi/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" passi/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" passi/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" passi/mm"); LSTR MSG_E_STEPS = _UxGT("E passi/mm"); LSTR MSG_EN_STEPS = _UxGT("* passi/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -497,9 +497,9 @@ namespace Language_it { LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; + LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") STR_K; LSTR MSG_BABYSTEP_TOTAL = _UxGT("Totali"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Interrompi se FC"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Risc.Fallito"); // Max 12 characters @@ -577,12 +577,12 @@ namespace Language_it { LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp max"); LSTR MSG_INFO_PSU = _UxGT("Alimentatore"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Potenza Drive"); - LSTR MSG_DAC_PERCENT_A = _UxGT("Driver ") LCD_STR_A _UxGT(" %"); - LSTR MSG_DAC_PERCENT_B = _UxGT("Driver ") LCD_STR_B _UxGT(" %"); - LSTR MSG_DAC_PERCENT_C = _UxGT("Driver ") LCD_STR_C _UxGT(" %"); - LSTR MSG_DAC_PERCENT_I = _UxGT("Driver ") LCD_STR_I _UxGT(" %"); - LSTR MSG_DAC_PERCENT_J = _UxGT("Driver ") LCD_STR_J _UxGT(" %"); - LSTR MSG_DAC_PERCENT_K = _UxGT("Driver ") LCD_STR_K _UxGT(" %"); + LSTR MSG_DAC_PERCENT_A = _UxGT("Driver ") STR_A _UxGT(" %"); + LSTR MSG_DAC_PERCENT_B = _UxGT("Driver ") STR_B _UxGT(" %"); + LSTR MSG_DAC_PERCENT_C = _UxGT("Driver ") STR_C _UxGT(" %"); + LSTR MSG_DAC_PERCENT_I = _UxGT("Driver ") STR_I _UxGT(" %"); + LSTR MSG_DAC_PERCENT_J = _UxGT("Driver ") STR_J _UxGT(" %"); + LSTR MSG_DAC_PERCENT_K = _UxGT("Driver ") STR_K _UxGT(" %"); LSTR MSG_DAC_PERCENT_E = _UxGT("Driver E %"); LSTR MSG_ERROR_TMC = _UxGT("ERR.CONNESSIONE TMC"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Scrivi DAC EEPROM"); diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index 16e605cc25c92..3a876a07e383f 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -116,23 +116,23 @@ namespace Language_jp_kana { LSTR MSG_SELECT_E = _UxGT("センタク *"); LSTR MSG_ACC = _UxGT("カソクド mm/s") SUPERSCRIPT_TWO; // "Accel" LSTR MSG_JERK = _UxGT("ヤクドウ mm/s"); // "Jerk" - LSTR MSG_VA_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_A; // "Va-jerk" - LSTR MSG_VB_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_B; // "Vb-jerk" - LSTR MSG_VC_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_C; // "Vc-jerk" - LSTR MSG_VI_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_I; // "Va-jerk" - LSTR MSG_VJ_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_J; // "Vb-jerk" - LSTR MSG_VK_JERK = _UxGT("ジク ヤクドウ mm/s") LCD_STR_K; // "Vc-jerk" - LSTR MSG_A_STEPS = LCD_STR_A _UxGT("ステップ/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT("ステップ/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT("ステップ/mm"); + LSTR MSG_VA_JERK = _UxGT("ジク ヤクドウ mm/s") STR_A; // "Va-jerk" + LSTR MSG_VB_JERK = _UxGT("ジク ヤクドウ mm/s") STR_B; // "Vb-jerk" + LSTR MSG_VC_JERK = _UxGT("ジク ヤクドウ mm/s") STR_C; // "Vc-jerk" + LSTR MSG_VI_JERK = _UxGT("ジク ヤクドウ mm/s") STR_I; // "Va-jerk" + LSTR MSG_VJ_JERK = _UxGT("ジク ヤクドウ mm/s") STR_J; // "Vb-jerk" + LSTR MSG_VK_JERK = _UxGT("ジク ヤクドウ mm/s") STR_K; // "Vc-jerk" + LSTR MSG_A_STEPS = STR_A _UxGT("ステップ/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT("ステップ/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT("ステップ/mm"); LSTR MSG_VE_JERK = _UxGT("エクストルーダー ヤクド"); // "Ve-jerk" - LSTR MSG_VMAX_A = _UxGT("サイダイオクリソクド ") LCD_STR_A; // "Vmax A" - LSTR MSG_VMAX_B = _UxGT("サイダイオクリソクド ") LCD_STR_B; // "Vmax B" - LSTR MSG_VMAX_C = _UxGT("サイダイオクリソクド ") LCD_STR_C; // "Vmax C" - LSTR MSG_VMAX_I = _UxGT("サイダイオクリソクド ") LCD_STR_I; // "Vmax I" - LSTR MSG_VMAX_J = _UxGT("サイダイオクリソクド ") LCD_STR_J; // "Vmax J" - LSTR MSG_VMAX_K = _UxGT("サイダイオクリソクド ") LCD_STR_K; // "Vmax K" - LSTR MSG_VMAX_E = _UxGT("サイダイオクリソクド ") LCD_STR_E; // "Vmax E" + LSTR MSG_VMAX_A = _UxGT("サイダイオクリソクド ") STR_A; // "Vmax A" + LSTR MSG_VMAX_B = _UxGT("サイダイオクリソクド ") STR_B; // "Vmax B" + LSTR MSG_VMAX_C = _UxGT("サイダイオクリソクド ") STR_C; // "Vmax C" + LSTR MSG_VMAX_I = _UxGT("サイダイオクリソクド ") STR_I; // "Vmax I" + LSTR MSG_VMAX_J = _UxGT("サイダイオクリソクド ") STR_J; // "Vmax J" + LSTR MSG_VMAX_K = _UxGT("サイダイオクリソクド ") STR_K; // "Vmax K" + LSTR MSG_VMAX_E = _UxGT("サイダイオクリソクド ") STR_E; // "Vmax E" LSTR MSG_VMAX_EN = _UxGT("サイダイオクリソクド *"); // "Vmax E1" LSTR MSG_VMIN = _UxGT("サイショウオクリソクド"); // "Vmin" LSTR MSG_VTRAV_MIN = _UxGT("サイショウイドウソクド"); // "VTrav min" @@ -217,12 +217,12 @@ namespace Language_jp_kana { LSTR MSG_INFO_MAX_TEMP = _UxGT("セッテイサイコウオン"); // "Max Temp" LSTR MSG_INFO_PSU = _UxGT("デンゲンシュベツ"); // "Power Supply" LSTR MSG_DRIVE_STRENGTH = _UxGT("モータークドウリョク"); // "Drive Strength" - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" DACシュツリョク %"); // "X Driver %" - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" DACシュツリョク %"); // "Y Driver %" - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" DACシュツリョク %"); // "Z Driver %" - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" DACシュツリョク %"); // "I Driver %" - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" DACシュツリョク %"); // "J Driver %" - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" DACシュツリョク %"); // "K Driver %" + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" DACシュツリョク %"); // "X Driver %" + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" DACシュツリョク %"); // "Y Driver %" + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" DACシュツリョク %"); // "Z Driver %" + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" DACシュツリョク %"); // "I Driver %" + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" DACシュツリョク %"); // "J Driver %" + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" DACシュツリョク %"); // "K Driver %" LSTR MSG_DAC_PERCENT_E = _UxGT("E DACシュツリョク %"); // "E Driver %" LSTR MSG_DAC_EEPROM_WRITE = _UxGT("EEPROMヘホゾン"); // "Store memory" LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("イチジテイシ"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 7c012f46df5a4..47c89e9e32919 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -274,12 +274,12 @@ namespace Language_pl { LSTR MSG_SELECT_E = _UxGT("Wybierz *"); LSTR MSG_ACC = _UxGT("Przyspieszenie"); LSTR MSG_JERK = _UxGT("Zryw"); - LSTR MSG_VA_JERK = _UxGT("Zryw V") LCD_STR_A; - LSTR MSG_VB_JERK = _UxGT("Zryw V") LCD_STR_B; - LSTR MSG_VC_JERK = _UxGT("Zryw V") LCD_STR_C; - LSTR MSG_VI_JERK = _UxGT("Zryw V") LCD_STR_I; - LSTR MSG_VJ_JERK = _UxGT("Zryw V") LCD_STR_J; - LSTR MSG_VK_JERK = _UxGT("Zryw V") LCD_STR_K; + LSTR MSG_VA_JERK = _UxGT("Zryw V") STR_A; + LSTR MSG_VB_JERK = _UxGT("Zryw V") STR_B; + LSTR MSG_VC_JERK = _UxGT("Zryw V") STR_C; + LSTR MSG_VI_JERK = _UxGT("Zryw V") STR_I; + LSTR MSG_VJ_JERK = _UxGT("Zryw V") STR_J; + LSTR MSG_VK_JERK = _UxGT("Zryw V") STR_K; LSTR MSG_VE_JERK = _UxGT("Zryw Ve"); LSTR MSG_VELOCITY = _UxGT("Prędkość (V)"); @@ -290,12 +290,12 @@ namespace Language_pl { LSTR MSG_A_TRAVEL = _UxGT("A-przesuń."); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Częstotliwość max"); LSTR MSG_STEPS_PER_MM = _UxGT("kroki/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" kroki/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" kroki/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" kroki/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" kroki/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" kroki/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" kroki/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" kroki/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" kroki/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" kroki/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" kroki/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" kroki/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" kroki/mm"); LSTR MSG_E_STEPS = _UxGT("E kroki/mm"); LSTR MSG_EN_STEPS = _UxGT("* kroki/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); @@ -446,12 +446,12 @@ namespace Language_pl { LSTR MSG_INFO_PSU = _UxGT("Zasilacz"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Siła silnika"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Siła %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Siła %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Siła %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Siła %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Siła %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Siła %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Siła %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Siła %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Siła %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Siła %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Siła %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Siła %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Siła %"); LSTR MSG_ERROR_TMC = _UxGT("TMC BŁĄD POŁĄCZENIA"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Zapisz DAC EEPROM"); diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index 524c2c97d8590..f73fe1f1b4818 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -102,12 +102,12 @@ namespace Language_pt { LSTR MSG_A_RETRACT = _UxGT("A-retracção"); LSTR MSG_A_TRAVEL = _UxGT("A-movimento"); LSTR MSG_STEPS_PER_MM = _UxGT("Passo/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" passo/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" passo/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" passo/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" passo/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" passo/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" passo/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" passo/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" passo/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" passo/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" passo/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" passo/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" passo/mm"); LSTR MSG_E_STEPS = _UxGT("E passo/mm"); LSTR MSG_EN_STEPS = _UxGT("* passo/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 0c44145e00e22..8d8c65f63d4ea 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -240,12 +240,12 @@ namespace Language_pt_br { LSTR MSG_SELECT_E = _UxGT("Selecionar *"); LSTR MSG_ACC = _UxGT("Acel."); LSTR MSG_JERK = _UxGT("Arrancada"); - LSTR MSG_VA_JERK = _UxGT("arrancada V") LCD_STR_A; - LSTR MSG_VB_JERK = _UxGT("arrancada V") LCD_STR_B; - LSTR MSG_VC_JERK = _UxGT("arrancada V") LCD_STR_C; - LSTR MSG_VI_JERK = _UxGT("arrancada V") LCD_STR_I; - LSTR MSG_VJ_JERK = _UxGT("arrancada V") LCD_STR_J; - LSTR MSG_VK_JERK = _UxGT("arrancada V") LCD_STR_K; + LSTR MSG_VA_JERK = _UxGT("arrancada V") STR_A; + LSTR MSG_VB_JERK = _UxGT("arrancada V") STR_B; + LSTR MSG_VC_JERK = _UxGT("arrancada V") STR_C; + LSTR MSG_VI_JERK = _UxGT("arrancada V") STR_I; + LSTR MSG_VJ_JERK = _UxGT("arrancada V") STR_J; + LSTR MSG_VK_JERK = _UxGT("arrancada V") STR_K; LSTR MSG_VE_JERK = _UxGT("arrancada VE"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Desv. Junção"); LSTR MSG_VELOCITY = _UxGT("Velocidade"); @@ -254,12 +254,12 @@ namespace Language_pt_br { LSTR MSG_A_RETRACT = _UxGT("Retrair A"); LSTR MSG_A_TRAVEL = _UxGT("Movimento A"); LSTR MSG_STEPS_PER_MM = _UxGT("Passo/mm"); - LSTR MSG_A_STEPS = _UxGT("Passo ") LCD_STR_A _UxGT("/mm"); - LSTR MSG_B_STEPS = _UxGT("Passo ") LCD_STR_B _UxGT("/mm"); - LSTR MSG_C_STEPS = _UxGT("Passo ") LCD_STR_C _UxGT("/mm"); - LSTR MSG_I_STEPS = _UxGT("Passo ") LCD_STR_I _UxGT("/mm"); - LSTR MSG_J_STEPS = _UxGT("Passo ") LCD_STR_J _UxGT("/mm"); - LSTR MSG_K_STEPS = _UxGT("Passo ") LCD_STR_K _UxGT("/mm"); + LSTR MSG_A_STEPS = _UxGT("Passo ") STR_A _UxGT("/mm"); + LSTR MSG_B_STEPS = _UxGT("Passo ") STR_B _UxGT("/mm"); + LSTR MSG_C_STEPS = _UxGT("Passo ") STR_C _UxGT("/mm"); + LSTR MSG_I_STEPS = _UxGT("Passo ") STR_I _UxGT("/mm"); + LSTR MSG_J_STEPS = _UxGT("Passo ") STR_J _UxGT("/mm"); + LSTR MSG_K_STEPS = _UxGT("Passo ") STR_K _UxGT("/mm"); LSTR MSG_E_STEPS = _UxGT("E/mm"); LSTR MSG_EN_STEPS = _UxGT("*/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index 29cdc51c80e99..f51179829a8ef 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -268,45 +268,45 @@ namespace Language_ro { LSTR MSG_SELECT_E = _UxGT("Select *"); LSTR MSG_ACC = _UxGT("Accel"); LSTR MSG_JERK = _UxGT("Jerk"); - LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); - LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); - LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); - LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Jerk"); - LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Jerk"); - LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Jerk"); + LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-Jerk"); + LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-Jerk"); + LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-Jerk"); + LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-Jerk"); + LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-Jerk"); + LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-Jerk"); LSTR MSG_VE_JERK = _UxGT("Ve-Jerk"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); LSTR MSG_VELOCITY = _UxGT("Velocity"); - LSTR MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - LSTR MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("Vmax ") STR_A; + LSTR MSG_VMAX_B = _UxGT("Vmax ") STR_B; + LSTR MSG_VMAX_C = _UxGT("Vmax ") STR_C; + LSTR MSG_VMAX_I = _UxGT("Vmax ") STR_I; + LSTR MSG_VMAX_J = _UxGT("Vmax ") STR_J; + LSTR MSG_VMAX_K = _UxGT("Vmax ") STR_K; + LSTR MSG_VMAX_E = _UxGT("Vmax ") STR_E; LSTR MSG_VMAX_EN = _UxGT("Vmax *"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("VTrav Min"); LSTR MSG_ACCELERATION = _UxGT("Acceleration"); - LSTR MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Amax ") STR_A; + LSTR MSG_AMAX_B = _UxGT("Amax ") STR_B; + LSTR MSG_AMAX_C = _UxGT("Amax ") STR_C; + LSTR MSG_AMAX_I = _UxGT("Amax ") STR_I; + LSTR MSG_AMAX_J = _UxGT("Amax ") STR_J; + LSTR MSG_AMAX_K = _UxGT("Amax ") STR_K; + LSTR MSG_AMAX_E = _UxGT("Amax ") STR_E; LSTR MSG_AMAX_EN = _UxGT("Amax *"); LSTR MSG_A_RETRACT = _UxGT("A-Retract"); LSTR MSG_A_TRAVEL = _UxGT("A-Travel"); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequency max"); LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); LSTR MSG_STEPS_PER_MM = _UxGT("Steps/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" steps/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" steps/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" steps/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" steps/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" steps/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" steps/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" steps/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" steps/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" steps/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" steps/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" steps/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" steps/mm"); LSTR MSG_E_STEPS = _UxGT("Esteps/mm"); LSTR MSG_EN_STEPS = _UxGT("*steps/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperature"); @@ -504,12 +504,12 @@ namespace Language_ro { LSTR MSG_INFO_MAX_TEMP = _UxGT("Temperatura Maxima"); LSTR MSG_INFO_PSU = _UxGT("PSU"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Drive Strength"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driver %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); LSTR MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 5e3d0f2fac348..d6b5bbfbdf04f 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -84,17 +84,17 @@ namespace Language_ru { LSTR MSG_HOME_OFFSET_X = _UxGT("Смещение дома X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Смещение дома Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Смещение дома Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Смещение дома ") LCD_STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Смещение дома ") LCD_STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Смещение дома ") LCD_STR_K; + LSTR MSG_HOME_OFFSET_I = _UxGT("Смещение дома ") STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Смещение дома ") STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Смещение дома ") STR_K; #else LSTR MSG_SET_HOME_OFFSETS = _UxGT("Установ.смещ.дома"); LSTR MSG_HOME_OFFSET_X = _UxGT("Смещ. дома X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Смещ. дома Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Смещ. дома Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Смещ. дома ") LCD_STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Смещ. дома ") LCD_STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Смещ. дома ") LCD_STR_K; + LSTR MSG_HOME_OFFSET_I = _UxGT("Смещ. дома ") STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Смещ. дома ") STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Смещ. дома ") STR_K; #endif LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Смещения применены"); LSTR MSG_SET_ORIGIN = _UxGT("Установить ноль"); @@ -339,9 +339,9 @@ namespace Language_ru { LSTR MSG_MOVE_X = _UxGT("Движение по X"); LSTR MSG_MOVE_Y = _UxGT("Движение по Y"); LSTR MSG_MOVE_Z = _UxGT("Движение по Z"); - LSTR MSG_MOVE_I = _UxGT("Движение по ") LCD_STR_I; - LSTR MSG_MOVE_J = _UxGT("Движение по ") LCD_STR_J; - LSTR MSG_MOVE_K = _UxGT("Движение по ") LCD_STR_K; + LSTR MSG_MOVE_I = _UxGT("Движение по ") STR_I; + LSTR MSG_MOVE_J = _UxGT("Движение по ") STR_J; + LSTR MSG_MOVE_K = _UxGT("Движение по ") STR_K; LSTR MSG_MOVE_E = _UxGT("Экструдер"); LSTR MSG_MOVE_EN = _UxGT("Экструдер *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Сопло не нагрето"); @@ -399,12 +399,12 @@ namespace Language_ru { LSTR MSG_SELECT_E = _UxGT("Выбор *"); LSTR MSG_ACC = _UxGT("Ускорение"); LSTR MSG_JERK = _UxGT("Рывок"); - LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-рывок"); - LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-рывок"); - LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-рывок"); - LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-рывок"); - LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-рывок"); - LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-рывок"); + LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-рывок"); + LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-рывок"); + LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-рывок"); + LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-рывок"); + LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-рывок"); + LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-рывок"); LSTR MSG_VE_JERK = _UxGT("Ve-рывок"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_JUNCTION_DEVIATION = _UxGT("Отклонение узла"); @@ -412,36 +412,36 @@ namespace Language_ru { LSTR MSG_JUNCTION_DEVIATION = _UxGT("Отклон. узла"); #endif LSTR MSG_VELOCITY = _UxGT("Скорость, мм/с"); - LSTR MSG_VMAX_A = _UxGT("Скор.макс ") LCD_STR_A; - LSTR MSG_VMAX_B = _UxGT("Скор.макс ") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("Скор.макс ") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("Скор.макс ") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("Скор.макс ") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("Скор.макс ") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("Скор.макс ") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("Скор.макс ") STR_A; + LSTR MSG_VMAX_B = _UxGT("Скор.макс ") STR_B; + LSTR MSG_VMAX_C = _UxGT("Скор.макс ") STR_C; + LSTR MSG_VMAX_I = _UxGT("Скор.макс ") STR_I; + LSTR MSG_VMAX_J = _UxGT("Скор.макс ") STR_J; + LSTR MSG_VMAX_K = _UxGT("Скор.макс ") STR_K; + LSTR MSG_VMAX_E = _UxGT("Скор.макс ") STR_E; LSTR MSG_VMAX_EN = _UxGT("Скор.макс *"); LSTR MSG_VMIN = _UxGT("Скор.мин"); LSTR MSG_VTRAV_MIN = _UxGT("Перемещение мин"); LSTR MSG_ACCELERATION = _UxGT("Ускорение, мм/с2"); - LSTR MSG_AMAX_A = _UxGT("Ускор.макс ") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("Ускор.макс ") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Ускор.макс ") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Ускор.макс ") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("Ускор.макс ") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Ускор.макс ") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Ускор.макс ") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Ускор.макс ") STR_A; + LSTR MSG_AMAX_B = _UxGT("Ускор.макс ") STR_B; + LSTR MSG_AMAX_C = _UxGT("Ускор.макс ") STR_C; + LSTR MSG_AMAX_I = _UxGT("Ускор.макс ") STR_I; + LSTR MSG_AMAX_J = _UxGT("Ускор.макс ") STR_J; + LSTR MSG_AMAX_K = _UxGT("Ускор.макс ") STR_K; + LSTR MSG_AMAX_E = _UxGT("Ускор.макс ") STR_E; LSTR MSG_AMAX_EN = _UxGT("Ускор.макс *"); LSTR MSG_A_RETRACT = _UxGT("Ускор.втягив."); LSTR MSG_A_TRAVEL = _UxGT("Ускор.путеш."); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Частота макс."); LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Подача мин."); LSTR MSG_STEPS_PER_MM = _UxGT("Шагов/мм"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" шаг/мм"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" шаг/мм"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" шаг/мм"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" шаг/мм"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" шаг/мм"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" шаг/мм"); + LSTR MSG_A_STEPS = STR_A _UxGT(" шаг/мм"); + LSTR MSG_B_STEPS = STR_B _UxGT(" шаг/мм"); + LSTR MSG_C_STEPS = STR_C _UxGT(" шаг/мм"); + LSTR MSG_I_STEPS = STR_I _UxGT(" шаг/мм"); + LSTR MSG_J_STEPS = STR_J _UxGT(" шаг/мм"); + LSTR MSG_K_STEPS = STR_K _UxGT(" шаг/мм"); LSTR MSG_E_STEPS = _UxGT("E шаг/мм"); LSTR MSG_EN_STEPS = _UxGT("* шаг/мм"); LSTR MSG_TEMPERATURE = _UxGT("Температура"); @@ -612,9 +612,9 @@ namespace Language_ru { LSTR MSG_BABYSTEP_X = _UxGT("Микрошаг X"); LSTR MSG_BABYSTEP_Y = _UxGT("Микрошаг Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Микрошаг Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Микрошаг ") LCD_STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Микрошаг ") LCD_STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Микрошаг ") LCD_STR_K; + LSTR MSG_BABYSTEP_I = _UxGT("Микрошаг ") STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Микрошаг ") STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Микрошаг ") STR_K; LSTR MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Сработал концевик"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Разогрев не удался"); @@ -711,12 +711,12 @@ namespace Language_ru { LSTR MSG_INFO_MAX_TEMP = _UxGT("Макс. ") LCD_STR_THERMOMETER; LSTR MSG_INFO_PSU = _UxGT("БП"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Сила привода"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Привод, %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Привод, %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Привод, %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Привод, %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Привод, %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Привод, %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Привод, %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Привод, %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Привод, %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Привод, %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Привод, %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Привод, %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Привод, %"); LSTR MSG_ERROR_TMC = _UxGT("СБОЙ СВЯЗИ С TMC"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Запись DAC в EEPROM"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index db694e224271d..64e298cb152ea 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -98,9 +98,9 @@ namespace Language_sk { LSTR MSG_HOME_OFFSET_X = _UxGT("X Ofset"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Y Ofset"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Z Ofset"); - LSTR MSG_HOME_OFFSET_I = LCD_STR_I _UxGT(" Ofset"); - LSTR MSG_HOME_OFFSET_J = LCD_STR_J _UxGT(" Ofset"); - LSTR MSG_HOME_OFFSET_K = LCD_STR_K _UxGT(" Ofset"); + LSTR MSG_HOME_OFFSET_I = STR_I _UxGT(" Ofset"); + LSTR MSG_HOME_OFFSET_J = STR_J _UxGT(" Ofset"); + LSTR MSG_HOME_OFFSET_K = STR_K _UxGT(" Ofset"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofsety nastavené"); LSTR MSG_SET_ORIGIN = _UxGT("Nastaviť začiatok"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Spriev. vyrovn."); @@ -282,9 +282,9 @@ namespace Language_sk { LSTR MSG_MOVE_X = _UxGT("Posunúť X"); LSTR MSG_MOVE_Y = _UxGT("Posunúť Y"); LSTR MSG_MOVE_Z = _UxGT("Posunúť Z"); - LSTR MSG_MOVE_I = _UxGT("Posunúť ") LCD_STR_I; - LSTR MSG_MOVE_J = _UxGT("Posunúť ") LCD_STR_J; - LSTR MSG_MOVE_K = _UxGT("Posunúť ") LCD_STR_K; + LSTR MSG_MOVE_I = _UxGT("Posunúť ") STR_I; + LSTR MSG_MOVE_J = _UxGT("Posunúť ") STR_J; + LSTR MSG_MOVE_K = _UxGT("Posunúť ") STR_K; LSTR MSG_MOVE_E = _UxGT("Extrudér"); LSTR MSG_MOVE_EN = _UxGT("Extrudér *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend je studený"); @@ -299,10 +299,10 @@ namespace Language_sk { LSTR MSG_MOVE_1IN = _UxGT("Posunúť o 1,0in"); LSTR MSG_SPEED = _UxGT("Rýchlosť"); LSTR MSG_MAXSPEED = _UxGT("Max rýchl. (mm/s)"); - LSTR MSG_MAXSPEED_X = _UxGT("Max rýchl. ") LCD_STR_A; - LSTR MSG_MAXSPEED_Y = _UxGT("Max rýchl. ") LCD_STR_B; - LSTR MSG_MAXSPEED_Z = _UxGT("Max rýchl. ") LCD_STR_C; - LSTR MSG_MAXSPEED_E = _UxGT("Max rýchl. ") LCD_STR_E; + LSTR MSG_MAXSPEED_X = _UxGT("Max rýchl. ") STR_A; + LSTR MSG_MAXSPEED_Y = _UxGT("Max rýchl. ") STR_B; + LSTR MSG_MAXSPEED_Z = _UxGT("Max rýchl. ") STR_C; + LSTR MSG_MAXSPEED_E = _UxGT("Max rýchl. ") STR_E; LSTR MSG_MAXSPEED_A = _UxGT("Max rýchl. @"); LSTR MSG_BED_Z = _UxGT("Výška podl."); LSTR MSG_NOZZLE = _UxGT("Tryska"); @@ -345,45 +345,45 @@ namespace Language_sk { LSTR MSG_SELECT_E = _UxGT("Vybrať *"); LSTR MSG_ACC = _UxGT("Zrýchlenie"); LSTR MSG_JERK = _UxGT("Skok"); - LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-skok"); - LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-skok"); - LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-skok"); - LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-skok"); - LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-skok"); - LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-skok"); + LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-skok"); + LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-skok"); + LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-skok"); + LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-skok"); + LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-skok"); + LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-skok"); LSTR MSG_VE_JERK = _UxGT("Ve-skok"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); LSTR MSG_VELOCITY = _UxGT("Rýchlosť"); - LSTR MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - LSTR MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("Vmax ") STR_A; + LSTR MSG_VMAX_B = _UxGT("Vmax ") STR_B; + LSTR MSG_VMAX_C = _UxGT("Vmax ") STR_C; + LSTR MSG_VMAX_I = _UxGT("Vmax ") STR_I; + LSTR MSG_VMAX_J = _UxGT("Vmax ") STR_J; + LSTR MSG_VMAX_K = _UxGT("Vmax ") STR_K; + LSTR MSG_VMAX_E = _UxGT("Vmax ") STR_E; LSTR MSG_VMAX_EN = _UxGT("Vmax *"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("VPrej Min"); LSTR MSG_ACCELERATION = _UxGT("Akcelerácia"); - LSTR MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Amax ") STR_A; + LSTR MSG_AMAX_B = _UxGT("Amax ") STR_B; + LSTR MSG_AMAX_C = _UxGT("Amax ") STR_C; + LSTR MSG_AMAX_I = _UxGT("Amax ") STR_I; + LSTR MSG_AMAX_J = _UxGT("Amax ") STR_J; + LSTR MSG_AMAX_K = _UxGT("Amax ") STR_K; + LSTR MSG_AMAX_E = _UxGT("Amax ") STR_E; LSTR MSG_AMAX_EN = _UxGT("Amax *"); LSTR MSG_A_RETRACT = _UxGT("A-retrakt"); LSTR MSG_A_TRAVEL = _UxGT("A-prejazd"); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Max. frekvencia"); LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min. posun"); LSTR MSG_STEPS_PER_MM = _UxGT("Kroky/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" krokov/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" krokov/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" krokov/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" krokov/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" krokov/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" krokov/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" krokov/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" krokov/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" krokov/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" krokov/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" krokov/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" krokov/mm"); LSTR MSG_E_STEPS = _UxGT("Ekrokov/mm"); LSTR MSG_EN_STEPS = _UxGT("*krokov/mm"); LSTR MSG_TEMPERATURE = _UxGT("Teplota"); @@ -528,9 +528,9 @@ namespace Language_sk { LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; + LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") STR_K; LSTR MSG_BABYSTEP_TOTAL = _UxGT("Celkom"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Zastavenie Endstop"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Chyba ohrevu"); @@ -625,12 +625,12 @@ namespace Language_sk { LSTR MSG_INFO_MAX_TEMP = _UxGT("Teplota max"); LSTR MSG_INFO_PSU = _UxGT("Nap. zdroj"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Budenie motorov"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Motor %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Motor %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Motor %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Motor %"); LSTR MSG_ERROR_TMC = _UxGT("CHYBA KOMUNIKÁ. TMC"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Uložiť do EEPROM"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index d4c03d0d61d3c..744fb7e3e6034 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -298,45 +298,45 @@ namespace Language_sv { LSTR MSG_SELECT_E = _UxGT("Välj *"); LSTR MSG_ACC = _UxGT("Accel"); LSTR MSG_JERK = _UxGT("Ryck"); - LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Ryck"); - LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Ryck"); - LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Ryck"); - LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Ryck"); - LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Ryck"); - LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Ryck"); + LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-Ryck"); + LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-Ryck"); + LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-Ryck"); + LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-Ryck"); + LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-Ryck"); + LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-Ryck"); LSTR MSG_VE_JERK = _UxGT("Ve-Ryck"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Knutpunkt Avv"); LSTR MSG_VELOCITY = _UxGT("Hastighet"); - LSTR MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - LSTR MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("Vmax ") STR_A; + LSTR MSG_VMAX_B = _UxGT("Vmax ") STR_B; + LSTR MSG_VMAX_C = _UxGT("Vmax ") STR_C; + LSTR MSG_VMAX_I = _UxGT("Vmax ") STR_I; + LSTR MSG_VMAX_J = _UxGT("Vmax ") STR_J; + LSTR MSG_VMAX_K = _UxGT("Vmax ") STR_K; + LSTR MSG_VMAX_E = _UxGT("Vmax ") STR_E; LSTR MSG_VMAX_EN = _UxGT("Vmax *"); LSTR MSG_VMIN = _UxGT("Vmin"); LSTR MSG_VTRAV_MIN = _UxGT("VTrav Min"); LSTR MSG_ACCELERATION = _UxGT("Acceleration"); - LSTR MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Amax ") STR_A; + LSTR MSG_AMAX_B = _UxGT("Amax ") STR_B; + LSTR MSG_AMAX_C = _UxGT("Amax ") STR_C; + LSTR MSG_AMAX_I = _UxGT("Amax ") STR_I; + LSTR MSG_AMAX_J = _UxGT("Amax ") STR_J; + LSTR MSG_AMAX_K = _UxGT("Amax ") STR_K; + LSTR MSG_AMAX_E = _UxGT("Amax ") STR_E; LSTR MSG_AMAX_EN = _UxGT("Amax *"); LSTR MSG_A_RETRACT = _UxGT("A-Dra tillbaka"); LSTR MSG_A_TRAVEL = _UxGT("A-Färdas"); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Frekvens max"); LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Flöde min"); LSTR MSG_STEPS_PER_MM = _UxGT("Steg/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" Steg/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" Steg/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" Steg/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" Steg/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" Steg/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" Steg/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" Steg/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" Steg/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" Steg/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" Steg/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" Steg/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" Steg/mm"); LSTR MSG_E_STEPS = _UxGT("E Steg/mm"); LSTR MSG_EN_STEPS = _UxGT("* Steg/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatur"); @@ -541,12 +541,12 @@ namespace Language_sv { LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); LSTR MSG_INFO_PSU = _UxGT("PSU"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Driv Styrka"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Driver %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Driver %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Driver %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Driver %"); LSTR MSG_ERROR_TMC = _UxGT("TMC KOPPLNINGSFEL"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Skriv"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 447ea9d5bf2c5..8a1864c966474 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -261,43 +261,43 @@ namespace Language_tr { LSTR MSG_ACC = _UxGT("İvme"); LSTR MSG_JERK = _UxGT("Sarsım"); - LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Sarsım"); - LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Sarsım"); - LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Sarsım"); - LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Sarsım"); - LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Sarsım"); - LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Sarsım"); + LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-Sarsım"); + LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-Sarsım"); + LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-Sarsım"); + LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-Sarsım"); + LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-Sarsım"); + LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-Sarsım"); LSTR MSG_VE_JERK = _UxGT("Ve-Sarsım"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Jonksiyon Sapması"); LSTR MSG_VELOCITY = _UxGT("Hız Vektörü"); - LSTR MSG_VMAX_A = _UxGT("HızVektör.max ") LCD_STR_A; - LSTR MSG_VMAX_B = _UxGT("HızVektör.max ") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("HızVektör.max ") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("HızVektör.max ") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("HızVektör.max ") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("HızVektör.max ") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("HızVektör.max ") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("HızVektör.max ") STR_A; + LSTR MSG_VMAX_B = _UxGT("HızVektör.max ") STR_B; + LSTR MSG_VMAX_C = _UxGT("HızVektör.max ") STR_C; + LSTR MSG_VMAX_I = _UxGT("HızVektör.max ") STR_I; + LSTR MSG_VMAX_J = _UxGT("HızVektör.max ") STR_J; + LSTR MSG_VMAX_K = _UxGT("HızVektör.max ") STR_K; + LSTR MSG_VMAX_E = _UxGT("HızVektör.max ") STR_E; LSTR MSG_VMAX_EN = _UxGT("HızVektör.max *"); LSTR MSG_VMIN = _UxGT("HızVektör.min"); LSTR MSG_VTRAV_MIN = _UxGT("HV.gezinme min"); LSTR MSG_ACCELERATION = _UxGT("Ivme"); - LSTR MSG_AMAX_A = _UxGT("Max. ivme ") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("Max. ivme ") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Max. ivme ") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Max. ivme ") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("Max. ivme ") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Max. ivme ") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Max. ivme ") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Max. ivme ") STR_A; + LSTR MSG_AMAX_B = _UxGT("Max. ivme ") STR_B; + LSTR MSG_AMAX_C = _UxGT("Max. ivme ") STR_C; + LSTR MSG_AMAX_I = _UxGT("Max. ivme ") STR_I; + LSTR MSG_AMAX_J = _UxGT("Max. ivme ") STR_J; + LSTR MSG_AMAX_K = _UxGT("Max. ivme ") STR_K; + LSTR MSG_AMAX_E = _UxGT("Max. ivme ") STR_E; LSTR MSG_AMAX_EN = _UxGT("Max. ivme *"); LSTR MSG_A_RETRACT = _UxGT("Ivme-geri çekme"); LSTR MSG_A_TRAVEL = _UxGT("Ivme-gezinme"); LSTR MSG_STEPS_PER_MM = _UxGT("Adım/mm"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" adım/mm"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" adım/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" adım/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" adım/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" adım/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" adım/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" adım/mm"); + LSTR MSG_B_STEPS = STR_B _UxGT(" adım/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" adım/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" adım/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" adım/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" adım/mm"); LSTR MSG_E_STEPS = _UxGT("E adım/mm"); LSTR MSG_EN_STEPS = _UxGT("* adım/mm"); LSTR MSG_TEMPERATURE = _UxGT("Sıcaklık"); @@ -474,12 +474,12 @@ namespace Language_tr { LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Sıc."); LSTR MSG_INFO_PSU = _UxGT("Güç Kaynağı"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Sürücü Gücü"); - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" Sürücü %"); - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" Sürücü %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" Sürücü %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Sürücü %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Sürücü %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Sürücü %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" Sürücü %"); + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" Sürücü %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" Sürücü %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" Sürücü %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" Sürücü %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" Sürücü %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E Sürücü %"); LSTR MSG_ERROR_TMC = _UxGT("TMC BAĞLANTI HATASI"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Yaz"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 028e48bb41bc6..7afc2e031c230 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -86,17 +86,17 @@ namespace Language_uk { LSTR MSG_HOME_OFFSET_X = _UxGT("Зміщення дому X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Зміщення дому Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Зміщення дому Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Зміщення дому ") LCD_STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Зміщення дому ") LCD_STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Зміщення дому ") LCD_STR_K; + LSTR MSG_HOME_OFFSET_I = _UxGT("Зміщення дому ") STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Зміщення дому ") STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Зміщення дому ") STR_K; #else LSTR MSG_SET_HOME_OFFSETS = _UxGT("Встан. зміщ. дому"); LSTR MSG_HOME_OFFSET_X = _UxGT("Зміщ. дому X"); LSTR MSG_HOME_OFFSET_Y = _UxGT("Зміщ. дому Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Зміщ. дому Z"); - LSTR MSG_HOME_OFFSET_I = _UxGT("Зміщ. дому ") LCD_STR_I; - LSTR MSG_HOME_OFFSET_J = _UxGT("Зміщ. дому ") LCD_STR_J; - LSTR MSG_HOME_OFFSET_K = _UxGT("Зміщ. дому ") LCD_STR_K; + LSTR MSG_HOME_OFFSET_I = _UxGT("Зміщ. дому ") STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Зміщ. дому ") STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Зміщ. дому ") STR_K; #endif LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Зміщення прийняті"); LSTR MSG_SET_ORIGIN = _UxGT("Встановити нуль"); @@ -340,9 +340,9 @@ namespace Language_uk { LSTR MSG_MOVE_X = _UxGT("Рух по X"); LSTR MSG_MOVE_Y = _UxGT("Рух по Y"); LSTR MSG_MOVE_Z = _UxGT("Рух по Z"); - LSTR MSG_MOVE_I = _UxGT("Рух по ") LCD_STR_I; - LSTR MSG_MOVE_J = _UxGT("Рух по ") LCD_STR_J; - LSTR MSG_MOVE_K = _UxGT("Рух по ") LCD_STR_K; + LSTR MSG_MOVE_I = _UxGT("Рух по ") STR_I; + LSTR MSG_MOVE_J = _UxGT("Рух по ") STR_J; + LSTR MSG_MOVE_K = _UxGT("Рух по ") STR_K; LSTR MSG_MOVE_E = _UxGT("Екструдер"); LSTR MSG_MOVE_EN = _UxGT("Екструдер *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Сопло дуже холодне"); @@ -404,12 +404,12 @@ namespace Language_uk { LSTR MSG_SELECT_E = _UxGT("Вибрати *"); LSTR MSG_ACC = _UxGT("Прискорорення"); LSTR MSG_JERK = _UxGT("Ривок"); - LSTR MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-ривок"); - LSTR MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-ривок"); - LSTR MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-ривок"); - LSTR MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-ривок"); - LSTR MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-ривок"); - LSTR MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-ривок"); + LSTR MSG_VA_JERK = _UxGT("V") STR_A _UxGT("-ривок"); + LSTR MSG_VB_JERK = _UxGT("V") STR_B _UxGT("-ривок"); + LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-ривок"); + LSTR MSG_VI_JERK = _UxGT("V") STR_I _UxGT("-ривок"); + LSTR MSG_VJ_JERK = _UxGT("V") STR_J _UxGT("-ривок"); + LSTR MSG_VK_JERK = _UxGT("V") STR_K _UxGT("-ривок"); LSTR MSG_VE_JERK = _UxGT("Ve-ривок"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_JUNCTION_DEVIATION = _UxGT("Відхилення вузла"); @@ -417,13 +417,13 @@ namespace Language_uk { LSTR MSG_JUNCTION_DEVIATION = _UxGT("Відхил.вузла"); #endif LSTR MSG_VELOCITY = _UxGT("Швидкість, мм/с"); - LSTR MSG_VMAX_A = _UxGT("Швидк.макс ") LCD_STR_A; - LSTR MSG_VMAX_B = _UxGT("Швидк.макс ") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("Швидк.макс ") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("Швидк.макс ") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("Швидк.макс ") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("Швидк.макс ") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("Швидк.макс ") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("Швидк.макс ") STR_A; + LSTR MSG_VMAX_B = _UxGT("Швидк.макс ") STR_B; + LSTR MSG_VMAX_C = _UxGT("Швидк.макс ") STR_C; + LSTR MSG_VMAX_I = _UxGT("Швидк.макс ") STR_I; + LSTR MSG_VMAX_J = _UxGT("Швидк.макс ") STR_J; + LSTR MSG_VMAX_K = _UxGT("Швидк.макс ") STR_K; + LSTR MSG_VMAX_E = _UxGT("Швидк.макс ") STR_E; LSTR MSG_VMAX_EN = _UxGT("Швидк.макс *"); LSTR MSG_VMIN = _UxGT("Швидк. мін"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 @@ -432,25 +432,25 @@ namespace Language_uk { LSTR MSG_VTRAV_MIN = _UxGT("Переміщ. мін"); #endif LSTR MSG_ACCELERATION = _UxGT("Прискорення, мм/с2"); - LSTR MSG_AMAX_A = _UxGT("Приск.макс ") LCD_STR_A; - LSTR MSG_AMAX_B = _UxGT("Приск.макс ") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Приск.макс ") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Приск.макс ") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("Приск.макс ") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Приск.макс ") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Приск.макс ") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Приск.макс ") STR_A; + LSTR MSG_AMAX_B = _UxGT("Приск.макс ") STR_B; + LSTR MSG_AMAX_C = _UxGT("Приск.макс ") STR_C; + LSTR MSG_AMAX_I = _UxGT("Приск.макс ") STR_I; + LSTR MSG_AMAX_J = _UxGT("Приск.макс ") STR_J; + LSTR MSG_AMAX_K = _UxGT("Приск.макс ") STR_K; + LSTR MSG_AMAX_E = _UxGT("Приск.макс ") STR_E; LSTR MSG_AMAX_EN = _UxGT("Приск.макс *"); LSTR MSG_A_RETRACT = _UxGT("Приск.втягув."); LSTR MSG_A_TRAVEL = _UxGT("Приск.переміщ."); LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Частота макс."); LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Подача мін."); LSTR MSG_STEPS_PER_MM = _UxGT("Кроків на мм"); - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" кроків/мм"); - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" кроків/мм"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" кроків/мм"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" кроків/мм"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" кроків/мм"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" кроків/мм"); + LSTR MSG_A_STEPS = STR_A _UxGT(" кроків/мм"); + LSTR MSG_B_STEPS = STR_B _UxGT(" кроків/мм"); + LSTR MSG_C_STEPS = STR_C _UxGT(" кроків/мм"); + LSTR MSG_I_STEPS = STR_I _UxGT(" кроків/мм"); + LSTR MSG_J_STEPS = STR_J _UxGT(" кроків/мм"); + LSTR MSG_K_STEPS = STR_K _UxGT(" кроків/мм"); LSTR MSG_E_STEPS = _UxGT("E кроків/мм"); LSTR MSG_EN_STEPS = _UxGT("* кроків/мм"); LSTR MSG_TEMPERATURE = _UxGT("Температура"); @@ -608,9 +608,9 @@ namespace Language_uk { LSTR MSG_BABYSTEP_X = _UxGT("Мікрокрок X"); LSTR MSG_BABYSTEP_Y = _UxGT("Мікрокрок Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Мікрокрок Z"); - LSTR MSG_BABYSTEP_I = _UxGT("Мікрокрок ") LCD_STR_I; - LSTR MSG_BABYSTEP_J = _UxGT("Мікрокрок ") LCD_STR_J; - LSTR MSG_BABYSTEP_K = _UxGT("Мікрокрок ") LCD_STR_K; + LSTR MSG_BABYSTEP_I = _UxGT("Мікрокрок ") STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Мікрокрок ") STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Мікрокрок ") STR_K; LSTR MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Кінцевик спрацював"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("Збій нагріву"); @@ -716,12 +716,12 @@ namespace Language_uk { LSTR MSG_INFO_MAX_TEMP = _UxGT("Макс. ") LCD_STR_THERMOMETER; LSTR MSG_INFO_PSU = _UxGT("Блок жив-ня"); LSTR MSG_DRIVE_STRENGTH = _UxGT("Сила мотору"); - LSTR MSG_DAC_PERCENT_A = _UxGT("Драйвер ") LCD_STR_A _UxGT(", %"); - LSTR MSG_DAC_PERCENT_B = _UxGT("Драйвер ") LCD_STR_B _UxGT(", %"); - LSTR MSG_DAC_PERCENT_C = _UxGT("Драйвер ") LCD_STR_C _UxGT(", %"); - LSTR MSG_DAC_PERCENT_I = _UxGT("Драйвер ") LCD_STR_I _UxGT(", %"); - LSTR MSG_DAC_PERCENT_J = _UxGT("Драйвер ") LCD_STR_J _UxGT(", %"); - LSTR MSG_DAC_PERCENT_K = _UxGT("Драйвер ") LCD_STR_K _UxGT(", %"); + LSTR MSG_DAC_PERCENT_A = _UxGT("Драйвер ") STR_A _UxGT(", %"); + LSTR MSG_DAC_PERCENT_B = _UxGT("Драйвер ") STR_B _UxGT(", %"); + LSTR MSG_DAC_PERCENT_C = _UxGT("Драйвер ") STR_C _UxGT(", %"); + LSTR MSG_DAC_PERCENT_I = _UxGT("Драйвер ") STR_I _UxGT(", %"); + LSTR MSG_DAC_PERCENT_J = _UxGT("Драйвер ") STR_J _UxGT(", %"); + LSTR MSG_DAC_PERCENT_K = _UxGT("Драйвер ") STR_K _UxGT(", %"); LSTR MSG_DAC_PERCENT_E = _UxGT("Драйвер E, %"); LSTR MSG_ERROR_TMC = _UxGT("ЗБІЙ ЗВ'ЯЗКУ З TMC"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Запис ЦАП у EEPROM"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index a419ddee560ad..879ccdeae7c6b 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -228,43 +228,43 @@ namespace Language_vi { LSTR MSG_SELECT_E = _UxGT("Lựa *"); LSTR MSG_ACC = _UxGT("Tăng Tốc"); LSTR MSG_JERK = _UxGT("Giật"); - LSTR MSG_VA_JERK = _UxGT("Giật-V") LCD_STR_A; - LSTR MSG_VB_JERK = _UxGT("Giật-V") LCD_STR_B; - LSTR MSG_VC_JERK = _UxGT("Giật-V") LCD_STR_C; - LSTR MSG_VI_JERK = _UxGT("Giật-V") LCD_STR_I; - LSTR MSG_VJ_JERK = _UxGT("Giật-V") LCD_STR_J; - LSTR MSG_VK_JERK = _UxGT("Giật-V") LCD_STR_K; + LSTR MSG_VA_JERK = _UxGT("Giật-V") STR_A; + LSTR MSG_VB_JERK = _UxGT("Giật-V") STR_B; + LSTR MSG_VC_JERK = _UxGT("Giật-V") STR_C; + LSTR MSG_VI_JERK = _UxGT("Giật-V") STR_I; + LSTR MSG_VJ_JERK = _UxGT("Giật-V") STR_J; + LSTR MSG_VK_JERK = _UxGT("Giật-V") STR_K; LSTR MSG_VE_JERK = _UxGT("Giật-Ve"); LSTR MSG_JUNCTION_DEVIATION = _UxGT("Độ Lệch Chỗ Giao"); // Junction Dev LSTR MSG_VELOCITY = _UxGT("Vận tốc"); // velocity - LSTR MSG_VMAX_A = _UxGT("Vđa") LCD_STR_A; // Vmax - LSTR MSG_VMAX_B = _UxGT("Vđa") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("Vđa") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("Vđa") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("Vđa") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("Vđa") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("Vđa") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("Vđa") STR_A; // Vmax + LSTR MSG_VMAX_B = _UxGT("Vđa") STR_B; + LSTR MSG_VMAX_C = _UxGT("Vđa") STR_C; + LSTR MSG_VMAX_I = _UxGT("Vđa") STR_I; + LSTR MSG_VMAX_J = _UxGT("Vđa") STR_J; + LSTR MSG_VMAX_K = _UxGT("Vđa") STR_K; + LSTR MSG_VMAX_E = _UxGT("Vđa") STR_E; LSTR MSG_VMAX_EN = _UxGT("Vđa *"); LSTR MSG_VMIN = _UxGT("Vthiểu"); // Vmin LSTR MSG_VTRAV_MIN = _UxGT("Vchuyển thiểu"); // VTrav min LSTR MSG_ACCELERATION = _UxGT("Sự tăng tốc"); // Acceleration - LSTR MSG_AMAX_A = _UxGT("Tăng tốc ca") LCD_STR_A; // Amax - LSTR MSG_AMAX_B = _UxGT("Tăng tốc ca") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("Tăng tốc ca") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("Tăng tốc ca") LCD_STR_I; // Amax - LSTR MSG_AMAX_J = _UxGT("Tăng tốc ca") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("Tăng tốc ca") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("Tăng tốc ca") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("Tăng tốc ca") STR_A; // Amax + LSTR MSG_AMAX_B = _UxGT("Tăng tốc ca") STR_B; + LSTR MSG_AMAX_C = _UxGT("Tăng tốc ca") STR_C; + LSTR MSG_AMAX_I = _UxGT("Tăng tốc ca") STR_I; // Amax + LSTR MSG_AMAX_J = _UxGT("Tăng tốc ca") STR_J; + LSTR MSG_AMAX_K = _UxGT("Tăng tốc ca") STR_K; + LSTR MSG_AMAX_E = _UxGT("Tăng tốc ca") STR_E; LSTR MSG_AMAX_EN = _UxGT("Tăng tốc ca *"); LSTR MSG_A_RETRACT = _UxGT("TT-Rút"); // A-retract LSTR MSG_A_TRAVEL = _UxGT("TT-Chuyển"); // A-travel LSTR MSG_STEPS_PER_MM = _UxGT("Bước/mm"); // Steps - LSTR MSG_A_STEPS = _UxGT("Bước") LCD_STR_A _UxGT("/mm"); // Steps/mm - LSTR MSG_B_STEPS = _UxGT("Bước") LCD_STR_B _UxGT("/mm"); - LSTR MSG_C_STEPS = _UxGT("Bước") LCD_STR_C _UxGT("/mm"); - LSTR MSG_I_STEPS = _UxGT("Bước") LCD_STR_I _UxGT("/mm"); // Steps/mm - LSTR MSG_J_STEPS = _UxGT("Bước") LCD_STR_J _UxGT("/mm"); - LSTR MSG_K_STEPS = _UxGT("Bước") LCD_STR_K _UxGT("/mm"); + LSTR MSG_A_STEPS = _UxGT("Bước") STR_A _UxGT("/mm"); // Steps/mm + LSTR MSG_B_STEPS = _UxGT("Bước") STR_B _UxGT("/mm"); + LSTR MSG_C_STEPS = _UxGT("Bước") STR_C _UxGT("/mm"); + LSTR MSG_I_STEPS = _UxGT("Bước") STR_I _UxGT("/mm"); // Steps/mm + LSTR MSG_J_STEPS = _UxGT("Bước") STR_J _UxGT("/mm"); + LSTR MSG_K_STEPS = _UxGT("Bước") STR_K _UxGT("/mm"); LSTR MSG_E_STEPS = _UxGT("BướcE/mm"); LSTR MSG_EN_STEPS = _UxGT("Bước */mm"); LSTR MSG_TEMPERATURE = _UxGT("Nhiệt độ"); // Temperature @@ -400,12 +400,12 @@ namespace Language_vi { LSTR MSG_INFO_MAX_TEMP = _UxGT("Nhiệt độ tối đa"); // Max temp LSTR MSG_INFO_PSU = _UxGT("Bộ nguồn"); // PSU LSTR MSG_DRIVE_STRENGTH = _UxGT("Sức mạnh ổ đĩa"); // Drive Strength - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" % trình điều khiển"); // X Driver % - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" % trình điều khiển"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" % trình điều khiển"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" % trình điều khiển"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" % trình điều khiển"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" % trình điều khiển"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" % trình điều khiển"); // X Driver % + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" % trình điều khiển"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" % trình điều khiển"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" % trình điều khiển"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" % trình điều khiển"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" % trình điều khiển"); LSTR MSG_DAC_PERCENT_E = _UxGT("E % trình điều khiển"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("Ghi DAC EEPROM"); // DAC EEPROM Write LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("In tạm dừng"); // PRINT PAUSED diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index e641f235e6526..7f0ca874d61eb 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -267,45 +267,45 @@ namespace Language_zh_CN { LSTR MSG_SELECT_E = _UxGT("选择 *"); LSTR MSG_ACC = _UxGT("加速度"); // "Accel" acceleration LSTR MSG_JERK = _UxGT("抖动速率"); // "Jerk" - LSTR MSG_VA_JERK = _UxGT("轴抖动速率") LCD_STR_A; // "Va-jerk" - LSTR MSG_VB_JERK = _UxGT("轴抖动速率") LCD_STR_B; // "Vb-jerk" - LSTR MSG_VC_JERK = _UxGT("轴抖动速率") LCD_STR_C; // "Vc-jerk" - LSTR MSG_VI_JERK = _UxGT("轴抖动速率") LCD_STR_I; // "Vi-jerk" - LSTR MSG_VJ_JERK = _UxGT("轴抖动速率") LCD_STR_J; // "Vj-jerk" - LSTR MSG_VK_JERK = _UxGT("轴抖动速率") LCD_STR_K; // "Vk-jerk" + LSTR MSG_VA_JERK = _UxGT("轴抖动速率") STR_A; // "Va-jerk" + LSTR MSG_VB_JERK = _UxGT("轴抖动速率") STR_B; // "Vb-jerk" + LSTR MSG_VC_JERK = _UxGT("轴抖动速率") STR_C; // "Vc-jerk" + LSTR MSG_VI_JERK = _UxGT("轴抖动速率") STR_I; // "Vi-jerk" + LSTR MSG_VJ_JERK = _UxGT("轴抖动速率") STR_J; // "Vj-jerk" + LSTR MSG_VK_JERK = _UxGT("轴抖动速率") STR_K; // "Vk-jerk" LSTR MSG_VE_JERK = _UxGT("挤出机抖动速率"); // "Ve-jerk" LSTR MSG_JUNCTION_DEVIATION = _UxGT("接点差"); LSTR MSG_VELOCITY = _UxGT("速度"); // "Velocity" - LSTR MSG_VMAX_A = _UxGT("最大进料速率") LCD_STR_A; // "Vmax " max_feedrate_mm_s - LSTR MSG_VMAX_B = _UxGT("最大进料速率") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("最大进料速率") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("最大进料速率") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("最大进料速率") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("最大进料速率") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("最大进料速率") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("最大进料速率") STR_A; // "Vmax " max_feedrate_mm_s + LSTR MSG_VMAX_B = _UxGT("最大进料速率") STR_B; + LSTR MSG_VMAX_C = _UxGT("最大进料速率") STR_C; + LSTR MSG_VMAX_I = _UxGT("最大进料速率") STR_I; + LSTR MSG_VMAX_J = _UxGT("最大进料速率") STR_J; + LSTR MSG_VMAX_K = _UxGT("最大进料速率") STR_K; + LSTR MSG_VMAX_E = _UxGT("最大进料速率") STR_E; LSTR MSG_VMAX_EN = _UxGT("最大进料速率 *"); LSTR MSG_VMIN = _UxGT("最小进料速率"); // "Vmin" min_feedrate_mm_s LSTR MSG_VTRAV_MIN = _UxGT("最小移动速率"); // "VTrav min" min_travel_feedrate_mm_s, (target) speed of the move LSTR MSG_ACCELERATION = _UxGT("加速度"); // "Acceleration" - LSTR MSG_AMAX_A = _UxGT("最大打印加速度") LCD_STR_A; // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves - LSTR MSG_AMAX_B = _UxGT("最大打印加速度") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("最大打印加速度") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("最大打印加速度") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("最大打印加速度") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("最大打印加速度") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("最大打印加速度") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("最大打印加速度") STR_A; // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves + LSTR MSG_AMAX_B = _UxGT("最大打印加速度") STR_B; + LSTR MSG_AMAX_C = _UxGT("最大打印加速度") STR_C; + LSTR MSG_AMAX_I = _UxGT("最大打印加速度") STR_I; + LSTR MSG_AMAX_J = _UxGT("最大打印加速度") STR_J; + LSTR MSG_AMAX_K = _UxGT("最大打印加速度") STR_K; + LSTR MSG_AMAX_E = _UxGT("最大打印加速度") STR_E; LSTR MSG_AMAX_EN = _UxGT("最大打印加速度 *"); LSTR MSG_A_RETRACT = _UxGT("收进加速度"); // "A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts LSTR MSG_A_TRAVEL = _UxGT("非打印移动加速度"); // "A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("频率最大"); LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("进给速度"); LSTR MSG_STEPS_PER_MM = _UxGT("轴步数/mm"); // "Steps/mm" axis_steps_per_mm, axis steps-per-unit G92 - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" 步数/mm"); // "Asteps/mm" - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" 步数/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" 步数/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" 步数/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" 步数/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" 步数/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" 步数/mm"); // "Asteps/mm" + LSTR MSG_B_STEPS = STR_B _UxGT(" 步数/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" 步数/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" 步数/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" 步数/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" 步数/mm"); LSTR MSG_E_STEPS = _UxGT("E 步数/mm"); // "Esteps/mm" LSTR MSG_EN_STEPS = _UxGT("* 步数/mm"); LSTR MSG_TEMPERATURE = _UxGT("温度"); // "Temperature" @@ -507,12 +507,12 @@ namespace Language_zh_CN { LSTR MSG_INFO_MAX_TEMP = _UxGT("最高温度"); // "Max Temp" LSTR MSG_INFO_PSU = _UxGT("电源供应"); // "Power Supply" LSTR MSG_DRIVE_STRENGTH = _UxGT("驱动力度"); // "Drive Strength" - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" 驱动 %"); // "X Driver %" - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" 驱动 %"); - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" 驱动 %"); - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" 驱动 %"); - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" 驱动 %"); - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" 驱动 %"); + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" 驱动 %"); // "X Driver %" + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" 驱动 %"); + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" 驱动 %"); + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" 驱动 %"); + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" 驱动 %"); + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" 驱动 %"); LSTR MSG_DAC_PERCENT_E = _UxGT("E 驱动 %"); // "E Driver %" LSTR MSG_ERROR_TMC = _UxGT("TMC 连接错误"); LSTR MSG_DAC_EEPROM_WRITE = _UxGT("保存驱动设置"); // "DAC EEPROM Write" diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index f168679e4a006..6c91cc1fec25b 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -252,43 +252,43 @@ namespace Language_zh_TW { LSTR MSG_SELECT_E = _UxGT("選擇 *"); LSTR MSG_ACC = _UxGT("加速度"); // "Accel" acceleration LSTR MSG_JERK = _UxGT("抖動速率"); // "Jerk" - LSTR MSG_VA_JERK = _UxGT("軸抖動速率") LCD_STR_A; // "Va-jerk" - LSTR MSG_VB_JERK = _UxGT("軸抖動速率") LCD_STR_B; - LSTR MSG_VC_JERK = _UxGT("軸抖動速率") LCD_STR_C; - LSTR MSG_VI_JERK = _UxGT("軸抖動速率") LCD_STR_I; - LSTR MSG_VJ_JERK = _UxGT("軸抖動速率") LCD_STR_J; - LSTR MSG_VK_JERK = _UxGT("軸抖動速率") LCD_STR_K; + LSTR MSG_VA_JERK = _UxGT("軸抖動速率") STR_A; // "Va-jerk" + LSTR MSG_VB_JERK = _UxGT("軸抖動速率") STR_B; + LSTR MSG_VC_JERK = _UxGT("軸抖動速率") STR_C; + LSTR MSG_VI_JERK = _UxGT("軸抖動速率") STR_I; + LSTR MSG_VJ_JERK = _UxGT("軸抖動速率") STR_J; + LSTR MSG_VK_JERK = _UxGT("軸抖動速率") STR_K; LSTR MSG_VE_JERK = _UxGT("擠出機抖動速率"); LSTR MSG_VELOCITY = _UxGT("速度"); // "Velocity" - LSTR MSG_VMAX_A = _UxGT("最大進料速率") LCD_STR_A; // "Vmax " max_feedrate_mm_s - LSTR MSG_VMAX_B = _UxGT("最大進料速率") LCD_STR_B; - LSTR MSG_VMAX_C = _UxGT("最大進料速率") LCD_STR_C; - LSTR MSG_VMAX_I = _UxGT("最大進料速率") LCD_STR_I; - LSTR MSG_VMAX_J = _UxGT("最大進料速率") LCD_STR_J; - LSTR MSG_VMAX_K = _UxGT("最大進料速率") LCD_STR_K; - LSTR MSG_VMAX_E = _UxGT("最大進料速率") LCD_STR_E; + LSTR MSG_VMAX_A = _UxGT("最大進料速率") STR_A; // "Vmax " max_feedrate_mm_s + LSTR MSG_VMAX_B = _UxGT("最大進料速率") STR_B; + LSTR MSG_VMAX_C = _UxGT("最大進料速率") STR_C; + LSTR MSG_VMAX_I = _UxGT("最大進料速率") STR_I; + LSTR MSG_VMAX_J = _UxGT("最大進料速率") STR_J; + LSTR MSG_VMAX_K = _UxGT("最大進料速率") STR_K; + LSTR MSG_VMAX_E = _UxGT("最大進料速率") STR_E; LSTR MSG_VMAX_EN = _UxGT("最大進料速率 *"); // "Vmax " max_feedrate_mm_s LSTR MSG_VMIN = _UxGT("最小進料速率"); // "Vmin" min_feedrate_mm_s LSTR MSG_VTRAV_MIN = _UxGT("最小移動速率"); // "VTrav min" min_travel_feedrate_mm_s, (target) speed of the move LSTR MSG_ACCELERATION = _UxGT("加速度"); // "Acceleration" - LSTR MSG_AMAX_A = _UxGT("最大列印加速度") LCD_STR_A; // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves - LSTR MSG_AMAX_B = _UxGT("最大列印加速度") LCD_STR_B; - LSTR MSG_AMAX_C = _UxGT("最大列印加速度") LCD_STR_C; - LSTR MSG_AMAX_I = _UxGT("最大列印加速度") LCD_STR_I; - LSTR MSG_AMAX_J = _UxGT("最大列印加速度") LCD_STR_J; - LSTR MSG_AMAX_K = _UxGT("最大列印加速度") LCD_STR_K; - LSTR MSG_AMAX_E = _UxGT("最大列印加速度") LCD_STR_E; + LSTR MSG_AMAX_A = _UxGT("最大列印加速度") STR_A; // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves + LSTR MSG_AMAX_B = _UxGT("最大列印加速度") STR_B; + LSTR MSG_AMAX_C = _UxGT("最大列印加速度") STR_C; + LSTR MSG_AMAX_I = _UxGT("最大列印加速度") STR_I; + LSTR MSG_AMAX_J = _UxGT("最大列印加速度") STR_J; + LSTR MSG_AMAX_K = _UxGT("最大列印加速度") STR_K; + LSTR MSG_AMAX_E = _UxGT("最大列印加速度") STR_E; LSTR MSG_AMAX_EN = _UxGT("最大列印加速度 *"); // "Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves LSTR MSG_A_RETRACT = _UxGT("回縮加速度"); // "A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts LSTR MSG_A_TRAVEL = _UxGT("非列印移動加速度"); // "A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves LSTR MSG_STEPS_PER_MM = _UxGT("軸步數/mm"); // "Steps/mm" axis_steps_per_mm, axis steps-per-unit G92 - LSTR MSG_A_STEPS = LCD_STR_A _UxGT(" 軸步數/mm"); // "Asteps/mm" axis_steps_per_mm, axis steps-per-unit G92 - LSTR MSG_B_STEPS = LCD_STR_B _UxGT(" 軸步數/mm"); - LSTR MSG_C_STEPS = LCD_STR_C _UxGT(" 軸步數/mm"); - LSTR MSG_I_STEPS = LCD_STR_I _UxGT(" 軸步數/mm"); - LSTR MSG_J_STEPS = LCD_STR_J _UxGT(" 軸步數/mm"); - LSTR MSG_K_STEPS = LCD_STR_K _UxGT(" 軸步數/mm"); + LSTR MSG_A_STEPS = STR_A _UxGT(" 軸步數/mm"); // "Asteps/mm" axis_steps_per_mm, axis steps-per-unit G92 + LSTR MSG_B_STEPS = STR_B _UxGT(" 軸步數/mm"); + LSTR MSG_C_STEPS = STR_C _UxGT(" 軸步數/mm"); + LSTR MSG_I_STEPS = STR_I _UxGT(" 軸步數/mm"); + LSTR MSG_J_STEPS = STR_J _UxGT(" 軸步數/mm"); + LSTR MSG_K_STEPS = STR_K _UxGT(" 軸步數/mm"); LSTR MSG_E_STEPS = _UxGT("擠出機步數/mm"); // "Esteps/mm" LSTR MSG_EN_STEPS = _UxGT("擠出機~步數/mm"); LSTR MSG_TEMPERATURE = _UxGT("溫度"); // "Temperature" @@ -455,12 +455,12 @@ namespace Language_zh_TW { LSTR MSG_INFO_MAX_TEMP = _UxGT("最高溫度"); // "Max Temp" LSTR MSG_INFO_PSU = _UxGT("電源供應"); // "Power Supply" LSTR MSG_DRIVE_STRENGTH = _UxGT("驅動力度"); // "Drive Strength" - LSTR MSG_DAC_PERCENT_A = LCD_STR_A _UxGT(" 驅動 %"); // X Driver % - LSTR MSG_DAC_PERCENT_B = LCD_STR_B _UxGT(" 驅動 %"); // Y Driver % - LSTR MSG_DAC_PERCENT_C = LCD_STR_C _UxGT(" 驅動 %"); // Z Driver % - LSTR MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" 驅動 %"); // I Driver % - LSTR MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" 驅動 %"); // J Driver % - LSTR MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" 驅動 %"); // K Driver % + LSTR MSG_DAC_PERCENT_A = STR_A _UxGT(" 驅動 %"); // X Driver % + LSTR MSG_DAC_PERCENT_B = STR_B _UxGT(" 驅動 %"); // Y Driver % + LSTR MSG_DAC_PERCENT_C = STR_C _UxGT(" 驅動 %"); // Z Driver % + LSTR MSG_DAC_PERCENT_I = STR_I _UxGT(" 驅動 %"); // I Driver % + LSTR MSG_DAC_PERCENT_J = STR_J _UxGT(" 驅動 %"); // J Driver % + LSTR MSG_DAC_PERCENT_K = STR_K _UxGT(" 驅動 %"); // K Driver % LSTR MSG_DAC_PERCENT_E = _UxGT("E 驅動 %"); //E Driver % LSTR MSG_ERROR_TMC = _UxGT("TMC連接錯誤"); // "TMC CONNECTION ERROR" LSTR MSG_DAC_EEPROM_WRITE = _UxGT("保存驅動設置"); // "DAC EEPROM Write" diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index a5b4455d6f6d9..5a1cedfbac951 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -84,10 +84,10 @@ void menu_backlash(); BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_CURRENT_PWM(LABEL,I) EDIT_ITEM_P(long5, PSTR(LABEL), &stepper.motor_current_setting[I], 100, 2000, stepper.refresh_motor_power) #if ANY_PIN(MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y) - EDIT_CURRENT_PWM(STR_X STR_Y, 0); + EDIT_CURRENT_PWM(STR_A STR_B, 0); #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) - EDIT_CURRENT_PWM(STR_Z, 1); + EDIT_CURRENT_PWM(STR_C, 1); #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) EDIT_CURRENT_PWM(STR_E, 2); diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index 388aebb744696..11027e7f95737 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -103,7 +103,7 @@ void menu_info_thermistors() { #if HAS_EXTRUDERS #define THERMISTOR_ID TEMP_SENSOR_0 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(LCD_STR_E0 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_P(PSTR(STR_E0 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_0_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_0_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -113,7 +113,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_1 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(LCD_STR_E1 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_P(PSTR(STR_E1 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_1_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_1_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -123,7 +123,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_2 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(LCD_STR_E2 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_P(PSTR(STR_E2 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_2_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_2_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -133,7 +133,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_3 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(LCD_STR_E3 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_P(PSTR(STR_E3 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_3_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_3_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -143,7 +143,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_4 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(LCD_STR_E4 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_P(PSTR(STR_E4 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_4_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_4_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -153,7 +153,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_5 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(LCD_STR_E5 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_P(PSTR(STR_E5 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_5_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_5_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -163,7 +163,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_6 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(LCD_STR_E6 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_P(PSTR(STR_E6 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_6_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_6_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -173,7 +173,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_7 #include "../thermistornames.h" - STATIC_ITEM_P(PSTR(LCD_STR_E7 ": " THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_P(PSTR(STR_E7 ": " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(HEATER_7_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(HEATER_7_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_HOTENDS, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 344b94e2e9ba1..d463436021652 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -346,13 +346,13 @@ void menu_move() { GCODES_ITEM_N(Z_AXIS, MSG_AUTO_HOME_A, PSTR("G28Z")); #endif #if HAS_I_AXIS - GCODES_ITEM_N(I_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS4_STR)); + GCODES_ITEM_N(I_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_I)); #endif #if HAS_J_AXIS - GCODES_ITEM_N(J_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS5_STR)); + GCODES_ITEM_N(J_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_J)); #endif #if HAS_K_AXIS - GCODES_ITEM_N(K_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS6_STR)); + GCODES_ITEM_N(K_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_K)); #endif END_MENU(); @@ -399,13 +399,13 @@ void menu_motion() { GCODES_ITEM_N(Z_AXIS, MSG_AUTO_HOME_A, PSTR("G28Z")); #endif #if HAS_I_AXIS - GCODES_ITEM_N(I_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS4_STR)); + GCODES_ITEM_N(I_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_I)); #endif #if HAS_J_AXIS - GCODES_ITEM_N(J_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS5_STR)); + GCODES_ITEM_N(J_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_J)); #endif #if HAS_K_AXIS - GCODES_ITEM_N(K_AXIS, MSG_AUTO_HOME_A, PSTR("G28" AXIS6_STR)); + GCODES_ITEM_N(K_AXIS, MSG_AUTO_HOME_A, PSTR("G28" STR_K)); #endif #endif #endif diff --git a/Marlin/src/lcd/menu/menu_tmc.cpp b/Marlin/src/lcd/menu/menu_tmc.cpp index ad7d632058797..be6289d851a36 100644 --- a/Marlin/src/lcd/menu/menu_tmc.cpp +++ b/Marlin/src/lcd/menu/menu_tmc.cpp @@ -38,13 +38,13 @@ void menu_tmc_current() { START_MENU(); BACK_ITEM(MSG_TMC_DRIVERS); #if AXIS_IS_TMC(X) - TMC_EDIT_STORED_I_RMS(X, STR_X); + TMC_EDIT_STORED_I_RMS(X, STR_A); #endif #if AXIS_IS_TMC(Y) - TMC_EDIT_STORED_I_RMS(Y, STR_Y); + TMC_EDIT_STORED_I_RMS(Y, STR_B); #endif #if AXIS_IS_TMC(Z) - TMC_EDIT_STORED_I_RMS(Z, STR_Z); + TMC_EDIT_STORED_I_RMS(Z, STR_C); #endif #if AXIS_IS_TMC(X2) TMC_EDIT_STORED_I_RMS(X2, STR_X2); @@ -62,28 +62,28 @@ void menu_tmc_current() { TMC_EDIT_STORED_I_RMS(Z4, STR_Z4); #endif #if AXIS_IS_TMC(E0) - TMC_EDIT_STORED_I_RMS(E0, LCD_STR_E0); + TMC_EDIT_STORED_I_RMS(E0, STR_E0); #endif #if AXIS_IS_TMC(E1) - TMC_EDIT_STORED_I_RMS(E1, LCD_STR_E1); + TMC_EDIT_STORED_I_RMS(E1, STR_E1); #endif #if AXIS_IS_TMC(E2) - TMC_EDIT_STORED_I_RMS(E2, LCD_STR_E2); + TMC_EDIT_STORED_I_RMS(E2, STR_E2); #endif #if AXIS_IS_TMC(E3) - TMC_EDIT_STORED_I_RMS(E3, LCD_STR_E3); + TMC_EDIT_STORED_I_RMS(E3, STR_E3); #endif #if AXIS_IS_TMC(E4) - TMC_EDIT_STORED_I_RMS(E4, LCD_STR_E4); + TMC_EDIT_STORED_I_RMS(E4, STR_E4); #endif #if AXIS_IS_TMC(E5) - TMC_EDIT_STORED_I_RMS(E5, LCD_STR_E5); + TMC_EDIT_STORED_I_RMS(E5, STR_E5); #endif #if AXIS_IS_TMC(E6) - TMC_EDIT_STORED_I_RMS(E6, LCD_STR_E6); + TMC_EDIT_STORED_I_RMS(E6, STR_E6); #endif #if AXIS_IS_TMC(E7) - TMC_EDIT_STORED_I_RMS(E7, LCD_STR_E7); + TMC_EDIT_STORED_I_RMS(E7, STR_E7); #endif END_MENU(); } @@ -103,14 +103,14 @@ void menu_tmc_current() { TERN_(Z2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z2, STR_Z2)); TERN_(Z3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z3, STR_Z3)); TERN_(Z4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z4, STR_Z4)); - TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0)); - TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E1, LCD_STR_E1)); - TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E2, LCD_STR_E2)); - TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E3, LCD_STR_E3)); - TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E4, LCD_STR_E4)); - TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E5, LCD_STR_E5)); - TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E6, LCD_STR_E6)); - TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E7, LCD_STR_E7)); + TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E0, STR_E0)); + TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E1, STR_E1)); + TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E2, STR_E2)); + TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E3, STR_E3)); + TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E4, STR_E4)); + TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E5, STR_E5)); + TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E6, STR_E6)); + TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E7, STR_E7)); END_MENU(); } @@ -155,14 +155,14 @@ void menu_tmc_current() { TERN_(Z2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z2, STR_Z2)); TERN_(Z3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z3, STR_Z3)); TERN_(Z4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z4, STR_Z4)); - TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E0, LCD_STR_E0)); - TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E1, LCD_STR_E1)); - TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E2, LCD_STR_E2)); - TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E3, LCD_STR_E3)); - TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E4, LCD_STR_E4)); - TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E5, LCD_STR_E5)); - TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E6, LCD_STR_E6)); - TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E7, LCD_STR_E7)); + TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E0, STR_E0)); + TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E1, STR_E1)); + TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E2, STR_E2)); + TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E3, STR_E3)); + TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E4, STR_E4)); + TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E5, STR_E5)); + TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E6, STR_E6)); + TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E7, STR_E7)); END_MENU(); } diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp index dea2e3fc2d4c2..a8c2695630d61 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp @@ -39,7 +39,7 @@ L64XX_Marlin L64xxManager; static const char LINEAR_AXIS_LIST( str_X[] PROGMEM = "X ", str_Y[] PROGMEM = "Y ", str_Z[] PROGMEM = "Z ", - str_I[] PROGMEM = AXIS4_STR " ", str_J[] PROGMEM = AXIS5_STR " ", str_K[] PROGMEM = AXIS6_STR " " + str_I[] PROGMEM = STR_I " ", str_J[] PROGMEM = STR_J " ", str_K[] PROGMEM = STR_K " " ), str_X2[] PROGMEM = "X2", str_Y2[] PROGMEM = "Y2", str_Z2[] PROGMEM = "Z2", str_Z3[] PROGMEM = "Z3", str_Z4[] PROGMEM = "Z4", diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 23084c48fbcb3..be08ba6ef011a 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1317,9 +1317,9 @@ void prepare_line_to_destination() { TEST(axis_bits, X_AXIS) ? "X" : "", TEST(axis_bits, Y_AXIS) ? "Y" : "", TEST(axis_bits, Z_AXIS) ? "Z" : "", - TEST(axis_bits, I_AXIS) ? AXIS4_STR : "", - TEST(axis_bits, J_AXIS) ? AXIS5_STR : "", - TEST(axis_bits, K_AXIS) ? AXIS6_STR : "" + TEST(axis_bits, I_AXIS) ? STR_I : "", + TEST(axis_bits, J_AXIS) ? STR_J : "", + TEST(axis_bits, K_AXIS) ? STR_K : "" ) ); SERIAL_ECHO_START(); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 4c86c06efe6fb..17d279cfa5f91 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1867,13 +1867,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move, " B:", target.b, " (", db, " steps)" " C:", target.c, " (", dc, " steps)" #if HAS_I_AXIS - " " AXIS4_STR ":", target.i, " (", di, " steps)" + " " STR_I ":", target.i, " (", di, " steps)" #endif #if HAS_J_AXIS - " " AXIS5_STR ":", target.j, " (", dj, " steps)" + " " STR_J ":", target.j, " (", dj, " steps)" #endif #if HAS_K_AXIS - " " AXIS6_STR ":", target.k, " (", dk, " steps)" + " " STR_K ":", target.k, " (", dk, " steps)" #endif #if HAS_EXTRUDERS " E:", target.e, " (", de, " steps)" diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index f7d53b6da7c37..c3cd4f10d67f2 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -219,8 +219,8 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #else #define _COOLER_FSTR(h) #endif -#define _E_FSTR(h,N) ((HOTENDS) > N && (h) == N) ? F(LCD_STR_E##N) : -#define HEATER_FSTR(h) _BED_FSTR(h) _CHAMBER_FSTR(h) _COOLER_FSTR(h) _E_FSTR(h,1) _E_FSTR(h,2) _E_FSTR(h,3) _E_FSTR(h,4) _E_FSTR(h,5) F(LCD_STR_E0) +#define _E_FSTR(h,N) ((HOTENDS) > N && (h) == N) ? F(STR_E##N) : +#define HEATER_FSTR(h) _BED_FSTR(h) _CHAMBER_FSTR(h) _COOLER_FSTR(h) _E_FSTR(h,1) _E_FSTR(h,2) _E_FSTR(h,3) _E_FSTR(h,4) _E_FSTR(h,5) _E_FSTR(h,6) _E_FSTR(h,7) F(STR_E0) // // Initialize MAX TC objects/SPI From 08b659747191d3b234c39e81546d845d31d49852 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 10 Jan 2022 04:49:03 -0600 Subject: [PATCH 271/273] =?UTF-8?q?=F0=9F=8E=A8=20Followup=20to=20#23462?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/scripts/upload.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/buildroot/share/scripts/upload.py b/buildroot/share/scripts/upload.py index 4a152067a4a28..bfce4ea49dfd0 100644 --- a/buildroot/share/scripts/upload.py +++ b/buildroot/share/scripts/upload.py @@ -14,7 +14,7 @@ # # 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")) @@ -92,7 +92,7 @@ def _GetFirmwareFiles(): raise Exception('Error getting firmware files') if Debug: print('OK') return Responses - + def _FilterFirmwareFiles(FirmwareList): Firmwares = [] for FWFile in FirmwareList: @@ -185,7 +185,7 @@ def _RemoveFirmwareFile(FirmwareFile): if not marlin_custom_firmware_upload: raise Exception(f"CUSTOM_FIRMWARE_UPLOAD must be enabled in 'Configuration_adv.h' for '{marlin_motherboard}'") - # Generate a new 8.3 random filename + # Generate a new 8.3 random filename # This board remember the last firmware filename and doesn't allow to flash from that filename upload_firmware_target_name = f"fw-{''.join(random.choices('ABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789', k=5))}.BIN" print(f"Board {marlin_motherboard}: Overriding firmware filename to '{upload_firmware_target_name}'") @@ -196,13 +196,13 @@ def _RemoveFirmwareFile(FirmwareFile): # Check SD card status _CheckSDCard() - + # Get firmware files FirmwareFiles = _GetFirmwareFiles() if Debug: for FirmwareFile in FirmwareFiles: print(f'Found: {FirmwareFile}') - + # Get all 1st level firmware files (to remove) OldFirmwareFiles = _FilterFirmwareFiles(FirmwareFiles[1:len(FirmwareFiles)-2]) # Skip header and footers of list if len(OldFirmwareFiles) == 0: @@ -220,7 +220,7 @@ def _RemoveFirmwareFile(FirmwareFile): if Debug: print('Cleanup completed') # WARNING! The serial port must be closed here because the serial transfer that follow needs it! - + # Upload firmware file if Debug: print(f"Copy '{upload_firmware_source_name}' --> '{upload_firmware_target_name}'") protocol = MarlinBinaryProtocol.Protocol(upload_port, upload_speed, upload_blocksize, float(upload_error_ratio), int(upload_timeout)) From 224b6e5af9250e92671ad3ee35bb10cd79b819ef Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 10 Jan 2022 05:34:16 -0600 Subject: [PATCH 272/273] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20some=20logical=20a?= =?UTF-8?q?xis=20usage?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/pause/G60.cpp | 9 ++++++--- Marlin/src/lcd/marlinui.cpp | 2 +- Marlin/src/module/motion.cpp | 6 ++++-- 3 files changed, 11 insertions(+), 6 deletions(-) diff --git a/Marlin/src/gcode/feature/pause/G60.cpp b/Marlin/src/gcode/feature/pause/G60.cpp index 4c7190091cfc1..d4770577a65f5 100644 --- a/Marlin/src/gcode/feature/pause/G60.cpp +++ b/Marlin/src/gcode/feature/pause/G60.cpp @@ -47,13 +47,16 @@ void GcodeSuite::G60() { SBI(saved_slots[slot >> 3], slot & 0x07); #if ENABLED(SAVED_POSITIONS_DEBUG) + { DEBUG_ECHOPGM(STR_SAVED_POS " S", slot); const xyze_pos_t &pos = stored_position[slot]; DEBUG_ECHOLNPAIR_F_P( - LIST_N(DOUBLE(LOGICAL_AXES), SP_E_STR, pos.e, - PSTR(" : X"), pos.x, SP_Y_STR, pos.y, SP_Z_STR, pos.z, - SP_I_STR, pos.i, SP_J_STR, pos.j, SP_K_STR, pos.k) + LIST_N(DOUBLE(LINEAR_AXES), PSTR(" : X"), pos.x, SP_Y_STR, pos.y, SP_Z_STR, pos.z, SP_I_STR, pos.i, SP_J_STR, pos.j, SP_K_STR, pos.k) + #if HAS_EXTRUDERS + , SP_E_STR, pos.e + #endif ); + } #endif } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 7b3e267310fb2..ab132216c8884 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -771,7 +771,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; // Add a manual move to the queue? if (axis != NO_AXIS_ENUM && ELAPSED(millis(), start_time) && !planner.is_full()) { - const feedRate_t fr_mm_s = (axis <= LOGICAL_AXES) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S; + const feedRate_t fr_mm_s = (axis < LOGICAL_AXES) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S; #if IS_KINEMATIC diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index be08ba6ef011a..a9c2ad6a7a7ac 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -265,8 +265,7 @@ void report_current_position_projected() { const xyz_pos_t lpos = cartes.asLogical(); SERIAL_ECHOPGM_P( - LIST_N(DOUBLE(LOGICAL_AXES), - SP_E_LBL, current_position.e, + LIST_N(DOUBLE(LINEAR_AXES), X_LBL, lpos.x, SP_Y_LBL, lpos.y, SP_Z_LBL, lpos.z, @@ -274,6 +273,9 @@ void report_current_position_projected() { SP_J_LBL, lpos.j, SP_K_LBL, lpos.k ) + #if HAS_EXTRUDERS + , SP_E_LBL, current_position.e + #endif ); stepper.report_positions(); From cc92a7aa3ae53695616f79229f3a78e439d1f9fd Mon Sep 17 00:00:00 2001 From: mistic100 Date: Sat, 8 Jan 2022 10:51:21 +0100 Subject: [PATCH 273/273] =?UTF-8?q?=F0=9F=9A=B8=20Wait=20for=20cooldown=20?= =?UTF-8?q?in=20MarlinUI=20power-off=20(#23476)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/marlinui.cpp | 8 +++++--- Marlin/src/lcd/marlinui.h | 2 +- Marlin/src/lcd/menu/menu_main.cpp | 2 +- 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index ab132216c8884..d22b11f9bd801 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1553,11 +1553,13 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; TERN_(HAS_LCD_MENU, return_to_status()); } - #if BOTH(PSU_CONTROL, PS_OFF_CONFIRM) + #if BOTH(HAS_LCD_MENU, PSU_CONTROL) + void MarlinUI::poweroff() { - queue.inject(F("M81")); - goto_previous_screen(); + queue.inject(F("M81" TERN_(POWER_OFF_WAIT_FOR_COOLDOWN, "S"))); + return_to_status(); } + #endif void MarlinUI::flow_fault() { diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index f409970e42a79..4d590cfbd387d 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -373,7 +373,7 @@ class MarlinUI { static void resume_print(); static void flow_fault(); - #if BOTH(PSU_CONTROL, PS_OFF_CONFIRM) + #if BOTH(HAS_MENU, PSU_CONTROL) static void poweroff(); #endif diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 6e66188c02ce0..f7e974a8649b5 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -380,7 +380,7 @@ void menu_main() { GET_TEXT(MSG_SWITCH_PS_OFF), (const char *)nullptr, PSTR("?") ); #else - GCODES_ITEM(MSG_SWITCH_PS_OFF, PSTR("M81")); + ACTION_ITEM(MSG_SWITCH_PS_OFF, ui.poweroff); #endif else GCODES_ITEM(MSG_SWITCH_PS_ON, PSTR("M80"));