diff --git a/.editorconfig b/.editorconfig index 57a5b2fb5ea4..1037e74ef3ec 100644 --- a/.editorconfig +++ b/.editorconfig @@ -1,19 +1,29 @@ # editorconfig.org root = true +[*] +trim_trailing_whitespace = true +insert_final_newline = true + [{*.patch,syntax_test_*}] trim_trailing_whitespace = false +[{*.c,*.cpp,*.h,*.ino,*.py,Makefile}] +end_of_line = lf + [{*.c,*.cpp,*.h,*.ino}] charset = utf-8 - -[{*.c,*.cpp,*.h,*.ino,Makefile}] -trim_trailing_whitespace = true -insert_final_newline = true -end_of_line = lf indent_style = space indent_size = 2 +[{Makefile}] +indent_style = tab +indent_size = 2 + +[*.md] +# Two spaces at the end of the line means newline in Markdown +trim_trailing_whitespace = false + [{*.py}] indent_style = space indent_size = 4 diff --git a/.github/code_of_conduct.md b/.github/code_of_conduct.md index 854fed4ec458..5fd9e0c8eeb5 100644 --- a/.github/code_of_conduct.md +++ b/.github/code_of_conduct.md @@ -28,15 +28,9 @@ Project maintainers are responsible for clarifying the standards of acceptable b Project maintainers have the right and responsibility to remove, edit, or reject comments, commits, code, issues, and other contributions that are not aligned to this Code of Conduct, or to ban temporarily or permanently any contributor for other behaviors that they deem inappropriate, threatening, offensive, or harmful. -## Scope - -This Code of Conduct applies both within project spaces and in public spaces when an individual is representing the project or its community. Examples of representing a project or community include using an official project e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event. Representation of a project may be further defined and clarified by project maintainers. - ## Enforcement -Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by contacting the project team at [marlinfirmware@github.com](mailto:marlinfirmware@github.com). All complaints will be reviewed and investigated and will result in a response that is deemed necessary and appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. Further details of specific enforcement policies may be posted separately. - -Project maintainers who do not follow or enforce the Code of Conduct in good faith may face temporary or permanent repercussions as determined by other members of the project's leadership. +Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by following GitHub's [reporting abuse or spam article](https://docs.github.com/en/communities/maintaining-your-safety-on-github/reporting-abuse-or-spam). All complaints will be reviewed and investigated and will result in a response that is deemed necessary and appropriate to the circumstances. ## Attribution diff --git a/.github/contributing.md b/.github/contributing.md index ef1726366a7d..c9b31998e99d 100644 --- a/.github/contributing.md +++ b/.github/contributing.md @@ -26,11 +26,12 @@ The following is a set of guidelines for contributing to Marlin, hosted by the [ ## Code of Conduct -This project and everyone participating in it is governed by the [Marlin Code of Conduct](code_of_conduct.md). By participating, you are expected to uphold this code. Please report unacceptable behavior to [marlinfirmware@github.com](mailto:marlinfirmware@github.com). +This project and everyone participating in it is governed by the [Marlin Code of Conduct](code_of_conduct.md). By participating, you are expected to uphold this code. Please report unacceptable behavior by following GitHub's [reporting abuse or spam article](https://docs.github.com/en/communities/maintaining-your-safety-on-github/reporting-abuse-or-spam). ## I don't want to read this whole thing I just have a question!!! -> **Note:** Please don't file an issue to ask a question. You'll get faster results by using the resources below. +> [!NOTE] +> Please don't file an issue to ask a question. You'll get faster results by using the resources below. We have a Message Board and a Facebook group where our knowledgable user community can provide helpful advice if you have questions. @@ -55,7 +56,8 @@ This section guides you through submitting a Bug Report for Marlin. Following th Before creating a Bug Report, please test the "nightly" development branch, as you might find out that you don't need to create one. When you are creating a Bug Report, please [include as many details as possible](#how-do-i-submit-a-good-bug-report). Fill out [the required template](ISSUE_TEMPLATE/bug_report.yml), the information it asks for helps us resolve issues faster. -> **Note:** Regressions can happen. If you find a **Closed** issue that seems like your issue, go ahead and open a new issue and include a link to the original issue in the body of your new one. All you need to create a link is the issue number, preceded by #. For example, #8888. +> [!NOTE] +> Regressions can happen. If you find a **Closed** issue that seems like your issue, go ahead and open a new issue and include a link to the original issue in the body of your new one. All you need to create a link is the issue number, preceded by #. For example, #8888. #### How Do I Submit A (Good) Bug Report? diff --git a/.gitignore b/.gitignore index a7f8a091aa4a..c7d47c607fd1 100755 --- a/.gitignore +++ b/.gitignore @@ -25,6 +25,9 @@ bdf2u8g.exe genpages.exe marlin_config.json mczip.h +language*.csv +out-csv/ +out-language/ *.gen *.sublime-workspace @@ -130,7 +133,9 @@ spi_flash.bin fs.img # CMake +buildroot/share/cmake/* CMakeLists.txt +!buildroot/share/cmake/CMakeLists.txt src/CMakeLists.txt CMakeListsPrivate.txt build/ diff --git a/.vscode/extensions.json b/.vscode/extensions.json index f495d14f53e8..52fe2a0bdbff 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -6,6 +6,7 @@ "platformio.platformio-ide" ], "unwantedRecommendations": [ + "ms-vscode-remote.remote-containers", "ms-vscode.cpptools-extension-pack" ] } diff --git a/Makefile b/Makefile index 2a18c0b4e829..bc26173aaf36 100644 --- a/Makefile +++ b/Makefile @@ -5,12 +5,14 @@ CONTAINER_IMAGE := marlin-dev help: @echo "Tasks for local development:" - @echo "* tests-single-ci: Run a single test from inside the CI" - @echo "* tests-single-local: Run a single test locally" - @echo "* tests-single-local-docker: Run a single test locally, using docker" - @echo "* tests-all-local: Run all tests locally" - @echo "* tests-all-local-docker: Run all tests locally, using docker" - @echo "* setup-local-docker: Build the local docker image" + @echo "make marlin : Build marlin for the configured board" + @echo "make format-pins : Reformat all pins files" + @echo "make tests-single-ci : Run a single test from inside the CI" + @echo "make tests-single-local : Run a single test locally" + @echo "make tests-single-local-docker : Run a single test locally, using docker" + @echo "make tests-all-local : Run all tests locally" + @echo "make tests-all-local-docker : Run all tests locally, using docker" + @echo "make setup-local-docker : Build the local docker image" @echo "" @echo "Options for testing:" @echo " TEST_TARGET Set when running tests-single-*, to select the" @@ -23,37 +25,41 @@ help: @echo " VERBOSE_PLATFORMIO If you want the full PIO output, set any value" @echo " GIT_RESET_HARD Used by CI: reset all local changes. WARNING:" @echo " THIS WILL UNDO ANY CHANGES YOU'VE MADE!" -.PHONY: help + +marlin: + ./buildroot/bin/mftest -a +.PHONY: marlin tests-single-ci: export GIT_RESET_HARD=true - $(MAKE) tests-single-local TEST_TARGET=$(TEST_TARGET) -.PHONY: tests-single-ci + $(MAKE) tests-single-local TEST_TARGET=$(TEST_TARGET) PLATFORMIO_BUILD_FLAGS=-DGITHUB_ACTION tests-single-local: @if ! test -n "$(TEST_TARGET)" ; then echo "***ERROR*** Set TEST_TARGET= or use make tests-all-local" ; return 1; fi export PATH="./buildroot/bin/:./buildroot/tests/:${PATH}" \ && export VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) \ && run_tests . $(TEST_TARGET) "$(ONLY_TEST)" -.PHONY: tests-single-local tests-single-local-docker: @if ! test -n "$(TEST_TARGET)" ; then echo "***ERROR*** Set TEST_TARGET= or use make tests-all-local-docker" ; return 1; fi @if ! $(CONTAINER_RT_BIN) images -q $(CONTAINER_IMAGE) > /dev/null ; then $(MAKE) setup-local-docker ; fi $(CONTAINER_RT_BIN) run $(CONTAINER_RT_OPTS) $(CONTAINER_IMAGE) $(MAKE) tests-single-local TEST_TARGET=$(TEST_TARGET) VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) GIT_RESET_HARD=$(GIT_RESET_HARD) ONLY_TEST="$(ONLY_TEST)" -.PHONY: tests-single-local-docker tests-all-local: export PATH="./buildroot/bin/:./buildroot/tests/:${PATH}" \ && export VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) \ && for TEST_TARGET in $$($(SCRIPTS_DIR)/get_test_targets.py) ; do echo "Running tests for $$TEST_TARGET" ; run_tests . $$TEST_TARGET ; done -.PHONY: tests-all-local tests-all-local-docker: @if ! $(CONTAINER_RT_BIN) images -q $(CONTAINER_IMAGE) > /dev/null ; then $(MAKE) setup-local-docker ; fi $(CONTAINER_RT_BIN) run $(CONTAINER_RT_OPTS) $(CONTAINER_IMAGE) $(MAKE) tests-all-local VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) GIT_RESET_HARD=$(GIT_RESET_HARD) -.PHONY: tests-all-local-docker setup-local-docker: $(CONTAINER_RT_BIN) build -t $(CONTAINER_IMAGE) -f docker/Dockerfile . -.PHONY: setup-local-docker + +PINS := $(shell find Marlin/src/pins -mindepth 2 -name '*.h') + +$(PINS): %: + @echo "Formatting $@" && node $(SCRIPTS_DIR)/pinsformat.js $@ + +format-pins: $(PINS) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 43de00b34920..4d63360de5d0 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -44,7 +44,7 @@ * * Advanced settings can be found in Configuration_adv.h */ -#define CONFIGURATION_H_VERSION 02010201 +#define CONFIGURATION_H_VERSION 02010202 //=========================================================================== //============================= Getting Started ============================= @@ -55,12 +55,13 @@ * * Example Configs: https://github.com/MarlinFirmware/Configurations/branches/all * - * Průša Calculator: https://blog.prusaprinters.org/calculator_3416/ + * Průša Calculator: https://blog.prusa3d.com/calculator_3416/ * * Calibration Guides: https://reprap.org/wiki/Calibration * https://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide - * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap + * https://web.archive.org/web/20220907014303/https://sites.google.com/site/repraplogphase/calibration-of-your-reprap * https://youtu.be/wAL9d7FgInk + * https://teachingtechyt.github.io/calibration.html * * Calibration Objects: https://www.thingiverse.com/thing:5573 * https://www.thingiverse.com/thing:1278865 @@ -266,7 +267,8 @@ #if ENABLED(SWITCHING_NOZZLE) #define SWITCHING_NOZZLE_SERVO_NR 0 //#define SWITCHING_NOZZLE_E1_SERVO_NR 1 // If two servos are used, the index of the second - #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 (single servo) or lowered/raised (dual servo) + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // A pair of angles for { E0, E1 }. + // For Dual Servo use two pairs: { { lower, raise }, { lower, raise } } #define SWITCHING_NOZZLE_SERVO_DWELL 2500 // Dwell time to wait for servo to make physical move #endif @@ -431,11 +433,11 @@ //#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin #if ENABLED(AUTO_POWER_CONTROL) - #define AUTO_POWER_FANS // Turn on PSU if fans need power - #define AUTO_POWER_E_FANS - #define AUTO_POWER_CONTROLLERFAN - #define AUTO_POWER_CHAMBER_FAN - #define AUTO_POWER_COOLER_FAN + #define AUTO_POWER_FANS // Turn on PSU for fans + #define AUTO_POWER_E_FANS // Turn on PSU for E Fans + #define AUTO_POWER_CONTROLLERFAN // Turn on PSU for Controller Fan + #define AUTO_POWER_CHAMBER_FAN // Turn on PSU for Chamber Fan + #define AUTO_POWER_COOLER_FAN // Turn on PSU for Cooler Fan #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 @@ -452,78 +454,70 @@ // @section temperature /** - * --NORMAL IS 4.7kΩ PULLUP!-- 1kΩ pullup can be used on hotend sensor, using correct resistor and table + * Temperature Sensors: * - * Temperature sensors available: - * - * SPI RTD/Thermocouple Boards - IMPORTANT: Read the NOTE below! - * ------- - * -5 : MAX31865 with Pt100/Pt1000, 2, 3, or 4-wire (only for sensors 0-1) - * NOTE: You must uncomment/set the MAX31865_*_OHMS_n defines below. - * -3 : MAX31855 with Thermocouple, -200°C to +700°C (only for sensors 0-1) - * -2 : MAX6675 with Thermocouple, 0°C to +700°C (only for sensors 0-1) - * - * NOTE: Ensure TEMP_n_CS_PIN is set in your pins file for each TEMP_SENSOR_n using an SPI Thermocouple. By default, - * Hardware SPI on the default serial bus is used. If you have also set TEMP_n_SCK_PIN and TEMP_n_MISO_PIN, - * Software SPI will be used on those ports instead. You can force Hardware SPI on the default bus in the - * Configuration_adv.h file. At this time, separate Hardware SPI buses for sensors are not supported. - * - * Analog Themocouple Boards - * ------- - * -4 : AD8495 with Thermocouple - * -1 : AD595 with Thermocouple + * NORMAL IS 4.7kΩ PULLUP! Hotend sensors can use 1kΩ pullup with correct resistor and table. * + * ================================================================ * Analog Thermistors - 4.7kΩ pullup - Normal - * ------- - * 1 : 100kΩ EPCOS - Best choice for EPCOS thermistors - * 331 : 100kΩ Same as #1, but 3.3V scaled for MEGA - * 332 : 100kΩ Same as #1, but 3.3V scaled for DUE - * 2 : 200kΩ ATC Semitec 204GT-2 - * 202 : 200kΩ Copymaster 3D - * 3 : ???Ω Mendel-parts thermistor - * 4 : 10kΩ Generic Thermistor !! DO NOT use for a hotend - it gives bad resolution at high temp. !! - * 5 : 100kΩ ATC Semitec 104GT-2/104NT-4-R025H42G - Used in ParCan, J-Head, and E3D, SliceEngineering 300°C - * 501 : 100kΩ Zonestar - Tronxy X3A - * 502 : 100kΩ Zonestar - used by hot bed in Zonestar Průša P802M - * 503 : 100kΩ Zonestar (Z8XM2) Heated Bed thermistor - * 504 : 100kΩ Zonestar P802QR2 (Part# QWG-104F-B3950) Hotend Thermistor - * 505 : 100kΩ Zonestar P802QR2 (Part# QWG-104F-3950) Bed Thermistor - * 512 : 100kΩ RPW-Ultra hotend - * 6 : 100kΩ EPCOS - Not as accurate as table #1 (created using a fluke thermocouple) - * 7 : 100kΩ Honeywell 135-104LAG-J01 - * 71 : 100kΩ Honeywell 135-104LAF-J01 - * 8 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT - * 9 : 100kΩ GE Sensing AL03006-58.2K-97-G1 - * 10 : 100kΩ RS PRO 198-961 - * 11 : 100kΩ Keenovo AC silicone mats, most Wanhao i3 machines - beta 3950, 1% - * 12 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT (#8) - calibrated for Makibox hot bed - * 13 : 100kΩ Hisens up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1% - * 15 : 100kΩ Calibrated for JGAurora A5 hotend - * 18 : 200kΩ ATC Semitec 204GT-2 Dagoma.Fr - MKS_Base_DKU001327 - * 22 : 100kΩ GTM32 Pro vB - hotend - 4.7kΩ pullup to 3.3V and 220Ω to analog input - * 23 : 100kΩ GTM32 Pro vB - bed - 4.7kΩ pullup to 3.3v and 220Ω to analog input - * 30 : 100kΩ Kis3d Silicone heating mat 200W/300W with 6mm precision cast plate (EN AW 5083) NTC100K - beta 3950 - * 60 : 100kΩ Maker's Tool Works Kapton Bed Thermistor - beta 3950 - * 61 : 100kΩ Formbot/Vivedino 350°C Thermistor - beta 3950 - * 66 : 4.7MΩ Dyze Design / Trianglelab T-D500 500°C High Temperature Thermistor - * 67 : 500kΩ SliceEngineering 450°C Thermistor - * 68 : PT100 amplifier board from Dyze Design - * 70 : 100kΩ bq Hephestos 2 - * 75 : 100kΩ Generic Silicon Heat Pad with NTC100K MGB18-104F39050L32 - * 2000 : 100kΩ Ultimachine Rambo TDK NTCG104LH104KT1 NTC100K motherboard Thermistor - * - * Analog Thermistors - 1kΩ pullup - Atypical, and requires changing out the 4.7kΩ pullup for 1kΩ. - * ------- (but gives greater accuracy and more stable PID) - * 51 : 100kΩ EPCOS (1kΩ pullup) - * 52 : 200kΩ ATC Semitec 204GT-2 (1kΩ pullup) - * 55 : 100kΩ ATC Semitec 104GT-2 - Used in ParCan & J-Head (1kΩ pullup) - * + * ================================================================ + * 1 : 100kΩ EPCOS - Best choice for EPCOS thermistors + * 331 : 100kΩ Same as #1, but 3.3V scaled for MEGA + * 332 : 100kΩ Same as #1, but 3.3V scaled for DUE + * 2 : 200kΩ ATC Semitec 204GT-2 + * 202 : 200kΩ Copymaster 3D + * 3 : ???Ω Mendel-parts thermistor + * 4 : 10kΩ Generic Thermistor !! DO NOT use for a hotend - it gives bad resolution at high temp. !! + * 5 : 100kΩ ATC Semitec 104GT-2/104NT-4-R025H42G - Used in ParCan, J-Head, and E3D, SliceEngineering 300°C + * 501 : 100kΩ Zonestar - Tronxy X3A + * 502 : 100kΩ Zonestar - used by hot bed in Zonestar Průša P802M + * 503 : 100kΩ Zonestar (Z8XM2) Heated Bed thermistor + * 504 : 100kΩ Zonestar P802QR2 (Part# QWG-104F-B3950) Hotend Thermistor + * 505 : 100kΩ Zonestar P802QR2 (Part# QWG-104F-3950) Bed Thermistor + * 512 : 100kΩ RPW-Ultra hotend + * 6 : 100kΩ EPCOS - Not as accurate as table #1 (created using a fluke thermocouple) + * 7 : 100kΩ Honeywell 135-104LAG-J01 + * 71 : 100kΩ Honeywell 135-104LAF-J01 + * 8 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT + * 9 : 100kΩ GE Sensing AL03006-58.2K-97-G1 + * 10 : 100kΩ RS PRO 198-961 + * 11 : 100kΩ Keenovo AC silicone mats, most Wanhao i3 machines - beta 3950, 1% + * 12 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT (#8) - calibrated for Makibox hot bed + * 13 : 100kΩ Hisens up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1% + * 14 : 100kΩ (R25), 4092K (beta25), 4.7kΩ pull-up, bed thermistor as used in Ender-5 S1 + * 15 : 100kΩ Calibrated for JGAurora A5 hotend + * 17 : 100kΩ Dagoma NTC white thermistor + * 18 : 200kΩ ATC Semitec 204GT-2 Dagoma.Fr - MKS_Base_DKU001327 + * 22 : 100kΩ GTM32 Pro vB - hotend - 4.7kΩ pullup to 3.3V and 220Ω to analog input + * 23 : 100kΩ GTM32 Pro vB - bed - 4.7kΩ pullup to 3.3v and 220Ω to analog input + * 30 : 100kΩ Kis3d Silicone heating mat 200W/300W with 6mm precision cast plate (EN AW 5083) NTC100K - beta 3950 + * 60 : 100kΩ Maker's Tool Works Kapton Bed Thermistor - beta 3950 + * 61 : 100kΩ Formbot/Vivedino 350°C Thermistor - beta 3950 + * 66 : 4.7MΩ Dyze Design / Trianglelab T-D500 500°C High Temperature Thermistor + * 67 : 500kΩ SliceEngineering 450°C Thermistor + * 68 : PT100 Smplifier board from Dyze Design + * 70 : 100kΩ bq Hephestos 2 + * 75 : 100kΩ Generic Silicon Heat Pad with NTC100K MGB18-104F39050L32 + * 666 : 200kΩ Einstart S custom thermistor with 10k pullup. + * 2000 : 100kΩ Ultimachine Rambo TDK NTCG104LH104KT1 NTC100K motherboard Thermistor + * + * ================================================================ + * Analog Thermistors - 1kΩ pullup + * Atypical, and requires changing out the 4.7kΩ pullup for 1kΩ. + * (but gives greater accuracy and more stable PID) + * ================================================================ + * 51 : 100kΩ EPCOS (1kΩ pullup) + * 52 : 200kΩ ATC Semitec 204GT-2 (1kΩ pullup) + * 55 : 100kΩ ATC Semitec 104GT-2 - Used in ParCan & J-Head (1kΩ pullup) + * + * ================================================================ * Analog Thermistors - 10kΩ pullup - Atypical - * ------- - * 99 : 100kΩ Found on some Wanhao i3 machines with a 10kΩ pull-up resistor + * ================================================================ + * 99 : 100kΩ Found on some Wanhao i3 machines with a 10kΩ pull-up resistor * + * ================================================================ * Analog RTDs (Pt100/Pt1000) - * ------- + * ================================================================ * 110 : Pt100 with 1kΩ pullup (atypical) * 147 : Pt100 with 4.7kΩ pullup * 1010 : Pt1000 with 1kΩ pullup (atypical) @@ -535,15 +529,34 @@ * NOTE: ADC pins are not 5V tolerant. Not recommended because it's possible to damage the CPU by going over 500°C. * 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x * + * ================================================================ + * SPI RTD/Thermocouple Boards + * ================================================================ + * -5 : MAX31865 with Pt100/Pt1000, 2, 3, or 4-wire (only for sensors 0-2 and bed) + * NOTE: You must uncomment/set the MAX31865_*_OHMS_n defines below. + * -3 : MAX31855 with Thermocouple, -200°C to +700°C (only for sensors 0-2 and bed) + * -2 : MAX6675 with Thermocouple, 0°C to +700°C (only for sensors 0-2 and bed) + * + * NOTE: Ensure TEMP_n_CS_PIN is set in your pins file for each TEMP_SENSOR_n using an SPI Thermocouple. By default, + * Hardware SPI on the default serial bus is used. If you have also set TEMP_n_SCK_PIN and TEMP_n_MISO_PIN, + * Software SPI will be used on those ports instead. You can force Hardware SPI on the default bus in the + * Configuration_adv.h file. At this time, separate Hardware SPI buses for sensors are not supported. + * + * ================================================================ + * Analog Thermocouple Boards + * ================================================================ + * -4 : AD8495 with Thermocouple + * -1 : AD595 with Thermocouple + * + * ================================================================ * Custom/Dummy/Other Thermal Sensors - * ------ + * ================================================================ * 0 : not used * 1000 : Custom - Specify parameters in Configuration_adv.h * * !!! Use these for Testing or Development purposes. NEVER for production machine. !!! * 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below. * 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below. - * */ #define TEMP_SENSOR_0 1 #define TEMP_SENSOR_1 0 @@ -655,14 +668,18 @@ // @section hotend temp -// Enable PIDTEMP for PID control or MPCTEMP for Predictive Model. -// temperature control. Disable both for bang-bang heating. -#define PIDTEMP // See the PID Tuning Guide at https://reprap.org/wiki/PID_Tuning -//#define MPCTEMP // ** EXPERIMENTAL ** +/** + * Temperature Control + * + * (NONE) : Bang-bang heating + * PIDTEMP : PID temperature control (~4.1K) + * MPCTEMP : Predictive Model temperature control. (~1.8K without auto-tune) + */ +#define PIDTEMP // See the PID Tuning Guide at https://reprap.org/wiki/PID_Tuning +//#define MPCTEMP // ** EXPERIMENTAL ** See https://marlinfw.org/docs/features/model_predictive_control.html -#define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current -#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current -#define PID_K1 0.95 // Smoothing factor within any PID loop +#define PID_MAX 255 // Limit hotend current while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current +#define PID_K1 0.95 // Smoothing factor within any PID loop #if ENABLED(PIDTEMP) //#define PID_DEBUG // Print PID debug data to the serial port. Use 'M303 D' to toggle activation. @@ -681,21 +698,23 @@ #define DEFAULT_Ki 1.59 #define DEFAULT_Kd 59.40 #endif +#else + #define BANG_MAX 255 // Limit hotend current while in bang-bang mode; 255=full current #endif /** * Model Predictive Control for hotend * - * Use a physical model of the hotend to control temperature. When configured correctly - * this gives better responsiveness and stability than PID and it also removes the need - * for PID_EXTRUSION_SCALING and PID_FAN_SCALING. Use M306 T to autotune the model. + * Use a physical model of the hotend to control temperature. When configured correctly this gives + * better responsiveness and stability than PID and removes the need for PID_EXTRUSION_SCALING + * and PID_FAN_SCALING. Use M306 T to autotune the model. * @section mpctemp */ #if ENABLED(MPCTEMP) - //#define MPC_EDIT_MENU // Add MPC editing to the "Advanced Settings" menu. (~1300 bytes of flash) + //#define MPC_EDIT_MENU // Add MPC editing to the "Advanced Settings" menu. (~1.3K bytes of flash) //#define MPC_AUTOTUNE_MENU // Add MPC auto-tuning to the "Advanced Settings" menu. (~350 bytes of flash) - #define MPC_MAX BANG_MAX // (0..255) Current to nozzle while MPC is active. + #define MPC_MAX 255 // (0..255) Current to nozzle while MPC is active. #define MPC_HEATER_POWER { 40.0f } // (W) Heat cartridge powers. #define MPC_INCLUDE_FAN // Model the fan speed? @@ -714,8 +733,12 @@ //#define MPC_FAN_0_ACTIVE_HOTEND #endif + // Filament Heat Capacity (joules/kelvin/mm) + // Set at runtime with M306 H #define FILAMENT_HEAT_CAPACITY_PERMM { 5.6e-3f } // 0.0056 J/K/mm for 1.75mm PLA (0.0149 J/K/mm for 2.85mm PLA). - //#define FILAMENT_HEAT_CAPACITY_PERMM { 3.6e-3f } // 0.0036 J/K/mm for 1.75mm PETG (0.0094 J/K/mm for 2.85mm PETG). + // 0.0036 J/K/mm for 1.75mm PETG (0.0094 J/K/mm for 2.85mm PETG). + // 0.00515 J/K/mm for 1.75mm ABS (0.0137 J/K/mm for 2.85mm ABS). + // 0.00522 J/K/mm for 1.75mm Nylon (0.0138 J/K/mm for 2.85mm Nylon). // Advanced options #define MPC_SMOOTHING_FACTOR 0.5f // (0.0...1.0) Noisy temperature sensors may need a lower value for stabilization. @@ -730,31 +753,29 @@ //====================== PID > Bed Temperature Control ====================== //=========================================================================== +// @section bed temp + +/** + * Max Bed Power + * Applies to all forms of bed control (PID, bang-bang, and bang-bang with hysteresis). + * When set to any value below 255, enables a form of PWM to the bed that acts like a divider + * so don't use it unless you are OK with PWM on your bed. (See the comment on enabling PIDTEMPBED) + */ +#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current + /** * PID Bed Heating * - * If this option is enabled set PID constants below. - * If this option is disabled, bang-bang will be used and BED_LIMIT_SWITCHING will enable hysteresis. - * * The PID frequency will be the same as the extruder PWM. * If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz, * which is fine for driving a square wave into a resistive load and does not significantly * impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W * heater. If your configuration is significantly different than this and you don't understand * the issues involved, don't use bed PID until someone else verifies that your hardware works. - * @section bed temp - */ -#define PIDTEMPBED - -//#define BED_LIMIT_SWITCHING - -/** - * Max Bed Power - * Applies to all forms of bed control (PID, bang-bang, and bang-bang with hysteresis). - * When set to any value below 255, enables a form of PWM to the bed that acts like a divider - * so don't use it unless you are OK with PWM on your bed. (See the comment on enabling PIDTEMPBED) + * + * With this option disabled, bang-bang will be used. BED_LIMIT_SWITCHING enables hysteresis. */ -#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current +//#define PIDTEMPBED #if ENABLED(PIDTEMPBED) //#define MIN_BED_POWER 0 @@ -768,7 +789,9 @@ #define DEFAULT_bedKd 1068.83 // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles. -#endif // PIDTEMPBED +#else + //#define BED_LIMIT_SWITCHING // Keep the bed temperature within BED_HYSTERESIS of the target +#endif //=========================================================================== //==================== PID > Chamber Temperature Control ==================== @@ -880,7 +903,12 @@ //#define COREYX //#define COREZX //#define COREZY -//#define MARKFORGED_XY // MarkForged. See https://reprap.org/forum/read.php?152,504042 + +// +// MarkForged Kinematics +// See https://reprap.org/forum/read.php?152,504042 +// +//#define MARKFORGED_XY //#define MARKFORGED_YX // Enable for a belt style printer with endless "Z" motion @@ -889,8 +917,8 @@ // Enable for Polargraph Kinematics //#define POLARGRAPH #if ENABLED(POLARGRAPH) - #define POLARGRAPH_MAX_BELT_LEN 1035.0 - #define DEFAULT_SEGMENTS_PER_SECOND 5 + #define POLARGRAPH_MAX_BELT_LEN 1035.0 // (mm) Belt length at full extension. Override with M665 H. + #define DEFAULT_SEGMENTS_PER_SECOND 5 // Move segmentation based on duration #endif // @section delta @@ -937,7 +965,7 @@ // Distance between bed and nozzle Z home position #define DELTA_HEIGHT 250.00 // (mm) Get this value from G33 auto calibrate - #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // Get these values from G33 auto calibrate + #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // (mm) Get these values from G33 auto calibrate // Horizontal distance bridged by diagonal push rods when effector is centered. #define DELTA_RADIUS 124.0 // (mm) Get this value from G33 auto calibrate @@ -945,11 +973,11 @@ // Trim adjustments for individual towers // tower angle corrections for X and Y tower / rotate XYZ so Z tower angle = 0 // measured in degrees anticlockwise looking from above the printer - #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // Get these values from G33 auto calibrate + #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // (mm) Get these values from G33 auto calibrate - // Delta radius and diagonal rod adjustments (mm) - //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } - //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } + // Delta radius and diagonal rod adjustments + //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } // (mm) + //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } // (mm) #endif // @section scara @@ -985,8 +1013,8 @@ // Radius around the center where the arm cannot reach #define MIDDLE_DEAD_ZONE_R 0 // (mm) - #define THETA_HOMING_OFFSET 0 // Calculated from Calibration Guide and M360 / M114. See http://reprap.harleystudio.co.za/?page_id=1073 - #define PSI_HOMING_OFFSET 0 // Calculated from Calibration Guide and M364 / M114. See http://reprap.harleystudio.co.za/?page_id=1073 + #define THETA_HOMING_OFFSET 0 // Calculated from Calibration Guide and M360 / M114. See https://www.morgan3dp.com/morgan-calibration-guide/ + #define PSI_HOMING_OFFSET 0 // Calculated from Calibration Guide and M364 / M114. See https://www.morgan3dp.com/morgan-calibration-guide/ #elif ENABLED(MP_SCARA) @@ -1020,7 +1048,7 @@ // Radius around the center where the arm cannot reach #define MIDDLE_DEAD_ZONE_R 0 // (mm) - // Calculated from Calibration Guide and M360 / M114. See http://reprap.harleystudio.co.za/?page_id=1073 + // Calculated from Calibration Guide and M360 / M114. See https://www.morgan3dp.com/morgan-calibration-guide/ #define THETA_HOMING_OFFSET 0 #define PSI_HOMING_OFFSET 0 #endif @@ -1297,19 +1325,17 @@ /** * Z_MIN_PROBE_PIN * - * Define this pin if the probe is not connected to Z_MIN_PIN. - * If not defined the default pin for the selected MOTHERBOARD - * will be used. Most of the time the default is what you want. + * Override this pin only if the probe cannot be connected to + * the default Z_MIN_PROBE_PIN for the selected MOTHERBOARD. * * - The simplest option is to use a free endstop connector. * - Use 5V for powered (usually inductive) sensors. * - * - RAMPS 1.3/1.4 boards may use the 5V, GND, and Aux4->D32 pin: - * - For simple switches connect... - * - normally-closed switches to GND and D32. - * - normally-open switches to 5V and D32. + * - For simple switches... + * - Normally-closed (NC) also connect to GND. + * - Normally-open (NO) also connect to 5V. */ -//#define Z_MIN_PROBE_PIN 32 // Pin 32 is the RAMPS default +//#define Z_MIN_PROBE_PIN -1 #if ENABLED(CR10V3_BLTOUCH) #define Z_MIN_PROBE_PIN 19 @@ -1344,8 +1370,10 @@ /** * Z Servo Probe, such as an endstop switch on a rotating arm. */ -//#define Z_PROBE_SERVO_NR 0 // Defaults to SERVO 0 connector. -//#define Z_SERVO_ANGLES { 70, 0 } // Z Servo Deploy and Stow angles +//#define Z_PROBE_SERVO_NR 0 +#ifdef Z_PROBE_SERVO_NR + //#define Z_SERVO_ANGLES { 70, 0 } // Z Servo Deploy and Stow angles +#endif /** * The BLTouch probe uses a Hall effect sensor and emulates a servo. @@ -1417,7 +1445,7 @@ #define MAG_MOUNTED_STOW_5 { PROBE_STOW_FEEDRATE, { 0, 0, 0 } } // Extra move if needed #endif -// Duet Smart Effector (for delta printers) - https://bit.ly/2ul5U7J +// Duet Smart Effector (for delta printers) - https://docs.duet3d.com/en/Duet3D_hardware/Accessories/Smart_Effector // When the pin is defined you can use M672 to set/reset the probe sensitivity. //#define DUET_SMART_EFFECTOR #if ENABLED(DUET_SMART_EFFECTOR) @@ -1433,7 +1461,7 @@ //#define SENSORLESS_PROBING /** - * Allen key retractable z-probe as seen on many Kossel delta printers - https://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe + * Allen key retractable z-probe as seen on many Kossel delta printers - https://reprap.org/wiki/Kossel#Autolevel_probe * Deploys by touching z-axis belt. Retracts by pushing the probe down. */ //#define Z_PROBE_ALLEN_KEY @@ -1480,7 +1508,7 @@ * * Tune and Adjust * - Probe Offsets can be tuned at runtime with 'M851', LCD menus, babystepping, etc. - * - PROBE_OFFSET_WIZARD (configuration_adv.h) can be used for setting the Z offset. + * - PROBE_OFFSET_WIZARD (Configuration_adv.h) can be used for setting the Z offset. * * Assuming the typical work area orientation: * - Probe to RIGHT of the Nozzle has a Positive X offset @@ -1582,12 +1610,12 @@ * Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle. * But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle. */ -#define Z_CLEARANCE_DEPLOY_PROBE 10 // Z Clearance for Deploy/Stow -#define Z_CLEARANCE_BETWEEN_PROBES 3 // Stock: 5 - Z Clearance between probe points -#define Z_CLEARANCE_MULTI_PROBE 3 // Stock: 5 - Z Clearance between multiple probes -#define Z_AFTER_PROBING 100 // Z position after probing is done +#define Z_CLEARANCE_DEPLOY_PROBE 10 // (mm) Z Clearance for Deploy/Stow +#define Z_CLEARANCE_BETWEEN_PROBES 5 // (mm) Z Clearance between probe points +#define Z_CLEARANCE_MULTI_PROBE 5 // (mm) Z Clearance between multiple probes +//#define Z_AFTER_PROBING 5 // (mm) Z position after probing is done -#define Z_PROBE_LOW_POINT -1 // Farthest distance below the trigger-point to go before stopping +#define Z_PROBE_LOW_POINT -2 // (mm) Farthest distance below the trigger-point to go before stopping // For M851 give a range for adjusting the Z probe offset #define Z_PROBE_OFFSET_RANGE_MIN -9 @@ -1643,23 +1671,23 @@ // Disable axis steppers immediately when they're not being stepped. // WARNING: When motors turn off there is a chance of losing position accuracy! -#define DISABLE_X false -#define DISABLE_Y false -#define DISABLE_Z false -//#define DISABLE_I false -//#define DISABLE_J false -//#define DISABLE_K false -//#define DISABLE_U false -//#define DISABLE_V false -//#define DISABLE_W false +//#define DISABLE_X +//#define DISABLE_Y +//#define DISABLE_Z +//#define DISABLE_I +//#define DISABLE_J +//#define DISABLE_K +//#define DISABLE_U +//#define DISABLE_V +//#define DISABLE_W // Turn off the display blinking that warns about possible accuracy reduction //#define DISABLE_REDUCED_ACCURACY_WARNING // @section extruder -#define DISABLE_E false // Disable the extruder when not stepping -#define DISABLE_INACTIVE_EXTRUDER // Keep only the active extruder enabled +//#define DISABLE_E // Disable the extruder when not stepping +#define DISABLE_OTHER_EXTRUDERS // Keep only the active extruder enabled // @section motion @@ -1905,6 +1933,12 @@ //#define AUTO_BED_LEVELING_UBL //#define MESH_BED_LEVELING +/** + * Commands to execute at the end of G29 probing. + * Useful to retract or move the Z probe out of the way. + */ +//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" + /** * Normally G28 leaves leveling disabled on completion. Enable one of * these options to restore the prior leveling state or to always enable @@ -1936,7 +1970,7 @@ /** * Enable detailed logging of G28, G29, M48, etc. * Turn on with the command 'M111 S32'. - * NOTE: Requires a lot of PROGMEM! + * NOTE: Requires a lot of flash! */ //#define DEBUG_LEVELING_FEATURE @@ -1996,7 +2030,7 @@ //#define EXTRAPOLATE_BEYOND_GRID // - // Experimental Subdivision of the grid by Catmull-Rom method. + // Subdivision of the grid by Catmull-Rom method. // Synthesizes intermediate points to produce a more detailed mesh. // //#define ABL_BILINEAR_SUBDIVISION @@ -2061,13 +2095,11 @@ #define LCD_BED_TRAMMING #if ENABLED(LCD_BED_TRAMMING) - #define BED_TRAMMING_INSET_LFRB { 45, 45, 45, 45 } // (mm) Left, Front, Right, Back insets - #define BED_TRAMMING_HEIGHT 0.0 // (mm) Z height of nozzle at leveling points - #define BED_TRAMMING_Z_HOP 4.0 // (mm) Z height of nozzle between leveling points - #define BED_TRAMMING_INCLUDE_CENTER // Move to the center after the last corner - #if ENABLED(CR10V3_BLTOUCH) - #define BED_TRAMMING_USE_PROBE - #endif + #define BED_TRAMMING_INSET_LFRB { 30, 30, 30, 30 } // (mm) Left, Front, Right, Back insets + #define BED_TRAMMING_HEIGHT 0.0 // (mm) Z height of nozzle at tramming points + #define BED_TRAMMING_Z_HOP 4.0 // (mm) Z height of nozzle between tramming points + //#define BED_TRAMMING_INCLUDE_CENTER // Move to the center after the last corner + //#define BED_TRAMMING_USE_PROBE #if ENABLED(BED_TRAMMING_USE_PROBE) #define BED_TRAMMING_PROBE_TOLERANCE 0.1 // (mm) #define BED_TRAMMING_VERIFY_RAISED // After adjustment triggers the probe, re-probe to verify @@ -2094,12 +2126,6 @@ #define BED_TRAMMING_LEVELING_ORDER { LF, RF, RB, LB } #endif -/** - * Commands to execute at the end of G29 probing. - * Useful to retract or move the Z probe out of the way. - */ -//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" - // @section homing // The center of the bed is at (X=0, Y=0) @@ -2129,8 +2155,8 @@ #endif #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT X_CENTER // X point for Z homing - #define Z_SAFE_HOMING_Y_POINT Y_CENTER // Y point for Z homing + #define Z_SAFE_HOMING_X_POINT X_CENTER // (mm) X point for Z homing + #define Z_SAFE_HOMING_Y_POINT Y_CENTER // (mm) Y point for Z homing #endif // Homing speeds (linear=mm/min, rotational=°/min) @@ -2214,7 +2240,7 @@ */ #define EEPROM_SETTINGS // Persistent storage with M500 and M501 //#define DISABLE_M503 // Saves ~2700 bytes of flash. Disable for release! -#define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save PROGMEM. +#define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save flash. #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. @@ -2287,7 +2313,7 @@ #endif /** - * Clean Nozzle Feature -- EXPERIMENTAL + * Clean Nozzle Feature * * Adds the G12 command to perform a nozzle cleaning process. * @@ -2321,7 +2347,6 @@ * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. * * Caveats: The ending Z should be the same as starting Z. - * Attention: EXPERIMENTAL. G-code arguments may change. */ //#define NOZZLE_CLEAN_FEATURE @@ -2436,7 +2461,7 @@ #define PASSWORD_ON_STARTUP #define PASSWORD_UNLOCK_GCODE // Unlock with the M511 P command. Disable to prevent brute-force attack. #define PASSWORD_CHANGE_GCODE // Change the password with M512 P S. - //#define PASSWORD_ON_SD_PRINT_MENU // This does not prevent gcodes from running + //#define PASSWORD_ON_SD_PRINT_MENU // This does not prevent G-codes from running //#define PASSWORD_AFTER_SD_PRINT_END //#define PASSWORD_AFTER_SD_PRINT_ABORT //#include "Configuration_Secure.h" // External file with PASSWORD_DEFAULT_VALUE @@ -2622,7 +2647,7 @@ // // Original RADDS LCD Display+Encoder+SDCardReader -// http://doku.radds.org/dokumentation/lcd-display/ +// https://web.archive.org/web/20200719145306/http://doku.radds.org/dokumentation/lcd-display/ // //#define RADDS_DISPLAY @@ -2652,7 +2677,6 @@ // // RigidBot Panel V1.0 -// http://www.inventapart.com/ // //#define RIGIDBOT_PANEL @@ -2696,8 +2720,9 @@ // // Sainsmart (YwRobot) LCD Displays // -// These require F.Malpartida's LiquidCrystal_I2C library -// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home +// These require LiquidCrystal_I2C library: +// https://github.com/MarlinFirmware/New-LiquidCrystal +// https://github.com/fmalpartida/New-LiquidCrystal/wiki // //#define LCD_SAINSMART_I2C_1602 //#define LCD_SAINSMART_I2C_2004 @@ -2730,7 +2755,7 @@ // // -// 2-wire Non-latching LCD SR from https://goo.gl/aJJ4sH +// 2-wire Non-latching LCD SR from https://github.com/fmalpartida/New-LiquidCrystal/wiki/schematics#user-content-ShiftRegister_connection // LCD configuration: https://reprap.org/wiki/SAV_3D_LCD // //#define SAV_3DLCD @@ -2802,7 +2827,7 @@ // // MaKr3d Makr-Panel with graphic controller and SD support. -// https://reprap.org/wiki/MaKr3d_MaKrPanel +// https://reprap.org/wiki/MaKrPanel // //#define MAKRPANEL @@ -2820,7 +2845,7 @@ // // Cartesio UI -// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// https://web.archive.org/web/20180605050442/http://mauk.cc/webshop/cartesio-shop/electronics/user-interface // //#define CARTESIO_UI @@ -2864,16 +2889,16 @@ //#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. +// BigTreeTech Mini 12864 V1.0 / V2.0 is an alias for FYSETC_MINI_12864_2_1. Type A/B. NeoPixel RGB Backlight. +// https://github.com/bigtreetech/MINI-12864 // -//#define BTT_MINI_12864_V1 +//#define BTT_MINI_12864 // -// Factory display for Creality CR-10 -// https://www.aliexpress.com/item/32833148327.html +// Factory display for Creality CR-10 / CR-7 / Ender-3 +// https://marlinfw.org/docs/hardware/controllers.html#cr10_stockdisplay // -// This is RAMPS-compatible using a single 10-pin connector. -// (For CR-10 owners who want to replace the Melzi Creality board but retain the display) +// Connect to EXP1 on RAMPS and compatible boards. // //#define CR10_STOCKDISPLAY @@ -2988,10 +3013,12 @@ * ORIGIN (Marlin DWIN_SET) * - Download https://github.com/coldtobi/Marlin_DGUS_Resources * - Copy the downloaded DWIN_SET folder to the SD card. + * - Product: https://www.aliexpress.com/item/32993409517.html * * FYSETC (Supplier default) * - Download https://github.com/FYSETC/FYSTLCD-2.0 * - Copy the downloaded SCREEN folder to the SD card. + * - Product: https://www.aliexpress.com/item/32961471929.html * * HIPRECY (Supplier default) * - Download https://github.com/HiPrecy/Touch-Lcd-LEO @@ -3000,10 +3027,17 @@ * MKS (MKS-H43) (Supplier default) * - Download https://github.com/makerbase-mks/MKS-H43 * - Copy the downloaded DWIN_SET folder to the SD card. + * - Product: https://www.aliexpress.com/item/1005002008179262.html * * RELOADED (T5UID1) - * - Download https://github.com/Desuuuu/DGUS-reloaded/releases + * - Download https://github.com/Neo2003/DGUS-reloaded/releases * - Copy the downloaded DWIN_SET folder to the SD card. + * + * Flash display with DGUS Displays for Marlin: + * - Format the SD card to FAT32 with an allocation size of 4kb. + * - Download files as specified for your type of display. + * - Plug the microSD card into the back of the display. + * - Boot the display and wait for the update to complete. */ //#define DGUS_LCD_UI_ORIGIN //#define DGUS_LCD_UI_FYSETC @@ -3062,6 +3096,7 @@ // // 480x320, 3.5", SPI Display with Rotary Encoder from MKS // Usually paired with MKS Robin Nano V2 & V3 +// https://github.com/makerbase-mks/MKS-TFT-Hardware/tree/master/MKS%20TS35 // //#define MKS_TS35_V2_0 @@ -3126,12 +3161,14 @@ //#define ANET_ET5_TFT35 // -// 1024x600, 7", RGB Stock Display with Rotary Encoder from BIQU-BX +// 1024x600, 7", RGB Stock Display with Rotary Encoder from BIQU BX +// https://github.com/bigtreetech/BIQU-BX/tree/master/Hardware // //#define BIQU_BX_TFT70 // // 480x320, 3.5", SPI Stock Display with Rotary Encoder from BIQU B1 SE Series +// https://github.com/bigtreetech/TFT35-SPI/tree/master/v1 // //#define BTT_TFT35_SPI_V1_0 @@ -3169,11 +3206,11 @@ //#define TFT_LVGL_UI #if ENABLED(TFT_COLOR_UI) - //#define TFT_SHARED_SPI // SPI is shared between TFT display and other devices. Disable async data transfer + //#define TFT_SHARED_IO // SPI is shared between TFT display and other devices. Disable async data transfer #endif #if ENABLED(TFT_LVGL_UI) - //#define MKS_WIFI_MODULE // MKS WiFi module + //#define MKS_WIFI_MODULE // MKS WiFi module #endif /** @@ -3320,6 +3357,9 @@ //#define RGB_LED_G_PIN 43 //#define RGB_LED_B_PIN 35 //#define RGB_LED_W_PIN -1 +#endif + +#if ANY(RGB_LED, RGBW_LED, PCA9632) //#define RGB_STARTUP_TEST // For PWM pins, fade between all colors #if ENABLED(RGB_STARTUP_TEST) #define RGB_STARTUP_TEST_INNER_MS 10 // (ms) Reduce or increase fading speed @@ -3353,7 +3393,7 @@ // Use some of the NeoPixel LEDs for static (background) lighting //#define NEOPIXEL_BKGD_INDEX_FIRST 0 // Index of the first background LED //#define NEOPIXEL_BKGD_INDEX_LAST 5 // Index of the last background LED - //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W + //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W //#define NEOPIXEL_BKGD_ALWAYS_ON // Keep the backlight on when other NeoPixels are off #endif diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index cbbd9ebc65f2..b4c462d6d70a 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -32,7 +32,7 @@ * * Basic settings can be found in Configuration.h */ -#define CONFIGURATION_ADV_H_VERSION 02010201 +#define CONFIGURATION_ADV_H_VERSION 02010202 // @section develop @@ -192,12 +192,10 @@ /** * Hephestos 2 24V heated bed upgrade kit. - * https://store.bq.com/en/heated-bed-kit-hephestos2 + * https://www.en3dstudios.com/product/bq-hephestos-2-heated-bed-kit/ */ //#define HEPHESTOS2_HEATED_BED_KIT #if ENABLED(HEPHESTOS2_HEATED_BED_KIT) - #undef TEMP_SENSOR_BED - #define TEMP_SENSOR_BED 70 #define HEATER_BED_INVERTING true #endif @@ -280,9 +278,7 @@ #define THERMAL_PROTECTION_BOARD // Halt the printer if the board sensor leaves the temp range below. #define BOARD_MINTEMP 8 // (°C) #define BOARD_MAXTEMP 70 // (°C) - #ifndef TEMP_BOARD_PIN - //#define TEMP_BOARD_PIN -1 // Board temp sensor pin, if not set in pins file. - #endif + //#define TEMP_BOARD_PIN -1 // Board temp sensor pin override. #endif /** @@ -302,8 +298,8 @@ * THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD */ #if ENABLED(THERMAL_PROTECTION_HOTENDS) - #define THERMAL_PROTECTION_PERIOD 60 // Seconds - #define THERMAL_PROTECTION_HYSTERESIS 10 // Degrees Celsius + #define THERMAL_PROTECTION_PERIOD 40 // (seconds) + #define THERMAL_PROTECTION_HYSTERESIS 4 // (°C) #define ADAPTIVE_FAN_SLOWING // Slow part cooling fan if temperature drops #if BOTH(ADAPTIVE_FAN_SLOWING, PIDTEMP) @@ -322,50 +318,50 @@ * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set * below 2. */ - #define WATCH_TEMP_PERIOD 50 // Seconds - #define WATCH_TEMP_INCREASE 2 // Degrees Celsius + #define WATCH_TEMP_PERIOD 40 // (seconds) + #define WATCH_TEMP_INCREASE 2 // (°C) #endif /** * Thermal Protection parameters for the bed are just as above for hotends. */ #if ENABLED(THERMAL_PROTECTION_BED) - #define THERMAL_PROTECTION_BED_PERIOD 50 // Seconds - #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius + #define THERMAL_PROTECTION_BED_PERIOD 20 // (seconds) + #define THERMAL_PROTECTION_BED_HYSTERESIS 2 // (°C) /** * As described above, except for the bed (M140/M190/M303). */ - #define WATCH_BED_TEMP_PERIOD 180 // Seconds - #define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius + #define WATCH_BED_TEMP_PERIOD 60 // (seconds) + #define WATCH_BED_TEMP_INCREASE 2 // (°C) #endif /** * Thermal Protection parameters for the heated chamber. */ #if ENABLED(THERMAL_PROTECTION_CHAMBER) - #define THERMAL_PROTECTION_CHAMBER_PERIOD 20 // Seconds - #define THERMAL_PROTECTION_CHAMBER_HYSTERESIS 2 // Degrees Celsius + #define THERMAL_PROTECTION_CHAMBER_PERIOD 20 // (seconds) + #define THERMAL_PROTECTION_CHAMBER_HYSTERESIS 2 // (°C) /** * Heated chamber watch settings (M141/M191). */ - #define WATCH_CHAMBER_TEMP_PERIOD 60 // Seconds - #define WATCH_CHAMBER_TEMP_INCREASE 2 // Degrees Celsius + #define WATCH_CHAMBER_TEMP_PERIOD 60 // (seconds) + #define WATCH_CHAMBER_TEMP_INCREASE 2 // (°C) #endif /** * 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 // (°C) /** * 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 // (°C) #endif #if ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_BED, THERMAL_PROTECTION_CHAMBER, THERMAL_PROTECTION_COOLER) @@ -377,7 +373,7 @@ #endif #if ENABLED(PIDTEMP) - // Add an experimental additional term to the heater power, proportional to the extrusion speed. + // Add an 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. //#define PID_EXTRUSION_SCALING #if ENABLED(PID_EXTRUSION_SCALING) @@ -386,12 +382,12 @@ #endif /** - * Add an experimental additional term to the heater power, proportional to the fan speed. + * Add an additional term to the heater power, proportional to the fan speed. * A well-chosen Kf value should add just enough power to compensate for power-loss from the cooling fan. * You can either just add a constant compensation with the DEFAULT_Kf value * or follow the instruction below to get speed-dependent compensation. * - * Constant compensation (use only with fanspeeds of 0% and 100%) + * Constant compensation (use only with fan speeds of 0% and 100%) * --------------------------------------------------------------------- * A good starting point for the Kf-value comes from the calculation: * kf = (power_fan * eff_fan) / power_heater * 255 @@ -418,7 +414,7 @@ //#define PID_FAN_SCALING_ALTERNATIVE_DEFINITION #if ENABLED(PID_FAN_SCALING_ALTERNATIVE_DEFINITION) // The alternative definition is used for an easier configuration. - // Just figure out Kf at fullspeed (255) and PID_FAN_SCALING_MIN_SPEED. + // Just figure out Kf at full speed (255) and PID_FAN_SCALING_MIN_SPEED. // DEFAULT_Kf and PID_FAN_SCALING_LIN_FACTOR are calculated accordingly. #define PID_FAN_SCALING_AT_FULL_SPEED 13.0 //=PID_FAN_SCALING_LIN_FACTOR*255+DEFAULT_Kf @@ -530,6 +526,8 @@ #define TEMP_SENSOR_AD8495_OFFSET 0.0 #define TEMP_SENSOR_AD8495_GAIN 1.0 +// @section fans + /** * Controller Fan * To cool down the stepper drivers and MOSFETs. @@ -593,7 +591,7 @@ * FAST_PWM_FAN_FREQUENCY * Set this to your desired frequency. * 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. + * i.e., F = 31.4kHz on 16MHz micro-controllers or F = 39.2kHz on 20MHz micro-controllers. * 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. @@ -627,8 +625,6 @@ */ //#define REDUNDANT_PART_COOLING_FAN 2 // Index of the fan to sync with FAN 0. -// @section extruder - /** * Extruder cooling fans * @@ -705,6 +701,7 @@ #define FANMUX2_PIN -1 /** + * @section caselight * M355 Case Light on-off / brightness */ //#define CASE_LIGHT_ENABLE @@ -727,7 +724,7 @@ #endif #endif -// @section homing +// @section endstops // If you want endstops to stay on (by default) even when not homing // enable this option. Override at any time with M120, M121. @@ -744,6 +741,8 @@ //#define CLOSED_LOOP_MOVE_COMPLETE_PIN -1 #endif +// @section idex + /** * Dual X Carriage * @@ -778,7 +777,6 @@ #define X1_MAX_POS X_BED_SIZE // A max coordinate so the X1 carriage can't hit the parked X2 carriage #define X2_MIN_POS 80 // A min coordinate so the X2 carriage can't hit the parked X1 carriage #define X2_MAX_POS 353 // The max position of the X2 carriage, typically also the home position - #define X2_HOME_DIR 1 // Set to 1. The X2 carriage always homes to the max endstop position #define X2_HOME_POS X2_MAX_POS // Default X2 home position. Set to X2_MAX_POS. // NOTE: For Dual X Carriage use M218 T1 Xn to override the X2_HOME_POS. // This allows recalibration of endstops distance without a rebuild. @@ -794,6 +792,8 @@ //#define EVENT_GCODE_IDEX_AFTER_MODECHANGE "G28X" #endif +// @section multi stepper + /** * Multi-Stepper / Multi-Endstop * @@ -865,6 +865,8 @@ //#define INVERT_E1_VS_E0_DIR // E direction signals are opposites #endif +// @section extruder + // Activate a solenoid on the active extruder with M380. Disable all with M381. // Define SOL0_PIN, SOL1_PIN, etc., for each extruder that has a solenoid. //#define EXT_SOLENOID @@ -887,7 +889,7 @@ #define QUICK_HOME // If G28 contains XY do a diagonal move first //#define HOME_Y_BEFORE_X // If G28 contains XY home Y before X -//#define HOME_Z_FIRST // Home Z first. Requires a Z-MIN endstop (not a probe). +//#define HOME_Z_FIRST // Home Z first. Requires a real endstop (not a probe). //#define CODEPENDENT_XY_HOMING // If X/Y can't home without homing Y/X first // @section bltouch @@ -932,12 +934,15 @@ * Danger: Don't activate 5V mode unless attached to a 5V-tolerant controller! * V3.0 or 3.1: Set default mode to 5V mode at Marlin startup. * If disabled, OD mode is the hard-coded default on 3.0 - * On startup, Marlin will compare its eeprom to this value. If the selected mode - * differs, a mode set eeprom write will be completed at initialization. - * Use the option below to force an eeprom write to a V3.1 probe regardless. + * On startup, Marlin will compare its EEPROM to this value. If the selected mode + * differs, a mode set EEPROM write will be completed at initialization. + * Use the option below to force an EEPROM write to a V3.1 probe regardless. */ #define BLTOUCH_SET_5V_MODE + // Safety: Enable voltage mode settings in the LCD menu. + //#define BLTOUCH_LCD_VOLTAGE_MENU + /** * Safety: Activate if connecting a probe with an unknown voltage mode. * V3.0: Set a probe into mode selected above at Marlin startup. Required for 5V mode on 3.0 @@ -956,12 +961,10 @@ */ //#define BLTOUCH_HS_MODE true - // Safety: Enable voltage mode settings in the LCD menu. - //#define BLTOUCH_LCD_VOLTAGE_MENU #endif // BLTOUCH -// @section extras +// @section calibration /** * Z Steppers Auto-Alignment @@ -1034,8 +1037,8 @@ #endif #if ENABLED(ASSISTED_TRAMMING) - // Define positions for probe points. - #define TRAMMING_POINT_XY { { 45, 20 }, { 280, 20 }, { 280, 280 }, { 45, 280 } } + // Define from 3 to 9 points to probe. + #define TRAMMING_POINT_XY { { 20, 20 }, { 180, 20 }, { 180, 180 }, { 20, 180 } } // Define position names for probe points. #define TRAMMING_POINT_NAME_1 "Front-Left" @@ -1060,7 +1063,7 @@ #endif -// @section motion +// @section motion control /** * Input Shaping -- EXPERIMENTAL @@ -1099,6 +1102,8 @@ //#define SHAPING_MENU // Add a menu to the LCD to set shaping parameters. #endif +// @section motion + #define AXIS_RELATIVE_MODES { false, false, false, false } // Add a Duplicate option for well-separated conjoined nozzles @@ -1118,20 +1123,20 @@ /** * Idle Stepper Shutdown - * Set DISABLE_INACTIVE_? 'true' to shut down axis steppers after an idle period. - * The Deactive Time can be overridden with M18 and M84. Set to 0 for No Timeout. + * Enable DISABLE_IDLE_* to shut down axis steppers after an idle period. + * The default timeout duration can be overridden with M18 and M84. Set to 0 for No Timeout. */ -#define DEFAULT_STEPPER_DEACTIVE_TIME 120 -#define DISABLE_INACTIVE_X true -#define DISABLE_INACTIVE_Y true -#define DISABLE_INACTIVE_Z true // Set 'false' if the nozzle could fall onto your printed part! -#define DISABLE_INACTIVE_I true -#define DISABLE_INACTIVE_J true -#define DISABLE_INACTIVE_K true -#define DISABLE_INACTIVE_U true -#define DISABLE_INACTIVE_V true -#define DISABLE_INACTIVE_W true -#define DISABLE_INACTIVE_E true +#define DEFAULT_STEPPER_TIMEOUT_SEC 120 +#define DISABLE_IDLE_X +#define DISABLE_IDLE_Y +#define DISABLE_IDLE_Z // Disable if the nozzle could fall onto your printed part! +//#define DISABLE_IDLE_I +//#define DISABLE_IDLE_J +//#define DISABLE_IDLE_K +//#define DISABLE_IDLE_U +//#define DISABLE_IDLE_V +//#define DISABLE_IDLE_W +#define DISABLE_IDLE_E // Shut down all idle extruders // Default Minimum Feedrates for printing and travel moves #define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s. °/s for rotational-only moves) Minimum feedrate. Set with M205 S. @@ -1155,7 +1160,7 @@ */ //#define XY_FREQUENCY_LIMIT 10 // (Hz) Maximum frequency of small zigzag infill moves. Set with M201 F. #ifdef XY_FREQUENCY_LIMIT - #define XY_FREQUENCY_MIN_PERCENT 5 // (percent) Minimum FR percentage to apply. Set with M201 G. + #define XY_FREQUENCY_MIN_PERCENT 5 // (%) Minimum FR percentage to apply. Set with M201 G. #endif // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end @@ -1228,7 +1233,7 @@ #define CALIBRATION_NOZZLE_TIP_HEIGHT 1.0 // mm #define CALIBRATION_NOZZLE_OUTER_DIAMETER 2.0 // mm - // Uncomment to enable reporting (required for "G425 V", but consumes PROGMEM). + // Uncomment to enable reporting (required for "G425 V", but consumes flash). //#define CALIBRATION_REPORTING // The true location and dimension the cube/bolt/washer on the bed. @@ -1256,7 +1261,7 @@ //#define CALIBRATION_MEASURE_WMAX // Probing at the exact top center only works if the center is flat. If - // probing on a screwhead or hollow washer, probe near the edges. + // probing on a screw head or hollow washer, probe near the edges. //#define CALIBRATION_MEASURE_AT_TOP_EDGES // Define the pin to read during calibration @@ -1436,7 +1441,7 @@ #define LCD_TIMEOUT_TO_STATUS 15000 // (ms) #if ENABLED(SHOW_BOOTSCREEN) - #define BOOTSCREEN_TIMEOUT 4000 // (ms) Total Duration to display the boot screen(s) + #define BOOTSCREEN_TIMEOUT 3000 // (ms) Total Duration to display the boot screen(s) #if EITHER(HAS_MARLINUI_U8GLIB, TFT_COLOR_UI) #define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving lots of flash) #endif @@ -1620,12 +1625,12 @@ // SD Card Sorting options #if ENABLED(SDCARD_SORT_ALPHA) #define SDSORT_LIMIT 40 // Maximum number of sorted items (10-256). Costs 27 bytes each. - #define FOLDER_SORTING -1 // -1=above 0=none 1=below - #define SDSORT_GCODE false // Allow turning sorting on/off with LCD and M34 G-code. - #define SDSORT_USES_RAM true // Pre-allocate a static array for faster pre-sorting. - #define SDSORT_USES_STACK true // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.) - #define SDSORT_CACHE_NAMES true // Keep sorted items in RAM longer for speedy performance. Most expensive option. - #define SDSORT_DYNAMIC_RAM true // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use! + #define SDSORT_FOLDERS -1 // -1=above 0=none 1=below + #define SDSORT_GCODE false // Enable G-code M34 to set sorting behaviors: M34 S<-1|0|1> F<-1|0|1> + #define SDSORT_USES_RAM false // Pre-allocate a static array for faster pre-sorting. + #define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.) + #define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option. + #define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use! #define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting. // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM. #endif @@ -1824,7 +1829,7 @@ #endif /** - * Status (Info) Screen customizations + * Status (Info) Screen customization * These options may affect code size and screen render time. * Custom status screens can forcibly override these settings. */ @@ -2068,7 +2073,7 @@ #if ENABLED(BABYSTEPPING) //#define INTEGRATED_BABYSTEPPING // EXPERIMENTAL integration of babystepping into the Stepper ISR //#define BABYSTEP_WITHOUT_HOMING - #define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement). + //#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement) //#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA! #define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way //#define BABYSTEP_MILLIMETER_UNITS // Specify BABYSTEP_MULTIPLICATOR_(XY|Z) in mm instead of micro-steps @@ -2079,7 +2084,7 @@ #if ENABLED(DOUBLECLICK_FOR_Z_BABYSTEPPING) #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds. // Note: Extra time may be added to mitigate controller latency. - //#define MOVE_Z_WHEN_IDLE // Jump to the move Z menu on doubleclick when printer is idle. + //#define MOVE_Z_WHEN_IDLE // Jump to the move Z menu on double-click when printer is idle. #if ENABLED(MOVE_Z_WHEN_IDLE) #define MOVE_Z_IDLE_MULTIPLICATOR 1 // Multiply 1mm by this factor for the move step size. #endif @@ -2123,7 +2128,6 @@ #endif //#define ADVANCE_K_EXTRA // Add a second linear advance constant, configurable with M900 L. //#define LA_DEBUG // Print debug information to serial during operation. Disable for production use. - //#define EXPERIMENTAL_SCURVE // Allow S-Curve Acceleration to be used with LA. //#define ALLOW_LOW_EJERK // Allow a DEFAULT_EJERK value of <10. Recommended for direct drive hotends. //#define EXPERIMENTAL_I2S_LA // Allow I2S_STEPPER_STREAM to be used with LA. Performance degrades as the LA step rate reaches ~20kHz. #endif @@ -2216,6 +2220,8 @@ #endif +// @section probes + /** * Thermal Probe Compensation * @@ -2278,7 +2284,7 @@ // 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 Z offset (e.g., as set with M851 Z). - #define PTC_PROBE_HEATING_OFFSET 0.5 + #define PTC_PROBE_HEATING_OFFSET 0.5 // (mm) #endif #endif // PTC_PROBE || PTC_BED || PTC_HOTEND @@ -2333,6 +2339,8 @@ #define G38_MINIMUM_MOVE 0.0275 // (mm) Minimum distance that will produce a move. #endif +// @section motion + // Moves (or segments) with fewer steps than this will be joined with the next move #define MIN_STEPS_PER_SEGMENT 6 @@ -2388,7 +2396,7 @@ //================================= Buffers ================================= //=========================================================================== -// @section motion +// @section gcode // The number of linear moves that can be in the planner at once. // The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g., 8, 16, 32) @@ -2473,11 +2481,13 @@ //#define FULL_REPORT_TO_HOST_FEATURE // Auto-report the machine status like Grbl CNC #endif -// Bad Serial-connections can miss a received command by sending an 'ok' -// Therefore some clients abort after 30 seconds in a timeout. -// Some other clients start sending commands while receiving a 'wait'. -// This "wait" is only sent when the buffer is empty. 1 second is a good value here. -//#define NO_TIMEOUTS 1000 // Milliseconds +/** + * Bad Serial-connections can miss a received command by sending an 'ok' + * Therefore some clients abort after 30 seconds in a timeout. + * Some other clients start sending commands while receiving a 'wait'. + * This "wait" is only sent when the buffer is empty. 1 second is a good value here. + */ +//#define NO_TIMEOUTS 1000 // (ms) // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. #define ADVANCED_OK @@ -2509,6 +2519,8 @@ */ //#define EXTRA_FAN_SPEED +// @section gcode + /** * Firmware-based and LCD-controlled retract * @@ -2543,6 +2555,8 @@ #endif #endif +// @section tool change + /** * Universal tool change settings. * Applies to all types of extruders except where explicitly noted. @@ -2560,9 +2574,9 @@ * Extra G-code to run while executing tool-change commands. Can be used to use an additional * stepper motor (e.g., I axis in Configuration.h) to drive the tool-changer. */ - //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 A0" // Extra G-code to run while executing tool-change command T0 - //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10" // Extra G-code to run while executing tool-change command T1 - //#define EVENT_GCODE_TOOLCHANGE_ALWAYS_RUN // Always execute above G-code sequences. Use with caution! + //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 A0" // Extra G-code to run while executing tool-change command T0 + //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10" // Extra G-code to run while executing tool-change command T1 + //#define EVENT_GCODE_TOOLCHANGE_ALWAYS_RUN // Always execute above G-code sequences. Use with caution! /** * Tool Sensors detect when tools have been picked up or dropped. @@ -2738,10 +2752,10 @@ #endif #if AXIS_IS_TMC_CONFIG(X2) - #define X2_CURRENT 800 - #define X2_CURRENT_HOME X2_CURRENT - #define X2_MICROSTEPS X_MICROSTEPS - #define X2_RSENSE 0.11 + #define X2_CURRENT X_CURRENT + #define X2_CURRENT_HOME X_CURRENT_HOME + #define X2_MICROSTEPS X_MICROSTEPS + #define X2_RSENSE X_RSENSE #define X2_CHAIN_POS -1 //#define X2_INTERPOLATE true //#define X2_HOLD_MULTIPLIER 0.5 @@ -2758,10 +2772,10 @@ #endif #if AXIS_IS_TMC_CONFIG(Y2) - #define Y2_CURRENT 800 - #define Y2_CURRENT_HOME Y2_CURRENT - #define Y2_MICROSTEPS Y_MICROSTEPS - #define Y2_RSENSE 0.11 + #define Y2_CURRENT Y_CURRENT + #define Y2_CURRENT_HOME Y_CURRENT_HOME + #define Y2_MICROSTEPS Y_MICROSTEPS + #define Y2_RSENSE Y_RSENSE #define Y2_CHAIN_POS -1 //#define Y2_INTERPOLATE true //#define Y2_HOLD_MULTIPLIER 0.5 @@ -2778,30 +2792,30 @@ #endif #if AXIS_IS_TMC_CONFIG(Z2) - #define Z2_CURRENT 850 - #define Z2_CURRENT_HOME Z2_CURRENT - #define Z2_MICROSTEPS Z_MICROSTEPS - #define Z2_RSENSE 0.11 + #define Z2_CURRENT Z_CURRENT + #define Z2_CURRENT_HOME Z_CURRENT_HOME + #define Z2_MICROSTEPS Z_MICROSTEPS + #define Z2_RSENSE Z_RSENSE #define Z2_CHAIN_POS -1 //#define Z2_INTERPOLATE true //#define Z2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC_CONFIG(Z3) - #define Z3_CURRENT 800 - #define Z3_CURRENT_HOME Z3_CURRENT - #define Z3_MICROSTEPS Z_MICROSTEPS - #define Z3_RSENSE 0.11 + #define Z3_CURRENT Z_CURRENT + #define Z3_CURRENT_HOME Z_CURRENT_HOME + #define Z3_MICROSTEPS Z_MICROSTEPS + #define Z3_RSENSE Z_RSENSE #define Z3_CHAIN_POS -1 //#define Z3_INTERPOLATE true //#define Z3_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC_CONFIG(Z4) - #define Z4_CURRENT 800 - #define Z4_CURRENT_HOME Z4_CURRENT - #define Z4_MICROSTEPS Z_MICROSTEPS - #define Z4_RSENSE 0.11 + #define Z4_CURRENT Z_CURRENT + #define Z4_CURRENT_HOME Z_CURRENT_HOME + #define Z4_MICROSTEPS Z_MICROSTEPS + #define Z4_RSENSE Z_RSENSE #define Z4_CHAIN_POS -1 //#define Z4_INTERPOLATE true //#define Z4_HOLD_MULTIPLIER 0.5 @@ -2877,63 +2891,63 @@ #endif #if AXIS_IS_TMC_CONFIG(E1) - #define E1_CURRENT 730 + #define E1_CURRENT E0_CURRENT #define E1_MICROSTEPS E0_MICROSTEPS - #define E1_RSENSE 0.11 + #define E1_RSENSE E0_RSENSE #define E1_CHAIN_POS -1 //#define E1_INTERPOLATE true //#define E1_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC_CONFIG(E2) - #define E2_CURRENT 800 + #define E2_CURRENT E0_CURRENT #define E2_MICROSTEPS E0_MICROSTEPS - #define E2_RSENSE 0.11 + #define E2_RSENSE E0_RSENSE #define E2_CHAIN_POS -1 //#define E2_INTERPOLATE true //#define E2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC_CONFIG(E3) - #define E3_CURRENT 800 + #define E3_CURRENT E0_CURRENT #define E3_MICROSTEPS E0_MICROSTEPS - #define E3_RSENSE 0.11 + #define E3_RSENSE E0_RSENSE #define E3_CHAIN_POS -1 //#define E3_INTERPOLATE true //#define E3_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC_CONFIG(E4) - #define E4_CURRENT 800 + #define E4_CURRENT E0_CURRENT #define E4_MICROSTEPS E0_MICROSTEPS - #define E4_RSENSE 0.11 + #define E4_RSENSE E0_RSENSE #define E4_CHAIN_POS -1 //#define E4_INTERPOLATE true //#define E4_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC_CONFIG(E5) - #define E5_CURRENT 800 + #define E5_CURRENT E0_CURRENT #define E5_MICROSTEPS E0_MICROSTEPS - #define E5_RSENSE 0.11 + #define E5_RSENSE E0_RSENSE #define E5_CHAIN_POS -1 //#define E5_INTERPOLATE true //#define E5_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC_CONFIG(E6) - #define E6_CURRENT 800 + #define E6_CURRENT E0_CURRENT #define E6_MICROSTEPS E0_MICROSTEPS - #define E6_RSENSE 0.11 + #define E6_RSENSE E0_RSENSE #define E6_CHAIN_POS -1 //#define E6_INTERPOLATE true //#define E6_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC_CONFIG(E7) - #define E7_CURRENT 800 + #define E7_CURRENT E0_CURRENT #define E7_MICROSTEPS E0_MICROSTEPS - #define E7_RSENSE 0.11 + #define E7_RSENSE E0_RSENSE #define E7_CHAIN_POS -1 //#define E7_INTERPOLATE true //#define E7_HOLD_MULTIPLIER 0.5 @@ -2945,28 +2959,28 @@ * Override default SPI pins for TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160 drivers here. * The default pins can be found in your board's pins file. */ - //#define X_CS_PIN -1 - //#define Y_CS_PIN -1 - //#define Z_CS_PIN -1 - //#define X2_CS_PIN -1 - //#define Y2_CS_PIN -1 - //#define Z2_CS_PIN -1 - //#define Z3_CS_PIN -1 - //#define Z4_CS_PIN -1 - //#define I_CS_PIN -1 - //#define J_CS_PIN -1 - //#define K_CS_PIN -1 - //#define U_CS_PIN -1 - //#define V_CS_PIN -1 - //#define W_CS_PIN -1 - //#define E0_CS_PIN -1 - //#define E1_CS_PIN -1 - //#define E2_CS_PIN -1 - //#define E3_CS_PIN -1 - //#define E4_CS_PIN -1 - //#define E5_CS_PIN -1 - //#define E6_CS_PIN -1 - //#define E7_CS_PIN -1 + //#define X_CS_PIN -1 + //#define Y_CS_PIN -1 + //#define Z_CS_PIN -1 + //#define X2_CS_PIN -1 + //#define Y2_CS_PIN -1 + //#define Z2_CS_PIN -1 + //#define Z3_CS_PIN -1 + //#define Z4_CS_PIN -1 + //#define I_CS_PIN -1 + //#define J_CS_PIN -1 + //#define K_CS_PIN -1 + //#define U_CS_PIN -1 + //#define V_CS_PIN -1 + //#define W_CS_PIN -1 + //#define E0_CS_PIN -1 + //#define E1_CS_PIN -1 + //#define E2_CS_PIN -1 + //#define E3_CS_PIN -1 + //#define E4_CS_PIN -1 + //#define E5_CS_PIN -1 + //#define E6_CS_PIN -1 + //#define E7_CS_PIN -1 /** * Software option for SPI driven drivers (TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160). @@ -2974,9 +2988,9 @@ * but you can override or define them here. */ //#define TMC_USE_SW_SPI - //#define TMC_SW_MOSI -1 - //#define TMC_SW_MISO -1 - //#define TMC_SW_SCK -1 + //#define TMC_SPI_MOSI -1 + //#define TMC_SPI_MISO -1 + //#define TMC_SPI_SCK -1 // @section tmc/serial @@ -3152,7 +3166,7 @@ * * It is recommended to set HOMING_BUMP_MM to { 0, 0, 0 }. * - * SPI_ENDSTOPS *** Beta feature! *** TMC2130/TMC5160 Only *** + * SPI_ENDSTOPS *** TMC2130/TMC5160 Only *** * Poll the driver through SPI to determine load when homing. * Removes the need for a wire from DIAG1 to an endstop pin. * @@ -3180,7 +3194,7 @@ //#define U_STALL_SENSITIVITY 8 //#define V_STALL_SENSITIVITY 8 //#define W_STALL_SENSITIVITY 8 - //#define SPI_ENDSTOPS // TMC2130 only + //#define SPI_ENDSTOPS // TMC2130/TMC5160 only //#define IMPROVE_HOMING_RELIABILITY #endif @@ -3199,8 +3213,7 @@ //#define TMC_HOME_PHASE { 896, 896, 896 } /** - * Beta feature! - * Create a 50/50 square wave step pulse optimal for stepper drivers. + * Step on both rising and falling edge signals (as with a square wave). */ #define SQUARE_WAVE_STEPPING @@ -3236,9 +3249,8 @@ /** * TWI/I2C BUS * - * This feature is an EXPERIMENTAL feature so it shall not be used on production - * machines. Enabling this will allow you to send and receive I2C data from slave - * devices on the bus. + * This feature is EXPERIMENTAL but may be useful for custom I2C peripherals. + * Enable this to send and receive I2C data from slave devices on the bus. * * ; Example #1 * ; This macro send the string "Marlin" to the slave device with address 0x63 (99) @@ -3285,7 +3297,7 @@ //#define PHOTOGRAPH_PIN 23 // Canon Hack Development Kit - // https://captain-slow.dk/2014/03/09/3d-printing-timelapses/ + // https://web.archive.org/web/20200920094805/https://captain-slow.dk/2014/03/09/3d-printing-timelapses/ //#define CHDK_PIN 4 // Optional second move with delay to trigger the camera shutter @@ -3439,7 +3451,7 @@ * Feed rates are set by the F parameter of a move command e.g. G1 X0 Y10 F6000 * Laser power would be calculated by bit shifting off 8 LSB's. In binary this is div 256. * The calculation gives us ocr values from 0 to 255, values over F65535 will be set as 255 . - * More refined power control such as compesation for accell/decell will be addressed in future releases. + * More refined power control such as compensation for accel/decel will be addressed in future releases. * * M5 I clears inline mode and set power to 0, M5 sets the power output to 0 but leaves inline mode on. */ @@ -3447,8 +3459,8 @@ /** * Enable M3 commands for laser mode inline power planner syncing. * This feature enables any M3 S-value to be injected into the block buffers while in - * CUTTER_MODE_CONTINUOUS. The option allows M3 laser power to be commited without waiting - * for a planner syncronization + * CUTTER_MODE_CONTINUOUS. The option allows M3 laser power to be committed without waiting + * for a planner synchronization */ //#define LASER_POWER_SYNC @@ -3662,7 +3674,7 @@ * Use 'M200 [T] L' to override and 'M502' to reset. * A non-zero value activates Volume-based Extrusion Limiting. */ - #define DEFAULT_VOLUMETRIC_EXTRUDER_LIMIT 0.00 // (mm^3/sec) + #define DEFAULT_VOLUMETRIC_EXTRUDER_LIMIT 0.00 // (mm^3/sec) #endif #endif @@ -3686,7 +3698,9 @@ //#define GCODE_QUOTED_STRINGS // Support for quoted string parameters #endif -// Support for MeatPack G-code compression (https://github.com/scottmudge/OctoPrint-MeatPack) +/** + * Support for MeatPack G-code compression (https://github.com/scottmudge/OctoPrint-MeatPack) + */ //#define MEATPACK_ON_SERIAL_PORT_1 //#define MEATPACK_ON_SERIAL_PORT_2 @@ -3718,8 +3732,6 @@ //#define VARIABLE_G0_FEEDRATE // The G0 feedrate is set by F in G0 motion mode #endif -// @section gcode - /** * Startup commands * @@ -3884,7 +3896,7 @@ * Wiki: https://wiki.aus3d.com.au/Magnetic_Encoder * Github: https://github.com/Aus3D/MagneticEncoder * - * Supplier: https://aus3d.com.au/magnetic-encoder-module + * Supplier: https://aus3d.com.au/products/magnetic-encoder-module * Alternative Supplier: https://reliabuild3d.com/ * * Reliabuild encoders have been modified to improve reliability. @@ -4071,13 +4083,17 @@ #endif /** - * WiFi Support (Espressif ESP32 WiFi) + * Native ESP32 board with WiFi or add-on ESP32 WiFi-101 module */ -//#define WIFISUPPORT // Marlin embedded WiFi management +//#define WIFISUPPORT // Marlin embedded WiFi management. Not needed for simple WiFi serial port. //#define ESP3D_WIFISUPPORT // ESP3D Library WiFi management (https://github.com/luc-github/ESP3DLib) -#if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) - //#define WEBSUPPORT // Start a webserver (which may include auto-discovery) +/** + * Extras for an ESP32-based motherboard with WIFISUPPORT + * These options don't apply to add-on WiFi modules based on ESP32 WiFi101. + */ +#if ENABLED(WIFISUPPORT) + //#define WEBSUPPORT // Start a webserver (which may include auto-discovery) using SPIFFS //#define OTASUPPORT // Support over-the-air firmware updates //#define WIFI_CUSTOM_COMMAND // Accept feature config commands (e.g., WiFi ESP3D) from the host @@ -4127,35 +4143,34 @@ // Add an LCD menu for MMU2 //#define MMU2_MENUS - #if EITHER(MMU2_MENUS, HAS_PRUSA_MMU2S) - // Settings for filament load / unload from the LCD menu. - // This is for Průša MK3-style extruders. Customize for your hardware. - #define MMU2_FILAMENTCHANGE_EJECT_FEED 80.0 - #define MMU2_LOAD_TO_NOZZLE_SEQUENCE \ - { 7.2, 1145 }, \ - { 14.4, 871 }, \ - { 36.0, 1393 }, \ - { 14.4, 871 }, \ - { 50.0, 198 } - - #define MMU2_RAMMING_SEQUENCE \ - { 1.0, 1000 }, \ - { 1.0, 1500 }, \ - { 2.0, 2000 }, \ - { 1.5, 3000 }, \ - { 2.5, 4000 }, \ - { -15.0, 5000 }, \ - { -14.0, 1200 }, \ - { -6.0, 600 }, \ - { 10.0, 700 }, \ - { -10.0, 400 }, \ - { -50.0, 2000 } - #endif + + // Settings for filament load / unload from the LCD menu. + // This is for Průša MK3-style extruders. Customize for your hardware. + #define MMU2_FILAMENTCHANGE_EJECT_FEED 80.0 + #define MMU2_LOAD_TO_NOZZLE_SEQUENCE \ + { 7.2, 1145 }, \ + { 14.4, 871 }, \ + { 36.0, 1393 }, \ + { 14.4, 871 }, \ + { 50.0, 198 } + + #define MMU2_RAMMING_SEQUENCE \ + { 1.0, 1000 }, \ + { 1.0, 1500 }, \ + { 2.0, 2000 }, \ + { 1.5, 3000 }, \ + { 2.5, 4000 }, \ + { -15.0, 5000 }, \ + { -14.0, 1200 }, \ + { -6.0, 600 }, \ + { 10.0, 700 }, \ + { -10.0, 400 }, \ + { -50.0, 2000 } /** * Using a sensor like the MMU2S * This mode requires a MK3S extruder with a sensor at the extruder idler, like the MMU2S. - * See https://help.prusa3d.com/en/guide/3b-mk3s-mk2-5s-extruder-upgrade_41560, step 11 + * See https://help.prusa3d.com/guide/3b-mk3s-mk2-5s-extruder-upgrade_41560#42048, step 11 */ #if HAS_PRUSA_MMU2S #define MMU2_C0_RETRY 5 // Number of retries (total time = timeout*retries) diff --git a/Marlin/Makefile b/Marlin/Makefile index ca7cacaa6acb..e5ba9cb341e4 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -63,8 +63,8 @@ HARDWARE_MOTHERBOARD ?= 1020 ifeq ($(OS),Windows_NT) # Windows - ARDUINO_INSTALL_DIR ?= ${HOME}/Arduino - ARDUINO_USER_DIR ?= ${HOME}/Arduino + ARDUINO_INSTALL_DIR ?= ${HOME}/AppData/Local/Arduino + ARDUINO_USER_DIR ?= ${HOME}/Documents/Arduino else UNAME_S := $(shell uname -s) ifeq ($(UNAME_S),Linux) @@ -82,11 +82,11 @@ endif # Arduino source install directory, and version number # On most linuxes this will be /usr/share/arduino -ARDUINO_INSTALL_DIR ?= ${HOME}/Arduino -ARDUINO_VERSION ?= 106 +ARDUINO_INSTALL_DIR ?= ${HOME}/AppData/Local/Arduino # C:/Users/${USERNAME}/AppData/Local/Arduino +ARDUINO_VERSION ?= 10819 # The installed Libraries are in the User folder -ARDUINO_USER_DIR ?= ${HOME}/Arduino +ARDUINO_USER_DIR ?= ${HOME}/Documents/Arduino # You can optionally set a path to the avr-gcc tools. # Requires a trailing slash. For example, /usr/local/avr-gcc/bin/ @@ -656,18 +656,18 @@ ifeq ($(HARDWARE_VARIANT), $(filter $(HARDWARE_VARIANT),arduino Teensy Sanguino) # Old libraries (avr-core 1.6.21 < / Arduino < 1.6.8) VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/SPI # New libraries (avr-core >= 1.6.21 / Arduino >= 1.6.8) - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/SPI/src + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/arduino/avr/1.8.6/libraries/SPI/src endif ifeq ($(IS_MCU),1) - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/cores/arduino + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/arduino/avr/1.8.6/cores/arduino # Old libraries (avr-core 1.6.21 < / Arduino < 1.6.8) VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/SPI VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/SoftwareSerial # New libraries (avr-core >= 1.6.21 / Arduino >= 1.6.8) - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/SPI/src - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/SoftwareSerial/src + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/arduino/avr/1.8.6/libraries/SPI/src + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/arduino/avr/1.8.6/libraries/SoftwareSerial/src endif VPATH += $(ARDUINO_INSTALL_DIR)/libraries/LiquidCrystal/src @@ -681,17 +681,17 @@ ifeq ($(WIRE), 1) VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/Wire VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/Wire/utility # New libraries (avr-core >= 1.6.21 / Arduino >= 1.6.8) - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/Wire/src - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/libraries/Wire/src/utility + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/avr/1.8.6/libraries/Wire/src + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/avr/1.8.6/libraries/Wire/src/utility endif ifeq ($(NEOPIXEL), 1) VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Adafruit_NeoPixel endif ifeq ($(U8GLIB), 1) -VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib -VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib/csrc -VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib/cppsrc -VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib/fntsrc +VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib-HAL +VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib-HAL/src +# VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib +# VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib/src endif ifeq ($(TMC), 1) VPATH += $(ARDUINO_INSTALL_DIR)/libraries/TMCStepper/src @@ -700,9 +700,9 @@ endif ifeq ($(HARDWARE_VARIANT), arduino) HARDWARE_SUB_VARIANT ?= mega - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/variants/$(HARDWARE_SUB_VARIANT) + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/avr/1.8.6/variants/$(HARDWARE_SUB_VARIANT) else ifeq ($(HARDWARE_VARIANT), Sanguino) - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/marlin/avr/variants/sanguino + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/avr/1.8.6/variants/sanguino else ifeq ($(HARDWARE_VARIANT), archim) VPATH += $(ARDUINO_INSTALL_DIR)/packages/ultimachine/hardware/sam/1.6.9-b/system/libsam VPATH += $(ARDUINO_INSTALL_DIR)/packages/ultimachine/hardware/sam/1.6.9-b/system/CMSIS/CMSIS/Include/ @@ -718,7 +718,7 @@ else ifeq ($(HARDWARE_VARIANT), archim) LDLIBS = $(ARDUINO_INSTALL_DIR)/packages/ultimachine/hardware/sam/1.6.9-b/variants/archim/libsam_sam3x8e_gcc_rel.a else HARDWARE_SUB_VARIANT ?= standard - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/$(HARDWARE_VARIANT)/variants/$(HARDWARE_SUB_VARIANT) + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/avr/1.8.6/variants/$(HARDWARE_SUB_VARIANT) endif LIB_SRC = wiring.c \ @@ -733,7 +733,7 @@ endif ifeq ($(HARDWARE_VARIANT), Teensy) LIB_SRC = wiring.c - VPATH += $(ARDUINO_INSTALL_DIR)/hardware/teensy/cores/teensy + VPATH += $(ARDUINO_INSTALL_DIR)/packages/arduino/hardware/teensy/cores/teensy endif LIB_CXXSRC = WMath.cpp WString.cpp Print.cpp SPI.cpp @@ -880,7 +880,7 @@ AVRDUDE_WRITE_FLASH = -Uflash:w:$(BUILD_DIR)/$(TARGET).hex:i ifeq ($(shell uname -s), Linux) AVRDUDE_CONF = /etc/avrdude/avrdude.conf else - AVRDUDE_CONF = $(ARDUINO_INSTALL_DIR)/hardware/tools/avr/etc/avrdude.conf + AVRDUDE_CONF = $(ARDUINO_INSTALL_DIR)/packages/arduino/tools/avrdude/6.3.0-arduino17/etc/avrdude.conf endif AVRDUDE_FLAGS = -D -C$(AVRDUDE_CONF) \ -p$(PROG_MCU) -P$(AVRDUDE_PORT) -c$(AVRDUDE_PROGRAMMER) \ diff --git a/Marlin/Marlin.ino b/Marlin/Marlin.ino index 57c825445fb5..066cc1717d35 100644 --- a/Marlin/Marlin.ino +++ b/Marlin/Marlin.ino @@ -2,7 +2,7 @@ Marlin Firmware - (c) 2011-2020 MarlinFirmware + (c) 2011-2024 MarlinFirmware Portions of Marlin are (c) by their respective authors. All code complies with GPLv2 and/or GPLv3 @@ -27,7 +27,7 @@ Configuration - https://github.com/MarlinFirmware/Configurations Example configurations for several printer models. - - https://www.youtube.com/watch?v=3gwWVFtdg-4 + - https://youtu.be/3gwWVFtdg-4 A good 20-minute overview of Marlin configuration by Tom Sanladerer. (Applies to Marlin 1.0.x, so Jerk and Acceleration should be halved.) Also... https://www.google.com/search?tbs=vid%3A1&q=configure+marlin diff --git a/Marlin/Version.h b/Marlin/Version.h index 8287902b687e..ac1fcce3af12 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -28,7 +28,7 @@ /** * Marlin release version identifier */ -//#define SHORT_BUILD_VERSION "2.1.2.1" +//#define SHORT_BUILD_VERSION "2.1.2.2" /** * Verbose version identifier which should contain a reference to the location @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-05-16" +//#define STRING_DISTRIBUTION_DATE "2024-02-08" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/config.ini b/Marlin/config.ini index e61462336994..439c7e9e1aa1 100644 --- a/Marlin/config.ini +++ b/Marlin/config.ini @@ -3,6 +3,6 @@ # config.ini - Options to apply before the build # [config:base] -ini_use_config = all@rowan-config/base_cr10v3.ini, all@rowan-config/rowan_cr10v3.ini, all@rowan-config/department.ini -ini_config_vers = 02010201 +ini_use_config = example/Creality/CR-10 V3 @ release-2.1.2.2, all@rowan-config/rowan_cr10v3.ini, all@rowan-config/department.ini +ini_config_vers = 02010202 ; config_export = 2 diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index 5382eb36a2bd..3dadfafe8c2a 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -63,18 +63,23 @@ void save_reset_reason() { void MarlinHAL::init() { // Init Servo Pins - #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) #if HAS_SERVO_0 - INIT_SERVO(0); + OUT_WRITE(SERVO0_PIN, LOW); #endif #if HAS_SERVO_1 - INIT_SERVO(1); + OUT_WRITE(SERVO1_PIN, LOW); #endif #if HAS_SERVO_2 - INIT_SERVO(2); + OUT_WRITE(SERVO2_PIN, LOW); #endif #if HAS_SERVO_3 - INIT_SERVO(3); + OUT_WRITE(SERVO3_PIN, LOW); + #endif + #if HAS_SERVO_4 + OUT_WRITE(SERVO4_PIN, LOW); + #endif + #if HAS_SERVO_5 + OUT_WRITE(SERVO5_PIN, LOW); #endif init_pwm_timers(); // Init user timers to default frequency - 1000HZ @@ -145,12 +150,12 @@ void MarlinHAL::reboot() { // Free Memory Accessor // ------------------------ -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../../sd/SdFatUtil.h" int freeMemory() { return SdFatUtil::FreeRam(); } -#else // !SDSUPPORT +#else // !HAS_MEDIA extern "C" { extern char __bss_end; @@ -167,6 +172,6 @@ void MarlinHAL::reboot() { } } -#endif // !SDSUPPORT +#endif // !HAS_MEDIA #endif // __AVR__ diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index d458790979ff..0f8825255af9 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 @@ -140,15 +142,15 @@ typedef Servo hal_servo_t; #endif #define LCD_SERIAL lcdSerial #if HAS_DGUS_LCD - #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.get_tx_buffer_free() + #define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.get_tx_buffer_free() #endif #endif // // ADC // -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_VREF_MV 5000 +#define HAL_ADC_RESOLUTION 10 // // Pin Mapping for M42, M43, M226 diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index dc98f2f79e71..db6a12734d4d 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -119,7 +119,6 @@ void spiBegin() { while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } } - /** begin spi transaction */ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { // Based on Arduino SPI library @@ -175,7 +174,6 @@ void spiBegin() { SPSR = clockDiv | 0x01; } - #else // SOFTWARE_SPI || FORCE_SOFT_SPI // ------------------------ @@ -198,7 +196,7 @@ void spiBegin() { // output pin high - like sending 0xFF WRITE(SD_MOSI_PIN, HIGH); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { WRITE(SD_SCK_PIN, HIGH); nop; // adjust so SCK is nice @@ -225,7 +223,7 @@ void spiBegin() { void spiSend(uint8_t data) { // no interrupts during byte send - about 8µs cli(); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { WRITE(SD_SCK_PIN, LOW); WRITE(SD_MOSI_PIN, data & 0x80); data <<= 1; diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h index 7eb76000d66e..a40730e0a87f 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -34,12 +34,9 @@ #include #include "../../inc/MarlinConfigPre.h" +#include "../../core/types.h" #include "../../core/serial_hook.h" -#ifndef SERIAL_PORT - #define SERIAL_PORT 0 -#endif - #ifndef USBCON // The presence of the UBRRH register is used to detect a UART. @@ -138,10 +135,6 @@ #define BYTE 0 - // Templated type selector - template struct TypeSelector { typedef T type;} ; - template struct TypeSelector { typedef F type; }; - template class MarlinSerial { protected: @@ -164,7 +157,7 @@ static constexpr B_U2Xx B_U2X = 0; // Base size of type on buffer size - typedef typename TypeSelector<(Cfg::RX_SIZE>256), uint16_t, uint8_t>::type ring_buffer_pos_t; + typedef uvalue_t(Cfg::RX_SIZE - 1) ring_buffer_pos_t; struct ring_buffer_r { volatile ring_buffer_pos_t head, tail; @@ -283,7 +276,7 @@ static constexpr bool DROPPED_RX = false; static constexpr bool RX_FRAMING_ERRORS = false; static constexpr bool MAX_RX_QUEUED = false; - static constexpr bool RX_OVERRUNS = BOTH(HAS_DGUS_LCD, SERIAL_STATS_RX_BUFFER_OVERRUNS); + static constexpr bool RX_OVERRUNS = ALL(HAS_DGUS_LCD, SERIAL_STATS_RX_BUFFER_OVERRUNS); }; typedef Serial1Class< MarlinSerial< LCDSerialCfg > > MSerialLCD; diff --git a/Marlin/src/HAL/AVR/Servo.cpp b/Marlin/src/HAL/AVR/Servo.cpp index 0a1ef5337ae9..8ce9bc11b8cc 100644 --- a/Marlin/src/HAL/AVR/Servo.cpp +++ b/Marlin/src/HAL/AVR/Servo.cpp @@ -63,7 +63,6 @@ static volatile int8_t Channel[_Nbr_16timers]; // counter for the servo being pulsed for each timer (or -1 if refresh interval) - /************ static functions common to all instances ***********************/ static inline void handle_interrupts(const timer16_Sequence_t timer, volatile uint16_t* TCNTn, volatile uint16_t* OCRnA) { diff --git a/Marlin/src/HAL/AVR/eeprom.cpp b/Marlin/src/HAL/AVR/eeprom.cpp index 8d084dec7fdf..6465e4702544 100644 --- a/Marlin/src/HAL/AVR/eeprom.cpp +++ b/Marlin/src/HAL/AVR/eeprom.cpp @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) +#if ANY(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) /** * PersistentStore for Arduino-style EEPROM interface diff --git a/Marlin/src/HAL/AVR/endstop_interrupts.h b/Marlin/src/HAL/AVR/endstop_interrupts.h index 5511aa406fec..52b3ad98d3b3 100644 --- a/Marlin/src/HAL/AVR/endstop_interrupts.h +++ b/Marlin/src/HAL/AVR/endstop_interrupts.h @@ -91,7 +91,6 @@ void endstop_ISR() { endstops.update(); } #endif - // Install Pin change interrupt for a pin. Can be called multiple times. void pciSetup(const int8_t pin) { if (digitalPinHasPCICR(pin)) { @@ -120,7 +119,7 @@ void pciSetup(const int8_t pin) { void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - #if HAS_X_MAX + #if USE_X_MAX #if (digitalPinToInterrupt(X_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(X_MAX_PIN); #else @@ -128,7 +127,7 @@ void setup_endstop_interrupts() { pciSetup(X_MAX_PIN); #endif #endif - #if HAS_X_MIN + #if USE_X_MIN #if (digitalPinToInterrupt(X_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(X_MIN_PIN); #else @@ -136,7 +135,7 @@ void setup_endstop_interrupts() { pciSetup(X_MIN_PIN); #endif #endif - #if HAS_Y_MAX + #if USE_Y_MAX #if (digitalPinToInterrupt(Y_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Y_MAX_PIN); #else @@ -144,7 +143,7 @@ void setup_endstop_interrupts() { pciSetup(Y_MAX_PIN); #endif #endif - #if HAS_Y_MIN + #if USE_Y_MIN #if (digitalPinToInterrupt(Y_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Y_MIN_PIN); #else @@ -152,7 +151,7 @@ void setup_endstop_interrupts() { pciSetup(Y_MIN_PIN); #endif #endif - #if HAS_Z_MAX + #if USE_Z_MAX #if (digitalPinToInterrupt(Z_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z_MAX_PIN); #else @@ -160,7 +159,7 @@ void setup_endstop_interrupts() { pciSetup(Z_MAX_PIN); #endif #endif - #if HAS_Z_MIN + #if USE_Z_MIN #if (digitalPinToInterrupt(Z_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z_MIN_PIN); #else @@ -168,97 +167,97 @@ void setup_endstop_interrupts() { pciSetup(Z_MIN_PIN); #endif #endif - #if HAS_I_MAX + #if USE_I_MAX #if (digitalPinToInterrupt(I_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(I_MAX_PIN); #else - static_assert(digitalPinHasPCICR(I_MAX_PIN), "I_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(I_MAX_PIN), "I_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(I_MAX_PIN); #endif - #elif HAS_I_MIN + #elif USE_I_MIN #if (digitalPinToInterrupt(I_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(I_MIN_PIN); #else - static_assert(digitalPinHasPCICR(I_MIN_PIN), "I_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(I_MIN_PIN), "I_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(I_MIN_PIN); #endif #endif - #if HAS_J_MAX + #if USE_J_MAX #if (digitalPinToInterrupt(J_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(J_MAX_PIN); #else - static_assert(digitalPinHasPCICR(J_MAX_PIN), "J_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(J_MAX_PIN), "J_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(J_MAX_PIN); #endif - #elif HAS_J_MIN + #elif USE_J_MIN #if (digitalPinToInterrupt(J_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(J_MIN_PIN); #else - static_assert(digitalPinHasPCICR(J_MIN_PIN), "J_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(J_MIN_PIN), "J_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(J_MIN_PIN); #endif #endif - #if HAS_K_MAX + #if USE_K_MAX #if (digitalPinToInterrupt(K_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(K_MAX_PIN); #else - static_assert(digitalPinHasPCICR(K_MAX_PIN), "K_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(K_MAX_PIN), "K_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(K_MAX_PIN); #endif - #elif HAS_K_MIN + #elif USE_K_MIN #if (digitalPinToInterrupt(K_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(K_MIN_PIN); #else - static_assert(digitalPinHasPCICR(K_MIN_PIN), "K_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(K_MIN_PIN), "K_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(K_MIN_PIN); #endif #endif - #if HAS_U_MAX + #if USE_U_MAX #if (digitalPinToInterrupt(U_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(U_MAX_PIN); #else - static_assert(digitalPinHasPCICR(U_MAX_PIN), "U_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(U_MAX_PIN), "U_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(U_MAX_PIN); #endif - #elif HAS_U_MIN + #elif USE_U_MIN #if (digitalPinToInterrupt(U_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(U_MIN_PIN); #else - static_assert(digitalPinHasPCICR(U_MIN_PIN), "U_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(U_MIN_PIN), "U_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(U_MIN_PIN); #endif #endif - #if HAS_V_MAX + #if USE_V_MAX #if (digitalPinToInterrupt(V_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(V_MAX_PIN); #else - static_assert(digitalPinHasPCICR(V_MAX_PIN), "V_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(V_MAX_PIN), "V_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(V_MAX_PIN); #endif - #elif HAS_V_MIN + #elif USE_V_MIN #if (digitalPinToInterrupt(V_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(V_MIN_PIN); #else - static_assert(digitalPinHasPCICR(V_MIN_PIN), "V_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(V_MIN_PIN), "V_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(V_MIN_PIN); #endif #endif - #if HAS_W_MAX + #if USE_W_MAX #if (digitalPinToInterrupt(W_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(W_MAX_PIN); #else - static_assert(digitalPinHasPCICR(W_MAX_PIN), "W_MAX_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(W_MAX_PIN), "W_MAX_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(W_MAX_PIN); #endif - #elif HAS_W_MIN + #elif USE_W_MIN #if (digitalPinToInterrupt(W_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(W_MIN_PIN); #else - static_assert(digitalPinHasPCICR(W_MIN_PIN), "W_MIN_PIN is not interrupt-capable"); + static_assert(digitalPinHasPCICR(W_MIN_PIN), "W_MIN_PIN is not interrupt-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."); pciSetup(W_MIN_PIN); #endif #endif - #if HAS_X2_MAX + #if USE_X2_MAX #if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(X2_MAX_PIN); #else @@ -266,7 +265,7 @@ void setup_endstop_interrupts() { pciSetup(X2_MAX_PIN); #endif #endif - #if HAS_X2_MIN + #if USE_X2_MIN #if (digitalPinToInterrupt(X2_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(X2_MIN_PIN); #else @@ -274,7 +273,7 @@ void setup_endstop_interrupts() { pciSetup(X2_MIN_PIN); #endif #endif - #if HAS_Y2_MAX + #if USE_Y2_MAX #if (digitalPinToInterrupt(Y2_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Y2_MAX_PIN); #else @@ -282,7 +281,7 @@ void setup_endstop_interrupts() { pciSetup(Y2_MAX_PIN); #endif #endif - #if HAS_Y2_MIN + #if USE_Y2_MIN #if (digitalPinToInterrupt(Y2_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Y2_MIN_PIN); #else @@ -290,7 +289,7 @@ void setup_endstop_interrupts() { pciSetup(Y2_MIN_PIN); #endif #endif - #if HAS_Z2_MAX + #if USE_Z2_MAX #if (digitalPinToInterrupt(Z2_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z2_MAX_PIN); #else @@ -298,7 +297,7 @@ void setup_endstop_interrupts() { pciSetup(Z2_MAX_PIN); #endif #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN #if (digitalPinToInterrupt(Z2_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z2_MIN_PIN); #else @@ -306,7 +305,7 @@ void setup_endstop_interrupts() { pciSetup(Z2_MIN_PIN); #endif #endif - #if HAS_Z3_MAX + #if USE_Z3_MAX #if (digitalPinToInterrupt(Z3_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z3_MAX_PIN); #else @@ -314,7 +313,7 @@ void setup_endstop_interrupts() { pciSetup(Z3_MAX_PIN); #endif #endif - #if HAS_Z3_MIN + #if USE_Z3_MIN #if (digitalPinToInterrupt(Z3_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z3_MIN_PIN); #else @@ -322,7 +321,7 @@ void setup_endstop_interrupts() { pciSetup(Z3_MIN_PIN); #endif #endif - #if HAS_Z4_MAX + #if USE_Z4_MAX #if (digitalPinToInterrupt(Z4_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z4_MAX_PIN); #else @@ -330,7 +329,7 @@ void setup_endstop_interrupts() { pciSetup(Z4_MAX_PIN); #endif #endif - #if HAS_Z4_MIN + #if USE_Z4_MIN #if (digitalPinToInterrupt(Z4_MIN_PIN) != NOT_AN_INTERRUPT) _ATTACH(Z4_MIN_PIN); #else diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index 0b2b8fd0b3a4..6da68e6245d3 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -132,7 +132,7 @@ void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { DEBUG_ECHOLNPGM("f=", f); DEBUG_ECHOLNPGM("(prescaler loop)"); - LOOP_L_N(i, COUNT(prescaler)) { // Loop through all prescaler values + for (uint8_t i = 0; i < COUNT(prescaler); ++i) { // Loop through all prescaler values const uint32_t p = prescaler[i]; // Extend to 32 bits for calculations DEBUG_ECHOLNPGM("prescaler[", i, "]=", p); uint16_t res_fast_temp, res_pc_temp; @@ -232,7 +232,7 @@ void MarlinHAL::init_pwm_timers() { #endif }; - LOOP_L_N(i, COUNT(pwm_pin)) + for (uint8_t i = 0; i < COUNT(pwm_pin); ++i) set_pwm_frequency(pwm_pin[i], 1000); } diff --git a/Marlin/src/HAL/AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h index 8a5e4650f4c6..4516d9cd540f 100644 --- a/Marlin/src/HAL/AVR/fastio.h +++ b/Marlin/src/HAL/AVR/fastio.h @@ -255,84 +255,6 @@ enum ClockSource2 : uint8_t { #define SET_FOCB(T,V) SET_FOC(T,B,V) #define SET_FOCC(T,V) SET_FOC(T,C,V) -#if 0 - -/** - * PWM availability macros - */ - -// Determine which hardware PWMs are already in use -#define _PWM_CHK_FAN_B(P) (P == E0_AUTO_FAN_PIN || P == E1_AUTO_FAN_PIN || P == E2_AUTO_FAN_PIN || P == E3_AUTO_FAN_PIN || P == E4_AUTO_FAN_PIN || P == E5_AUTO_FAN_PIN || P == E6_AUTO_FAN_PIN || P == E7_AUTO_FAN_PIN || P == CHAMBER_AUTO_FAN_PIN || P == COOLER_AUTO_FAN_PIN) -#if PIN_EXISTS(CONTROLLER_FAN) - #define PWM_CHK_FAN_B(P) (_PWM_CHK_FAN_B(P) || P == CONTROLLER_FAN_PIN) -#else - #define PWM_CHK_FAN_B(P) _PWM_CHK_FAN_B(P) -#endif - -#if ANY_PIN(FAN, FAN1, FAN2, FAN3, FAN4, FAN5, FAN6, FAN7) - #if PIN_EXISTS(FAN7) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN || P == FAN5_PIN || P == FAN6_PIN || P == FAN7_PIN) - #elif PIN_EXISTS(FAN6) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN || P == FAN5_PIN || P == FAN6_PIN) - #elif PIN_EXISTS(FAN5) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN || P == FAN5_PIN) - #elif PIN_EXISTS(FAN4) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN || P == FAN4_PIN) - #elif PIN_EXISTS(FAN3) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN || P == FAN3_PIN) - #elif PIN_EXISTS(FAN2) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN || P == FAN2_PIN) - #elif PIN_EXISTS(FAN1) - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN || P == FAN1_PIN) - #else - #define PWM_CHK_FAN_A(P) (P == FAN0_PIN) - #endif -#else - #define PWM_CHK_FAN_A(P) false -#endif - -#if HAS_MOTOR_CURRENT_PWM - #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) - #define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E_PIN || P == MOTOR_CURRENT_PWM_E0_PIN || P == MOTOR_CURRENT_PWM_E1_PIN || P == MOTOR_CURRENT_PWM_Z_PIN || P == MOTOR_CURRENT_PWM_XY_PIN) - #elif PIN_EXISTS(MOTOR_CURRENT_PWM_Z) - #define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E_PIN || P == MOTOR_CURRENT_PWM_E0_PIN || P == MOTOR_CURRENT_PWM_E1_PIN || P == MOTOR_CURRENT_PWM_Z_PIN) - #else - #define PWM_CHK_MOTOR_CURRENT(P) (P == MOTOR_CURRENT_PWM_E_PIN || P == MOTOR_CURRENT_PWM_E0_PIN || P == MOTOR_CURRENT_PWM_E1_PIN) - #endif -#else - #define PWM_CHK_MOTOR_CURRENT(P) false -#endif - -#ifdef NUM_SERVOS - #if AVR_ATmega2560_FAMILY - #define PWM_CHK_SERVO(P) (P == 5 || (NUM_SERVOS > 12 && P == 6) || (NUM_SERVOS > 24 && P == 46)) // PWMS 3A, 4A & 5A - #elif AVR_ATmega2561_FAMILY - #define PWM_CHK_SERVO(P) (P == 5) // PWM3A - #elif AVR_ATmega1284_FAMILY - #define PWM_CHK_SERVO(P) false - #elif AVR_AT90USB1286_FAMILY - #define PWM_CHK_SERVO(P) (P == 16) // PWM3A - #elif AVR_ATmega328_FAMILY - #define PWM_CHK_SERVO(P) false - #endif -#else - #define PWM_CHK_SERVO(P) false -#endif - -#if ENABLED(BARICUDA) - #if HAS_HEATER_1 && HAS_HEATER_2 - #define PWM_CHK_HEATER(P) (P == HEATER_1_PIN || P == HEATER_2_PIN) - #elif HAS_HEATER_1 - #define PWM_CHK_HEATER(P) (P == HEATER_1_PIN) - #endif -#else - #define PWM_CHK_HEATER(P) false -#endif - -#define PWM_CHK(P) (PWM_CHK_HEATER(P) || PWM_CHK_SERVO(P) || PWM_CHK_MOTOR_CURRENT(P) || PWM_CHK_FAN_A(P) || PWM_CHK_FAN_B(P)) - -#endif // PWM_CHK is not used in Marlin - // define which hardware PWMs are available for the current CPU // all timer 1 PWMS deleted from this list because they are never available #if AVR_ATmega2560_FAMILY diff --git a/Marlin/src/HAL/AVR/fastio/fastio_1280.h b/Marlin/src/HAL/AVR/fastio/fastio_1280.h index e6ecbabb800f..633774dda916 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_1280.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_1280.h @@ -27,6 +27,7 @@ * Hardware Pin : 02 03 06 07 01 05 15 16 17 18 23 24 25 26 64 63 13 12 46 45 44 43 78 77 76 75 74 73 72 71 60 59 58 57 56 55 54 53 50 70 52 51 42 41 40 39 38 37 36 35 22 21 20 19 97 96 95 94 93 92 91 90 89 88 87 86 85 84 83 82 | 04 08 09 10 11 14 27 28 29 30 31 32 33 34 47 48 49 61 62 65 66 67 68 69 79 80 81 98 99 100 * Port : E0 E1 E4 E5 G5 E3 H3 H4 H5 H6 B4 B5 B6 B7 J1 J0 H1 H0 D3 D2 D1 D0 A0 A1 A2 A3 A4 A5 A6 A7 C7 C6 C5 C4 C3 C2 C1 C0 D7 G2 G1 G0 L7 L6 L5 L4 L3 L2 L1 L0 B3 B2 B1 B0 F0 F1 F2 F3 F4 F5 F6 F7 K0 K1 K2 K3 K4 K5 K6 K7 | E2 E6 E7 xx xx H2 H7 G3 G4 xx xx xx xx xx D4 D5 D6 xx xx J2 J3 J4 J5 J6 J7 xx xx xx xx xx * Logical Pin : 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 | 78 79 80 xx xx 84 85 71 70 xx xx xx xx xx 81 82 83 xx xx 72 73 75 76 77 74 xx xx xx xx xx + * Analog Input : 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 * * Arduino Pin Layout video: https://youtu.be/rIqeVCX09FA * AVR alternate pin function overview video: https://youtu.be/1yd8wuI5Plg @@ -34,39 +35,36 @@ #include "../fastio.h" -// change for your board -#define DEBUG_LED DIO21 - // UART -#define RXD DIO0 -#define TXD DIO1 +#define RXD 0 +#define TXD 1 // SPI -#define SCK DIO52 -#define MISO DIO50 -#define MOSI DIO51 -#define SS DIO53 +#define MISO 50 +#define MOSI 51 +#define SCK 52 +#define SS 53 // TWI (I2C) -#define SCL DIO21 -#define SDA DIO20 +#define SCL 21 +#define SDA 20 // Timers and PWM -#define OC0A DIO13 -#define OC0B DIO4 -#define OC1A DIO11 -#define OC1B DIO12 -#define OC2A DIO10 -#define OC2B DIO9 -#define OC3A DIO5 -#define OC3B DIO2 -#define OC3C DIO3 -#define OC4A DIO6 -#define OC4B DIO7 -#define OC4C DIO8 -#define OC5A DIO46 -#define OC5B DIO45 -#define OC5C DIO44 +#define OC0A 13 +#define OC0B 4 +#define OC1A 11 +#define OC1B 12 +#define OC2A 10 +#define OC2B 9 +#define OC3A 5 +#define OC3B 2 +#define OC3C 3 +#define OC4A 6 +#define OC4B 7 +#define OC4C 8 +#define OC5A 46 +#define OC5B 45 +#define OC5C 44 // Digital I/O diff --git a/Marlin/src/HAL/AVR/fastio/fastio_1281.h b/Marlin/src/HAL/AVR/fastio/fastio_1281.h index 812586225d17..6067248978ae 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_1281.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_1281.h @@ -33,32 +33,29 @@ #include "../fastio.h" -// change for your board -#define DEBUG_LED DIO46 - // UART -#define RXD DIO0 -#define TXD DIO1 +#define RXD 0 +#define TXD 1 // SPI -#define SCK DIO10 -#define MISO DIO12 -#define MOSI DIO11 -#define SS DIO16 +#define SCK 10 +#define MISO 12 +#define MOSI 11 +#define SS 16 // TWI (I2C) -#define SCL DIO17 -#define SDA DIO18 +#define SCL 17 +#define SDA 18 // Timers and PWM -#define OC0A DIO9 -#define OC0B DIO4 -#define OC1A DIO7 -#define OC1B DIO8 -#define OC2A DIO6 -#define OC3A DIO5 -#define OC3B DIO2 -#define OC3C DIO3 +#define OC0A 9 +#define OC0B 4 +#define OC1A 7 +#define OC1B 8 +#define OC2A 6 +#define OC3A 5 +#define OC3B 2 +#define OC3C 3 // Digital I/O diff --git a/Marlin/src/HAL/AVR/fastio/fastio_168.h b/Marlin/src/HAL/AVR/fastio/fastio_168.h index 4f591b37b901..cc559797408b 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_168.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_168.h @@ -33,29 +33,27 @@ #include "../fastio.h" -#define DEBUG_LED AIO5 - // UART -#define RXD DIO0 -#define TXD DIO1 +#define RXD 0 +#define TXD 1 // SPI -#define SCK DIO13 -#define MISO DIO12 -#define MOSI DIO11 -#define SS DIO10 +#define SS 10 +#define MOSI 11 +#define MISO 12 +#define SCK 13 // TWI (I2C) #define SCL AIO5 #define SDA AIO4 // Timers and PWM -#define OC0A DIO6 -#define OC0B DIO5 -#define OC1A DIO9 -#define OC1B DIO10 -#define OC2A DIO11 -#define OC2B DIO3 +#define OC0A 6 +#define OC0B 5 +#define OC1A 9 +#define OC1B 10 +#define OC2A 11 +#define OC2B 3 // Digital I/O diff --git a/Marlin/src/HAL/AVR/fastio/fastio_644.h b/Marlin/src/HAL/AVR/fastio/fastio_644.h index 16bdc6a23da2..94b322a8190d 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_644.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_644.h @@ -59,34 +59,32 @@ #include "../fastio.h" -#define DEBUG_LED DIO0 - // UART -#define RXD DIO8 -#define TXD DIO9 -#define RXD0 DIO8 -#define TXD0 DIO9 +#define RXD 8 +#define TXD 9 +#define RXD0 8 +#define TXD0 9 -#define RXD1 DIO10 -#define TXD1 DIO11 +#define RXD1 10 +#define TXD1 11 // SPI -#define SCK DIO7 -#define MISO DIO6 -#define MOSI DIO5 -#define SS DIO4 +#define SS 4 +#define MOSI 5 +#define MISO 6 +#define SCK 7 // TWI (I2C) -#define SCL DIO16 -#define SDA DIO17 +#define SCL 16 +#define SDA 17 // Timers and PWM -#define OC0A DIO3 -#define OC0B DIO4 -#define OC1A DIO13 -#define OC1B DIO12 -#define OC2A DIO15 -#define OC2B DIO14 +#define OC0A 3 +#define OC0B 4 +#define OC1A 13 +#define OC1B 12 +#define OC2A 15 +#define OC2B 14 // Digital I/O diff --git a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h index d2a8aca6f38c..51c5e096586e 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h @@ -34,14 +34,11 @@ #include "../fastio.h" -// change for your board -#define DEBUG_LED DIO31 /* led D5 red */ - // SPI -#define SCK DIO21 // 9 -#define MISO DIO23 // 11 -#define MOSI DIO22 // 10 -#define SS DIO20 // 8 +#define SS 20 // 8 +#define SCK 21 // 9 +#define MOSI 22 // 10 +#define MISO 23 // 11 // Digital I/O @@ -682,7 +679,6 @@ #define PF7_PWM 0 #define PF7_DDR DDRF - /** * Some of the pin mapping functions of the Teensduino extension to the Arduino IDE * do not function the same as the other Arduino extensions. diff --git a/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h b/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h index 5f1c4b16019d..65b019b261a8 100644 --- a/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h @@ -20,3 +20,7 @@ * */ #pragma once + +#ifndef SERIAL_PORT + #define SERIAL_PORT 0 +#endif diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h index e66de96047a5..85ee683685ec 100644 --- a/Marlin/src/HAL/AVR/inc/SanityCheck.h +++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h @@ -33,13 +33,13 @@ * Check for common serial pin conflicts */ #define CHECK_SERIAL_PIN(N) ( \ - X_STOP_PIN == N || Y_STOP_PIN == N || Z_STOP_PIN == N \ - || X_MIN_PIN == N || Y_MIN_PIN == N || Z_MIN_PIN == N \ - || X_MAX_PIN == N || Y_MAX_PIN == N || Z_MAX_PIN == N \ - || X_STEP_PIN == N || Y_STEP_PIN == N || Z_STEP_PIN == N \ - || X_DIR_PIN == N || Y_DIR_PIN == N || Z_DIR_PIN == N \ - || X_ENA_PIN == N || Y_ENA_PIN == N || Z_ENA_PIN == N \ - || BTN_EN1 == N || BTN_EN2 == N \ + X_STOP_PIN == N || Y_STOP_PIN == N || Z_STOP_PIN == N \ + || X_MIN_PIN == N || Y_MIN_PIN == N || Z_MIN_PIN == N \ + || X_MAX_PIN == N || Y_MAX_PIN == N || Z_MAX_PIN == N \ + || X_STEP_PIN == N || Y_STEP_PIN == N || Z_STEP_PIN == N \ + || X_DIR_PIN == N || Y_DIR_PIN == N || Z_DIR_PIN == N \ + || X_ENA_PIN == N || Y_ENA_PIN == N || Z_ENA_PIN == N \ + || BTN_EN1 == N || BTN_EN2 == N || LCD_PINS_EN == N \ ) #if SERIAL_IN_USE(0) // D0-D1. No known conflicts. @@ -73,8 +73,8 @@ /** * Checks for SOFT PWM */ -#if HAS_FAN0 && FAN_PIN == 9 && DISABLED(FAN_SOFT_PWM) && ENABLED(SPEAKER) - #error "FAN_PIN 9 Hardware PWM uses Timer 2 which conflicts with Arduino AVR Tone Timer (for SPEAKER)." +#if HAS_FAN0 && FAN0_PIN == 9 && DISABLED(FAN_SOFT_PWM) && ENABLED(SPEAKER) + #error "FAN0_PIN 9 Hardware PWM uses Timer 2 which conflicts with Arduino AVR Tone Timer (for SPEAKER)." #error "Disable SPEAKER or enable FAN_SOFT_PWM." #endif @@ -95,11 +95,11 @@ /** * The Trinamic library includes SoftwareSerial.h, leading to a compile error. */ -#if BOTH(HAS_TRINAMIC_CONFIG, ENDSTOP_INTERRUPTS_FEATURE) +#if ALL(HAS_TRINAMIC_CONFIG, ENDSTOP_INTERRUPTS_FEATURE) #error "TMCStepper includes SoftwareSerial.h which is incompatible with ENDSTOP_INTERRUPTS_FEATURE. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif -#if BOTH(HAS_TMC_SW_SERIAL, MONITOR_DRIVER_STATUS) +#if ALL(HAS_TMC_SW_SERIAL, MONITOR_DRIVER_STATUS) #error "MONITOR_DRIVER_STATUS causes performance issues when used with SoftwareSerial-connected drivers. Disable MONITOR_DRIVER_STATUS or use hardware serial to continue." #endif diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index b91bde182d35..15db63b4d7f8 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -77,12 +77,12 @@ void PRINT_ARRAY_NAME(uint8_t x) { PGM_P const name_mem_pointer = (PGM_P)pgm_read_ptr(&pin_array[x].name); - LOOP_L_N(y, MAX_NAME_LENGTH) { + for (uint8_t y = 0; y < MAX_NAME_LENGTH; ++y) { char temp_char = pgm_read_byte(name_mem_pointer + y); if (temp_char != 0) SERIAL_CHAR(temp_char); else { - LOOP_L_N(i, MAX_NAME_LENGTH - y) SERIAL_CHAR(' '); + for (uint8_t i = 0; i < MAX_NAME_LENGTH - y; ++i) SERIAL_CHAR(' '); break; } } @@ -90,7 +90,6 @@ void PRINT_ARRAY_NAME(uint8_t x) { #define GET_ARRAY_IS_DIGITAL(x) pgm_read_byte(&pin_array[x].is_digital) - #if defined(__AVR_ATmega1284P__) // 1284 IDE extensions set this to the number of #undef NUM_DIGITAL_PINS // digital only pins while all other CPUs have it #define NUM_DIGITAL_PINS 32 // set to digital only + digital/analog @@ -110,7 +109,7 @@ void PRINT_ARRAY_NAME(uint8_t x) { * Print a pin's PWM status. * Return true if it's currently a PWM pin. */ -static bool pwm_status(uint8_t pin) { +bool pwm_status(uint8_t pin) { char buffer[20]; // for the sprintf statements switch (digitalPinToTimer_DEBUG(pin)) { @@ -164,7 +163,6 @@ static bool pwm_status(uint8_t pin) { SERIAL_ECHO_SP(2); } // pwm_status - const volatile uint8_t* const PWM_other[][3] PROGMEM = { { &TCCR0A, &TCCR0B, &TIMSK0 }, { &TCCR1A, &TCCR1B, &TIMSK1 }, @@ -182,7 +180,6 @@ const volatile uint8_t* const PWM_other[][3] PROGMEM = { #endif }; - const volatile uint8_t* const PWM_OCR[][3] PROGMEM = { #ifdef TIMER0A @@ -218,7 +215,6 @@ const volatile uint8_t* const PWM_OCR[][3] PROGMEM = { #endif }; - #define TCCR_A(T) pgm_read_word(&PWM_other[T][0]) #define TCCR_B(T) pgm_read_word(&PWM_other[T][1]) #define TIMSK(T) pgm_read_word(&PWM_other[T][2]) @@ -233,12 +229,12 @@ const volatile uint8_t* const PWM_OCR[][3] PROGMEM = { #define OCR_VAL(T, L) pgm_read_word(&PWM_OCR[T][L]) -static void err_is_counter() { SERIAL_ECHOPGM(" non-standard PWM mode"); } -static void err_is_interrupt() { SERIAL_ECHOPGM(" compare interrupt enabled"); } -static void err_prob_interrupt() { SERIAL_ECHOPGM(" overflow interrupt enabled"); } -static void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin"); SERIAL_ECHO_SP(14); } +void err_is_counter() { SERIAL_ECHOPGM(" non-standard PWM mode"); } +void err_is_interrupt() { SERIAL_ECHOPGM(" compare interrupt enabled"); } +void err_prob_interrupt() { SERIAL_ECHOPGM(" overflow interrupt enabled"); } +void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin"); SERIAL_ECHO_SP(14); } -inline void com_print(const uint8_t N, const uint8_t Z) { +void com_print(const uint8_t N, const uint8_t Z) { const uint8_t *TCCRA = (uint8_t*)TCCR_A(N); SERIAL_ECHOPGM(" COM", AS_DIGIT(N)); SERIAL_CHAR(Z); @@ -280,7 +276,7 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - if (TEST(*TMSK, TOIE)) err_prob_interrupt(); } -static void pwm_details(uint8_t pin) { +void pwm_details(uint8_t pin) { switch (digitalPinToTimer_DEBUG(pin)) { #if ABTEST(0) @@ -354,47 +350,41 @@ static void pwm_details(uint8_t pin) { } // 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 + int digitalRead_mod(const pin_t pin) { // same as digitalRead except the PWM stop section has been removed const uint8_t port = digitalPinToPort_DEBUG(pin); return (port != NOT_A_PIN) && (*portInputRegister(port) & digitalPinToBitMask_DEBUG(pin)) ? HIGH : LOW; } #endif -#ifndef PRINT_PORT - - void print_port(int8_t pin) { // print port number - #ifdef digitalPinToPort_DEBUG - uint8_t x; - SERIAL_ECHOPGM(" Port: "); - #if AVR_AT90USB1286_FAMILY - x = (pin == 46 || pin == 47) ? 'E' : digitalPinToPort_DEBUG(pin) + 64; - #else - x = digitalPinToPort_DEBUG(pin) + 64; - #endif - SERIAL_CHAR(x); - - #if AVR_AT90USB1286_FAMILY - if (pin == 46) - x = '2'; - else if (pin == 47) - x = '3'; - else { - uint8_t temp = digitalPinToBitMask_DEBUG(pin); - for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1; - } - #else +void print_port(const pin_t pin) { // print port number + #ifdef digitalPinToPort_DEBUG + uint8_t x; + SERIAL_ECHOPGM(" Port: "); + #if AVR_AT90USB1286_FAMILY + x = (pin == 46 || pin == 47) ? 'E' : digitalPinToPort_DEBUG(pin) + 64; + #else + x = digitalPinToPort_DEBUG(pin) + 64; + #endif + SERIAL_CHAR(x); + + #if AVR_AT90USB1286_FAMILY + if (pin == 46) + x = '2'; + else if (pin == 47) + x = '3'; + else { uint8_t temp = digitalPinToBitMask_DEBUG(pin); for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1; - #endif - SERIAL_CHAR(x); + } #else - SERIAL_ECHO_SP(10); + uint8_t temp = digitalPinToBitMask_DEBUG(pin); + for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1; #endif - } - - #define PRINT_PORT(p) print_port(p) - -#endif + SERIAL_CHAR(x); + #else + SERIAL_ECHO_SP(10); + #endif +} #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) diff --git a/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h index 582ae79ba787..c812d4fb1131 100644 --- a/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h +++ b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h @@ -22,11 +22,10 @@ #pragma once // -// some of the pin mapping functions of the Teensduino extension to the Arduino IDE -// do not function the same as the other Arduino extensions +// Some of the pin mapping functions of the Arduino IDE Teensduino extension +// function differently from other Arduino extensions. // - #define TEENSYDUINO_IDE //digitalPinToTimer(pin) function works like Arduino but Timers are not defined @@ -48,8 +47,6 @@ #define PE 5 #define PF 6 -#undef digitalPinToPort - const uint8_t PROGMEM digital_pin_to_port_PGM[] = { PD, // 0 - PD0 - INT0 - PWM PD, // 1 - PD1 - INT1 - PWM @@ -101,7 +98,7 @@ const uint8_t PROGMEM digital_pin_to_port_PGM[] = { PE, // 47 - PE3 (not defined in teensyduino) }; -#define digitalPinToPort(P) ( pgm_read_byte( digital_pin_to_port_PGM + (P) ) ) +#define digitalPinToPort(P) pgm_read_byte(digital_pin_to_port_PGM[P]) // digitalPinToBitMask(pin) is OK diff --git a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h index d9aa44c3cb15..fa479cfe8fd9 100644 --- a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h +++ b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h @@ -231,7 +231,6 @@ const uint8_t PROGMEM digital_pin_to_bit_mask_PGM_plus_70[] = { #define digitalPinToBitMask_plus_70(P) ( pgm_read_byte( digital_pin_to_bit_mask_PGM_plus_70 + (P) ) ) - const uint8_t PROGMEM digital_pin_to_timer_PGM_plus_70[] = { // TIMERS // ------------------------ diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index d9cdfc4f0131..94b17f310270 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp index 45b54379dba7..131174b06c41 100644 --- a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp +++ b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp @@ -88,7 +88,7 @@ void u8g_spiSend_sw_AVR_mode_0(uint8_t val) { volatile uint8_t *outData = u8g_outData, *outClock = u8g_outClock; U8G_ATOMIC_START(); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (val & 0x80) *outData |= bitData; else @@ -108,7 +108,7 @@ void u8g_spiSend_sw_AVR_mode_3(uint8_t val) { volatile uint8_t *outData = u8g_outData, *outClock = u8g_outClock; U8G_ATOMIC_START(); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { *outClock &= bitNotClock; if (val & 0x80) *outData |= bitData; @@ -120,7 +120,6 @@ void u8g_spiSend_sw_AVR_mode_3(uint8_t val) { U8G_ATOMIC_END(); } - #if ENABLED(FYSETC_MINI_12864) #define SPISEND_SW_AVR u8g_spiSend_sw_AVR_mode_3 #else diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp index 4353f1649732..763091cb009a 100644 --- a/Marlin/src/HAL/DUE/HAL.cpp +++ b/Marlin/src/HAL/DUE/HAL.cpp @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 @@ -45,7 +47,7 @@ uint16_t MarlinHAL::adc_result; #endif void MarlinHAL::init() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up #endif usb_task_init(); // Initialize the USB stack diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 585b8938417f..49a8be3fe7bb 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 @@ -123,7 +123,7 @@ typedef Servo hal_servo_t; // // ADC // -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 10 #ifndef analogInputToDigitalPin diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index f5bcaacee505..63ebf164f2b1 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -42,7 +42,7 @@ // Public functions // ------------------------ -#if EITHER(DUE_SOFTWARE_SPI, FORCE_SOFT_SPI) +#if ANY(DUE_SOFTWARE_SPI, FORCE_SOFT_SPI) // ------------------------ // Software SPI diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index 638f7a100722..90efe55fc23d 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -474,7 +474,6 @@ void MarlinSerial::flushTX() { } } - // If not using the USB port as serial port #if defined(SERIAL_PORT) && SERIAL_PORT >= 0 template class MarlinSerial< MarlinSerialCfg >; diff --git a/Marlin/src/HAL/DUE/MarlinSerial.h b/Marlin/src/HAL/DUE/MarlinSerial.h index 5a61bffee0da..b80ae2182312 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.h +++ b/Marlin/src/HAL/DUE/MarlinSerial.h @@ -30,6 +30,7 @@ #include #include "../../inc/MarlinConfigPre.h" +#include "../../core/types.h" #include "../../core/serial_hook.h" // Define constants and variables for buffering incoming serial data. We're @@ -52,10 +53,6 @@ // #error "TX_BUFFER_SIZE must be 0, a power of 2 greater than 1, and no greater than 256." //#endif -// Templated type selector -template struct TypeSelector { typedef T type;} ; -template struct TypeSelector { typedef F type; }; - // Templated structure wrapper template struct StructWrapper { constexpr StructWrapper(int) {} @@ -76,7 +73,7 @@ class MarlinSerial { static constexpr int HWUART_IRQ_ID = IRQ_IDS[Cfg::PORT]; // Base size of type on buffer size - typedef typename TypeSelector<(Cfg::RX_SIZE>256), uint16_t, uint8_t>::type ring_buffer_pos_t; + typedef uvalue_t(Cfg::RX_SIZE - 1) ring_buffer_pos_t; struct ring_buffer_r { volatile ring_buffer_pos_t head, tail; diff --git a/Marlin/src/HAL/DUE/MinSerial.cpp b/Marlin/src/HAL/DUE/MinSerial.cpp index e5b3dbfe6f36..505a712aa9a1 100644 --- a/Marlin/src/HAL/DUE/MinSerial.cpp +++ b/Marlin/src/HAL/DUE/MinSerial.cpp @@ -73,18 +73,18 @@ void install_min_serial() { } #if DISABLED(DYNAMIC_VECTORTABLE) -extern "C" { - __attribute__((naked)) void JumpHandler_ASM() { - __asm__ __volatile__ ( - "b CommonHandler_ASM\n" - ); + extern "C" { + __attribute__((naked)) void JumpHandler_ASM() { + __asm__ __volatile__ ( + "b CommonHandler_ASM\n" + ); + } + void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler(); } - void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler(); -} #endif #endif // POSTMORTEM_DEBUGGING diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp index 904924793b4c..86c8a4847026 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp @@ -81,7 +81,7 @@ Pio *SCK_pPio, *MOSI_pPio; uint32_t SCK_dwMask, MOSI_dwMask; void u8g_spiSend_sw_DUE_mode_0(uint8_t val) { // 3MHz - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (val & 0x80) MOSI_pPio->PIO_SODR = MOSI_dwMask; else @@ -95,7 +95,7 @@ void u8g_spiSend_sw_DUE_mode_0(uint8_t val) { // 3MHz } void u8g_spiSend_sw_DUE_mode_3(uint8_t val) { // 3.5MHz - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { SCK_pPio->PIO_CODR = SCK_dwMask; DELAY_NS(50); if (val & 0x80) diff --git a/Marlin/src/HAL/DUE/eeprom_flash.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp index 607764155b0a..915a699ed858 100644 --- a/Marlin/src/HAL/DUE/eeprom_flash.cpp +++ b/Marlin/src/HAL/DUE/eeprom_flash.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 @@ -292,7 +291,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) { uint32_t *p1 = (uint32_t*)addrflash; uint32_t *p2 = (uint32_t*)data; int count = 0; - for (i =0; i> 2; i++) { + for (i = 0; i < PageSize >> 2; i++) { if (p1[i] != p2[i]) { uint32_t delta = p1[i] ^ p2[i]; while (delta) { diff --git a/Marlin/src/HAL/DUE/eeprom_wired.cpp b/Marlin/src/HAL/DUE/eeprom_wired.cpp index 557a2f2cffa5..24f8c06d2e1b 100644 --- a/Marlin/src/HAL/DUE/eeprom_wired.cpp +++ b/Marlin/src/HAL/DUE/eeprom_wired.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/DUE/endstop_interrupts.h b/Marlin/src/HAL/DUE/endstop_interrupts.h index c1bbcb121bdc..08ffc256b9b5 100644 --- a/Marlin/src/HAL/DUE/endstop_interrupts.h +++ b/Marlin/src/HAL/DUE/endstop_interrupts.h @@ -47,33 +47,33 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); - TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN)); - TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN)); - TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN)); - TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN)); - TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN)); - TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/DUE/fastio.h b/Marlin/src/HAL/DUE/fastio.h index a609210d8130..77bc1911d8df 100644 --- a/Marlin/src/HAL/DUE/fastio.h +++ b/Marlin/src/HAL/DUE/fastio.h @@ -189,12 +189,12 @@ */ // UART -#define RXD DIO0 -#define TXD DIO1 +#define RXD 0 +#define TXD 1 // TWI (I2C) -#define SCL DIO21 -#define SDA DIO20 +#define SCL 21 +#define SDA 20 /** * pins diff --git a/Marlin/src/HAL/DUE/fastio/G2_PWM.h b/Marlin/src/HAL/DUE/fastio/G2_PWM.h index dc4edffff851..054eb2cf8039 100644 --- a/Marlin/src/HAL/DUE/fastio/G2_PWM.h +++ b/Marlin/src/HAL/DUE/fastio/G2_PWM.h @@ -49,7 +49,6 @@ extern volatile uint32_t *SODR_A, *SODR_B, *CODR_A, *CODR_B; #define PWM_MAP_INIT_ROW(IO,ZZ) { ZZ == 'A' ? SODR_A : SODR_B, ZZ == 'A' ? CODR_A : CODR_B, 1 << _PIN(IO) } - #define PWM_MAP_INIT { PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_X_PIN, 'B'), \ PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_Y_PIN, 'B'), \ PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_Z_PIN, 'B'), \ @@ -63,7 +62,7 @@ extern PWM_map ISR_table[NUM_PWMS]; extern uint32_t motor_current_setting[3]; #define IR_BIT(p) (WITHIN(p, 0, 3) ? (p) : (p) + 4) -#define COPY_ACTIVE_TABLE() do{ LOOP_L_N(i, 6) work_table[i] = active_table[i]; }while(0) +#define COPY_ACTIVE_TABLE() do{ for (uint8_t i = 0; i < 6; ++i) work_table[i] = active_table[i]; }while(0) #define PWM_MR0 19999 // base repetition rate minus one count - 20mS #define PWM_PR 24 // prescaler value - prescaler divide by 24 + 1 - 1 MHz output diff --git a/Marlin/src/HAL/DUE/fastio/G2_pins.h b/Marlin/src/HAL/DUE/fastio/G2_pins.h index 80c87bd39296..38fcc5e5df0b 100644 --- a/Marlin/src/HAL/DUE/fastio/G2_pins.h +++ b/Marlin/src/HAL/DUE/fastio/G2_pins.h @@ -168,7 +168,6 @@ const G2_PinDescription G2_g_APinDescription[] = { { PIOB, PIO_PB21, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 52 { PIOB, PIO_PB14, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 53 - // 54 .. 65 - Analog pins // ---------------------- { PIOA, PIO_PA16X1_AD7, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC0, ADC7, NOT_ON_PWM, NOT_ON_TIMER }, // AD0 diff --git a/Marlin/src/HAL/DUE/inc/Conditionals_post.h b/Marlin/src/HAL/DUE/inc/Conditionals_post.h index ce6d3fdde27f..295596b78b19 100644 --- a/Marlin/src/HAL/DUE/inc/Conditionals_post.h +++ b/Marlin/src/HAL/DUE/inc/Conditionals_post.h @@ -23,6 +23,6 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/DUE/inc/SanityCheck.h b/Marlin/src/HAL/DUE/inc/SanityCheck.h index 5f0a05baff23..a8f5de8298d1 100644 --- a/Marlin/src/HAL/DUE/inc/SanityCheck.h +++ b/Marlin/src/HAL/DUE/inc/SanityCheck.h @@ -68,9 +68,9 @@ * Usually the hardware SPI pins are only available to the LCD. This makes the DUE hard SPI used at the same time * as the TMC2130 soft SPI the most common setup. */ -#define _IS_HW_SPI(P) (defined(TMC_SW_##P) && (TMC_SW_##P == SD_MOSI_PIN || TMC_SW_##P == SD_MISO_PIN || TMC_SW_##P == SD_SCK_PIN)) +#define _IS_HW_SPI(P) (defined(TMC_SPI_##P) && (TMC_SPI_##P == SD_MOSI_PIN || TMC_SPI_##P == SD_MISO_PIN || TMC_SPI_##P == SD_SCK_PIN)) -#if ENABLED(SDSUPPORT) && HAS_DRIVER(TMC2130) +#if HAS_MEDIA && HAS_DRIVER(TMC2130) #if ENABLED(TMC_USE_SW_SPI) #if DISABLED(DUE_SOFTWARE_SPI) && (_IS_HW_SPI(MOSI) || _IS_HW_SPI(MISO) || _IS_HW_SPI(SCK)) #error "DUE hardware SPI is required but is incompatible with TMC2130 software SPI. Either disable TMC_USE_SW_SPI or use separate pins for the two SPIs." diff --git a/Marlin/src/HAL/DUE/pinsDebug.h b/Marlin/src/HAL/DUE/pinsDebug.h index 2aafe9be0c56..1544853553f0 100644 --- a/Marlin/src/HAL/DUE/pinsDebug.h +++ b/Marlin/src/HAL/DUE/pinsDebug.h @@ -64,7 +64,6 @@ #define NUMBER_PINS_TOTAL PINS_COUNT #define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin -#define PRINT_PORT(p) #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) @@ -93,6 +92,8 @@ void pwm_details(int32_t pin) { } } +void print_port(const pin_t) {} + /** * DUE Board pin | PORT | Label * ----------------+--------+------- diff --git a/Marlin/src/HAL/DUE/timers.cpp b/Marlin/src/HAL/DUE/timers.cpp index e5647817b6f0..e388255c0808 100644 --- a/Marlin/src/HAL/DUE/timers.cpp +++ b/Marlin/src/HAL/DUE/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index dc35c77e6384..db5d83a06f74 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/DUE/usb/compiler.h b/Marlin/src/HAL/DUE/usb/compiler.h index 633197914eef..27c554cdb7e1 100644 --- a/Marlin/src/HAL/DUE/usb/compiler.h +++ b/Marlin/src/HAL/DUE/usb/compiler.h @@ -142,7 +142,6 @@ */ #define COMPILER_PACK_RESET() COMPILER_PRAGMA(pack()) - /** * \brief Set aligned boundary. */ @@ -283,7 +282,6 @@ typedef double F64; //!< 64-bit floating-point number. typedef uint32_t iram_size_t; //! @} - /*! \name Status Types */ //! @{ @@ -291,7 +289,6 @@ typedef bool Status_bool_t; //!< Boolean status. typedef U8 Status_t; //!< 8-bit-coded status. //! @} - /*! \name Aliasing Aggregate Types */ //! @{ @@ -462,7 +459,6 @@ typedef struct #endif //! @} - #ifndef __ASSEMBLY__ // not for assembling. //! \name Optimization Control @@ -581,7 +577,6 @@ typedef struct //! @} - /*! \name Zero-Bit Counting * * Under GCC, __builtin_clz and __builtin_ctz behave like macros when @@ -692,7 +687,6 @@ typedef struct //! @} - /*! \name Bit Reversing */ //! @{ @@ -732,7 +726,6 @@ typedef struct //! @} - /*! \name Alignment */ //! @{ @@ -798,7 +791,6 @@ typedef struct */ #define Long_call(addr) ((*(void (*)(void))(addr))()) - /*! \name MCU Endianism Handling * ARM is MCU little endianism. */ @@ -868,7 +860,6 @@ typedef struct #define CPU_TO_BE32(x) swap32(x) //! @} - /*! \name Endianism Conversion * * The same considerations as for clz and ctz apply here but GCC's @@ -955,7 +946,6 @@ typedef struct //! @} - /*! \name Target Abstraction */ //! @{ @@ -997,7 +987,6 @@ typedef U8 Byte; //!< 8-bit unsigned integer. #endif // #ifndef __ASSEMBLY__ - #ifdef __ICCARM__ #define SHORTENUM __packed #elif defined(__GNUC__) diff --git a/Marlin/src/HAL/DUE/usb/conf_access.h b/Marlin/src/HAL/DUE/usb/conf_access.h index f401685223cb..0ea5fe228782 100644 --- a/Marlin/src/HAL/DUE/usb/conf_access.h +++ b/Marlin/src/HAL/DUE/usb/conf_access.h @@ -81,7 +81,6 @@ #define LUN_0_NAME "\"SD/MMC Card\"" //! @} - /*! \name Actions Associated with Memory Accesses * * Write here the action to associate with each memory access. @@ -112,5 +111,4 @@ #define GLOBAL_WR_PROTECT false //!< Management of a global write protection. //! @} - #endif // _CONF_ACCESS_H_ diff --git a/Marlin/src/HAL/DUE/usb/conf_clock.h b/Marlin/src/HAL/DUE/usb/conf_clock.h index 97e70e99a5b9..0c7815ee4d72 100644 --- a/Marlin/src/HAL/DUE/usb/conf_clock.h +++ b/Marlin/src/HAL/DUE/usb/conf_clock.h @@ -96,5 +96,4 @@ // - UPLL frequency: 480MHz // - USB clock: 480 / 1 = 480MHz - #endif /* CONF_CLOCK_H_INCLUDED */ diff --git a/Marlin/src/HAL/DUE/usb/conf_usb.h b/Marlin/src/HAL/DUE/usb/conf_usb.h index 4de9e347e213..fb4ef3424110 100644 --- a/Marlin/src/HAL/DUE/usb/conf_usb.h +++ b/Marlin/src/HAL/DUE/usb/conf_usb.h @@ -88,7 +88,6 @@ #endif //@} - /** * USB Device Callbacks definitions (Optional) * @{ @@ -101,7 +100,7 @@ #define USB_DEVICE_SPECIFIC_REQUEST() usb_task_other_requests() //@} -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA /** * USB Device low level configuration * When only one interface is used, these configurations are defined by the class module. @@ -150,7 +149,6 @@ //@} - /** * USB Interface Configuration * @{ @@ -185,7 +183,7 @@ //! Enable id string of interface to add an extra USB string #define UDI_CDC_IAD_STRING_ID 4 -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA /** * USB CDC low level configuration * In standalone these configurations are defined by the CDC module. @@ -210,7 +208,6 @@ //@} //@} - /** * Configuration of MSC interface * @{ @@ -245,7 +242,6 @@ //@} - /** * Description of Composite Device * @{ diff --git a/Marlin/src/HAL/DUE/usb/ctrl_access.c b/Marlin/src/HAL/DUE/usb/ctrl_access.c index 99f97f62cb80..b766ed12732b 100644 --- a/Marlin/src/HAL/DUE/usb/ctrl_access.c +++ b/Marlin/src/HAL/DUE/usb/ctrl_access.c @@ -68,7 +68,6 @@ #endif #include "ctrl_access.h" - //_____ D E F I N I T I O N S ______________________________________________ #ifdef FREERTOS_USED @@ -112,7 +111,6 @@ static xSemaphoreHandle ctrl_access_semphr = NULL; #endif // FREERTOS_USED - #if MAX_LUN /*! \brief Initializes an entry of the LUN descriptor table. @@ -242,17 +240,14 @@ static const struct #endif - #if GLOBAL_WR_PROTECT == true bool g_wr_protect; #endif - /*! \name Control Interface */ //! @{ - #ifdef FREERTOS_USED bool ctrl_access_init(void) @@ -270,7 +265,6 @@ bool ctrl_access_init(void) return true; } - /*! \brief Locks accesses to LUNs. * * \return \c true if the access was successfully locked, else \c false. @@ -288,7 +282,6 @@ static bool ctrl_access_lock(void) #endif // FREERTOS_USED - U8 get_nb_lun(void) { #if MEM_USB == ENABLE @@ -309,13 +302,11 @@ U8 get_nb_lun(void) #endif } - U8 get_cur_lun(void) { return LUN_ID_0; } - Ctrl_status mem_test_unit_ready(U8 lun) { Ctrl_status status; @@ -337,7 +328,6 @@ Ctrl_status mem_test_unit_ready(U8 lun) return status; } - Ctrl_status mem_read_capacity(U8 lun, U32 *u32_nb_sector) { Ctrl_status status; @@ -359,7 +349,6 @@ Ctrl_status mem_read_capacity(U8 lun, U32 *u32_nb_sector) return status; } - U8 mem_sector_size(U8 lun) { U8 sector_size; @@ -381,7 +370,6 @@ U8 mem_sector_size(U8 lun) return sector_size; } - bool mem_unload(U8 lun, bool unload) { bool unloaded; @@ -433,7 +421,6 @@ bool mem_wr_protect(U8 lun) return wr_protect; } - bool mem_removal(U8 lun) { bool removal; @@ -458,7 +445,6 @@ bool mem_removal(U8 lun) return removal; } - const char *mem_name(U8 lun) { #if MAX_LUN==0 @@ -475,17 +461,14 @@ const char *mem_name(U8 lun) #endif } - //! @} - #if ACCESS_USB == true /*! \name MEM <-> USB Interface */ //! @{ - Ctrl_status memory_2_usb(U8 lun, U32 addr, U16 nb_sector) { Ctrl_status status; @@ -505,7 +488,6 @@ Ctrl_status memory_2_usb(U8 lun, U32 addr, U16 nb_sector) return status; } - Ctrl_status usb_2_memory(U8 lun, U32 addr, U16 nb_sector) { Ctrl_status status; @@ -525,19 +507,16 @@ Ctrl_status usb_2_memory(U8 lun, U32 addr, U16 nb_sector) return status; } - //! @} #endif // ACCESS_USB == true - #if ACCESS_MEM_TO_RAM == true /*! \name MEM <-> RAM Interface */ //! @{ - Ctrl_status memory_2_ram(U8 lun, U32 addr, void *ram) { Ctrl_status status; @@ -564,7 +543,6 @@ Ctrl_status memory_2_ram(U8 lun, U32 addr, void *ram) return status; } - Ctrl_status ram_2_memory(U8 lun, U32 addr, const void *ram) { Ctrl_status status; @@ -591,19 +569,16 @@ Ctrl_status ram_2_memory(U8 lun, U32 addr, const void *ram) return status; } - //! @} #endif // ACCESS_MEM_TO_RAM == true - #if ACCESS_STREAM == true /*! \name Streaming MEM <-> MEM Interface */ //! @{ - #if ACCESS_MEM_TO_MEM == true #include "fat.h" @@ -625,21 +600,18 @@ Ctrl_status stream_mem_to_mem(U8 src_lun, U32 src_addr, U8 dest_lun, U32 dest_ad #endif // ACCESS_MEM_TO_MEM == true - Ctrl_status stream_state(U8 id) { UNUSED(id); return CTRL_GOOD; } - U16 stream_stop(U8 id) { UNUSED(id); return 0; } - //! @} #endif // ACCESS_STREAM diff --git a/Marlin/src/HAL/DUE/usb/ctrl_access.h b/Marlin/src/HAL/DUE/usb/ctrl_access.h index b33839076eae..d9cb05da7472 100644 --- a/Marlin/src/HAL/DUE/usb/ctrl_access.h +++ b/Marlin/src/HAL/DUE/usb/ctrl_access.h @@ -56,7 +56,6 @@ * Support and FAQ: visit Atmel Support */ - #ifndef _CTRL_ACCESS_H_ #define _CTRL_ACCESS_H_ @@ -89,7 +88,6 @@ typedef enum CTRL_BUSY = FAIL + 2 //!< Memory not initialized or changed. } Ctrl_status; - // FYI: Each Logical Unit Number (LUN) corresponds to a memory. // Check LUN defines. @@ -136,7 +134,6 @@ typedef enum #define LUN_ID_USB (MAX_LUN) //!< First dynamic LUN (USB host mass storage). //! @} - // Include LUN header files. #if LUN_0 == ENABLE #include LUN_0_INCLUDE @@ -166,13 +163,11 @@ typedef enum #include LUN_USB_INCLUDE #endif - // Check the configuration of write protection in conf_access.h. #ifndef GLOBAL_WR_PROTECT #error GLOBAL_WR_PROTECT must be defined as true or false in conf_access.h #endif - #if GLOBAL_WR_PROTECT == true //! Write protect. @@ -180,7 +175,6 @@ extern bool g_wr_protect; #endif - /*! \name Control Interface */ //! @{ @@ -279,7 +273,6 @@ extern const char *mem_name(U8 lun); //! @} - #if ACCESS_USB == true /*! \name MEM <-> USB Interface @@ -310,7 +303,6 @@ extern Ctrl_status usb_2_memory(U8 lun, U32 addr, U16 nb_sector); #endif // ACCESS_USB == true - #if ACCESS_MEM_TO_RAM == true /*! \name MEM <-> RAM Interface @@ -341,7 +333,6 @@ extern Ctrl_status ram_2_memory(U8 lun, U32 addr, const void *ram); #endif // ACCESS_MEM_TO_RAM == true - #if ACCESS_STREAM == true /*! \name Streaming MEM <-> MEM Interface diff --git a/Marlin/src/HAL/DUE/usb/genclk.h b/Marlin/src/HAL/DUE/usb/genclk.h index cde03bc0d107..45eba5873f8c 100644 --- a/Marlin/src/HAL/DUE/usb/genclk.h +++ b/Marlin/src/HAL/DUE/usb/genclk.h @@ -74,17 +74,17 @@ extern "C" { //@{ enum genclk_source { - GENCLK_PCK_SRC_SLCK_RC = 0, //!< Internal 32kHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_SLCK_XTAL = 1, //!< External 32kHz crystal oscillator as PCK source clock - GENCLK_PCK_SRC_SLCK_BYPASS = 2, //!< External 32kHz bypass oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_4M_RC = 3, //!< Internal 4MHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_8M_RC = 4, //!< Internal 8MHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_12M_RC = 5, //!< Internal 12MHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_XTAL = 6, //!< External crystal oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_BYPASS = 7, //!< External bypass oscillator as PCK source clock - GENCLK_PCK_SRC_PLLACK = 8, //!< Use PLLACK as PCK source clock - GENCLK_PCK_SRC_PLLBCK = 9, //!< Use PLLBCK as PCK source clock - GENCLK_PCK_SRC_MCK = 10, //!< Use Master Clk as PCK source clock + GENCLK_PCK_SRC_SLCK_RC = 0, //!< Internal 32kHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_SLCK_XTAL = 1, //!< External 32kHz crystal oscillator as PCK source clock + GENCLK_PCK_SRC_SLCK_BYPASS = 2, //!< External 32kHz bypass oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_4M_RC = 3, //!< Internal 4MHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_8M_RC = 4, //!< Internal 8MHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_12M_RC = 5, //!< Internal 12MHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_XTAL = 6, //!< External crystal oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_BYPASS = 7, //!< External bypass oscillator as PCK source clock + GENCLK_PCK_SRC_PLLACK = 8, //!< Use PLLACK as PCK source clock + GENCLK_PCK_SRC_PLLBCK = 9, //!< Use PLLBCK as PCK source clock + GENCLK_PCK_SRC_MCK = 10, //!< Use Master Clk as PCK source clock }; //@} @@ -93,176 +93,162 @@ enum genclk_source { //@{ enum genclk_divider { - GENCLK_PCK_PRES_1 = PMC_PCK_PRES_CLK_1, //!< Set PCK clock prescaler to 1 - GENCLK_PCK_PRES_2 = PMC_PCK_PRES_CLK_2, //!< Set PCK clock prescaler to 2 - GENCLK_PCK_PRES_4 = PMC_PCK_PRES_CLK_4, //!< Set PCK clock prescaler to 4 - GENCLK_PCK_PRES_8 = PMC_PCK_PRES_CLK_8, //!< Set PCK clock prescaler to 8 - GENCLK_PCK_PRES_16 = PMC_PCK_PRES_CLK_16, //!< Set PCK clock prescaler to 16 - GENCLK_PCK_PRES_32 = PMC_PCK_PRES_CLK_32, //!< Set PCK clock prescaler to 32 - GENCLK_PCK_PRES_64 = PMC_PCK_PRES_CLK_64, //!< Set PCK clock prescaler to 64 + GENCLK_PCK_PRES_1 = PMC_PCK_PRES_CLK_1, //!< Set PCK clock prescaler to 1 + GENCLK_PCK_PRES_2 = PMC_PCK_PRES_CLK_2, //!< Set PCK clock prescaler to 2 + GENCLK_PCK_PRES_4 = PMC_PCK_PRES_CLK_4, //!< Set PCK clock prescaler to 4 + GENCLK_PCK_PRES_8 = PMC_PCK_PRES_CLK_8, //!< Set PCK clock prescaler to 8 + GENCLK_PCK_PRES_16 = PMC_PCK_PRES_CLK_16, //!< Set PCK clock prescaler to 16 + GENCLK_PCK_PRES_32 = PMC_PCK_PRES_CLK_32, //!< Set PCK clock prescaler to 32 + GENCLK_PCK_PRES_64 = PMC_PCK_PRES_CLK_64, //!< Set PCK clock prescaler to 64 }; //@} struct genclk_config { - uint32_t ctrl; + uint32_t ctrl; }; -static inline void genclk_config_defaults(struct genclk_config *p_cfg, - uint32_t ul_id) -{ - ul_id = ul_id; - p_cfg->ctrl = 0; +static inline void genclk_config_defaults(struct genclk_config *p_cfg, uint32_t ul_id) { + ul_id = ul_id; + p_cfg->ctrl = 0; } -static inline void genclk_config_read(struct genclk_config *p_cfg, - uint32_t ul_id) -{ - p_cfg->ctrl = PMC->PMC_PCK[ul_id]; +static inline void genclk_config_read(struct genclk_config *p_cfg, uint32_t ul_id) { + p_cfg->ctrl = PMC->PMC_PCK[ul_id]; } -static inline void genclk_config_write(const struct genclk_config *p_cfg, - uint32_t ul_id) -{ - PMC->PMC_PCK[ul_id] = p_cfg->ctrl; +static inline void genclk_config_write(const struct genclk_config *p_cfg, uint32_t ul_id) { + PMC->PMC_PCK[ul_id] = p_cfg->ctrl; } //! \name Programmable Clock Source and Prescaler configuration //@{ -static inline void genclk_config_set_source(struct genclk_config *p_cfg, - enum genclk_source e_src) -{ - p_cfg->ctrl &= (~PMC_PCK_CSS_Msk); - - switch (e_src) { - case GENCLK_PCK_SRC_SLCK_RC: - case GENCLK_PCK_SRC_SLCK_XTAL: - case GENCLK_PCK_SRC_SLCK_BYPASS: - p_cfg->ctrl |= (PMC_PCK_CSS_SLOW_CLK); - break; - - case GENCLK_PCK_SRC_MAINCK_4M_RC: - case GENCLK_PCK_SRC_MAINCK_8M_RC: - case GENCLK_PCK_SRC_MAINCK_12M_RC: - case GENCLK_PCK_SRC_MAINCK_XTAL: - case GENCLK_PCK_SRC_MAINCK_BYPASS: - p_cfg->ctrl |= (PMC_PCK_CSS_MAIN_CLK); - break; - - case GENCLK_PCK_SRC_PLLACK: - p_cfg->ctrl |= (PMC_PCK_CSS_PLLA_CLK); - break; - - case GENCLK_PCK_SRC_PLLBCK: - p_cfg->ctrl |= (PMC_PCK_CSS_UPLL_CLK); - break; - - case GENCLK_PCK_SRC_MCK: - p_cfg->ctrl |= (PMC_PCK_CSS_MCK); - break; - } +static inline void genclk_config_set_source(struct genclk_config *p_cfg, enum genclk_source e_src) { + p_cfg->ctrl &= (~PMC_PCK_CSS_Msk); + + switch (e_src) { + case GENCLK_PCK_SRC_SLCK_RC: + case GENCLK_PCK_SRC_SLCK_XTAL: + case GENCLK_PCK_SRC_SLCK_BYPASS: + p_cfg->ctrl |= (PMC_PCK_CSS_SLOW_CLK); + break; + + case GENCLK_PCK_SRC_MAINCK_4M_RC: + case GENCLK_PCK_SRC_MAINCK_8M_RC: + case GENCLK_PCK_SRC_MAINCK_12M_RC: + case GENCLK_PCK_SRC_MAINCK_XTAL: + case GENCLK_PCK_SRC_MAINCK_BYPASS: + p_cfg->ctrl |= (PMC_PCK_CSS_MAIN_CLK); + break; + + case GENCLK_PCK_SRC_PLLACK: + p_cfg->ctrl |= (PMC_PCK_CSS_PLLA_CLK); + break; + + case GENCLK_PCK_SRC_PLLBCK: + p_cfg->ctrl |= (PMC_PCK_CSS_UPLL_CLK); + break; + + case GENCLK_PCK_SRC_MCK: + p_cfg->ctrl |= (PMC_PCK_CSS_MCK); + break; + } } -static inline void genclk_config_set_divider(struct genclk_config *p_cfg, - uint32_t e_divider) -{ - p_cfg->ctrl &= ~PMC_PCK_PRES_Msk; - p_cfg->ctrl |= e_divider; +static inline void genclk_config_set_divider(struct genclk_config *p_cfg, uint32_t e_divider) { + p_cfg->ctrl &= ~PMC_PCK_PRES_Msk; + p_cfg->ctrl |= e_divider; } //@} -static inline void genclk_enable(const struct genclk_config *p_cfg, - uint32_t ul_id) -{ - PMC->PMC_PCK[ul_id] = p_cfg->ctrl; - pmc_enable_pck(ul_id); +static inline void genclk_enable(const struct genclk_config *p_cfg, uint32_t ul_id) { + PMC->PMC_PCK[ul_id] = p_cfg->ctrl; + pmc_enable_pck(ul_id); } -static inline void genclk_disable(uint32_t ul_id) -{ - pmc_disable_pck(ul_id); +static inline void genclk_disable(uint32_t ul_id) { + pmc_disable_pck(ul_id); } -static inline void genclk_enable_source(enum genclk_source e_src) -{ - switch (e_src) { - case GENCLK_PCK_SRC_SLCK_RC: - if (!osc_is_ready(OSC_SLCK_32K_RC)) { - osc_enable(OSC_SLCK_32K_RC); - osc_wait_ready(OSC_SLCK_32K_RC); - } - break; - - case GENCLK_PCK_SRC_SLCK_XTAL: - if (!osc_is_ready(OSC_SLCK_32K_XTAL)) { - osc_enable(OSC_SLCK_32K_XTAL); - osc_wait_ready(OSC_SLCK_32K_XTAL); - } - break; - - case GENCLK_PCK_SRC_SLCK_BYPASS: - if (!osc_is_ready(OSC_SLCK_32K_BYPASS)) { - osc_enable(OSC_SLCK_32K_BYPASS); - osc_wait_ready(OSC_SLCK_32K_BYPASS); - } - break; - - case GENCLK_PCK_SRC_MAINCK_4M_RC: - if (!osc_is_ready(OSC_MAINCK_4M_RC)) { - osc_enable(OSC_MAINCK_4M_RC); - osc_wait_ready(OSC_MAINCK_4M_RC); - } - break; - - case GENCLK_PCK_SRC_MAINCK_8M_RC: - if (!osc_is_ready(OSC_MAINCK_8M_RC)) { - osc_enable(OSC_MAINCK_8M_RC); - osc_wait_ready(OSC_MAINCK_8M_RC); - } - break; - - case GENCLK_PCK_SRC_MAINCK_12M_RC: - if (!osc_is_ready(OSC_MAINCK_12M_RC)) { - osc_enable(OSC_MAINCK_12M_RC); - osc_wait_ready(OSC_MAINCK_12M_RC); - } - break; - - case GENCLK_PCK_SRC_MAINCK_XTAL: - if (!osc_is_ready(OSC_MAINCK_XTAL)) { - osc_enable(OSC_MAINCK_XTAL); - osc_wait_ready(OSC_MAINCK_XTAL); - } - break; - - case GENCLK_PCK_SRC_MAINCK_BYPASS: - if (!osc_is_ready(OSC_MAINCK_BYPASS)) { - osc_enable(OSC_MAINCK_BYPASS); - osc_wait_ready(OSC_MAINCK_BYPASS); - } - break; - -#ifdef CONFIG_PLL0_SOURCE - case GENCLK_PCK_SRC_PLLACK: - pll_enable_config_defaults(0); - break; -#endif - -#ifdef CONFIG_PLL1_SOURCE - case GENCLK_PCK_SRC_PLLBCK: - pll_enable_config_defaults(1); - break; -#endif - - case GENCLK_PCK_SRC_MCK: - break; - - default: - Assert(false); - break; - } +static inline void genclk_enable_source(enum genclk_source e_src) { + switch (e_src) { + case GENCLK_PCK_SRC_SLCK_RC: + if (!osc_is_ready(OSC_SLCK_32K_RC)) { + osc_enable(OSC_SLCK_32K_RC); + osc_wait_ready(OSC_SLCK_32K_RC); + } + break; + + case GENCLK_PCK_SRC_SLCK_XTAL: + if (!osc_is_ready(OSC_SLCK_32K_XTAL)) { + osc_enable(OSC_SLCK_32K_XTAL); + osc_wait_ready(OSC_SLCK_32K_XTAL); + } + break; + + case GENCLK_PCK_SRC_SLCK_BYPASS: + if (!osc_is_ready(OSC_SLCK_32K_BYPASS)) { + osc_enable(OSC_SLCK_32K_BYPASS); + osc_wait_ready(OSC_SLCK_32K_BYPASS); + } + break; + + case GENCLK_PCK_SRC_MAINCK_4M_RC: + if (!osc_is_ready(OSC_MAINCK_4M_RC)) { + osc_enable(OSC_MAINCK_4M_RC); + osc_wait_ready(OSC_MAINCK_4M_RC); + } + break; + + case GENCLK_PCK_SRC_MAINCK_8M_RC: + if (!osc_is_ready(OSC_MAINCK_8M_RC)) { + osc_enable(OSC_MAINCK_8M_RC); + osc_wait_ready(OSC_MAINCK_8M_RC); + } + break; + + case GENCLK_PCK_SRC_MAINCK_12M_RC: + if (!osc_is_ready(OSC_MAINCK_12M_RC)) { + osc_enable(OSC_MAINCK_12M_RC); + osc_wait_ready(OSC_MAINCK_12M_RC); + } + break; + + case GENCLK_PCK_SRC_MAINCK_XTAL: + if (!osc_is_ready(OSC_MAINCK_XTAL)) { + osc_enable(OSC_MAINCK_XTAL); + osc_wait_ready(OSC_MAINCK_XTAL); + } + break; + + case GENCLK_PCK_SRC_MAINCK_BYPASS: + if (!osc_is_ready(OSC_MAINCK_BYPASS)) { + osc_enable(OSC_MAINCK_BYPASS); + osc_wait_ready(OSC_MAINCK_BYPASS); + } + break; + + #ifdef CONFIG_PLL0_SOURCE + case GENCLK_PCK_SRC_PLLACK: + pll_enable_config_defaults(0); + break; + #endif + + #ifdef CONFIG_PLL1_SOURCE + case GENCLK_PCK_SRC_PLLBCK: + pll_enable_config_defaults(1); + break; + #endif + + case GENCLK_PCK_SRC_MCK: + break; + + default: + Assert(false); + break; + } } //! @} diff --git a/Marlin/src/HAL/DUE/usb/mrepeat.h b/Marlin/src/HAL/DUE/usb/mrepeat.h index 8363d9cde380..10a8237545de 100644 --- a/Marlin/src/HAL/DUE/usb/mrepeat.h +++ b/Marlin/src/HAL/DUE/usb/mrepeat.h @@ -57,7 +57,6 @@ #include "preprocessor.h" - //! Maximal number of repetitions supported by MREPEAT. #define MREPEAT_LIMIT 256 diff --git a/Marlin/src/HAL/DUE/usb/osc.h b/Marlin/src/HAL/DUE/usb/osc.h index 953bcbbed1d3..1585018ed851 100644 --- a/Marlin/src/HAL/DUE/usb/osc.h +++ b/Marlin/src/HAL/DUE/usb/osc.h @@ -62,28 +62,28 @@ extern "C" { * should be defined by the board code, otherwise default value are used. */ #ifndef BOARD_FREQ_SLCK_XTAL -# warning The board slow clock xtal frequency has not been defined. -# define BOARD_FREQ_SLCK_XTAL (32768UL) + #warning The board slow clock xtal frequency has not been defined. + #define BOARD_FREQ_SLCK_XTAL (32768UL) #endif #ifndef BOARD_FREQ_SLCK_BYPASS -# warning The board slow clock bypass frequency has not been defined. -# define BOARD_FREQ_SLCK_BYPASS (32768UL) + #warning The board slow clock bypass frequency has not been defined. + #define BOARD_FREQ_SLCK_BYPASS (32768UL) #endif #ifndef BOARD_FREQ_MAINCK_XTAL -# warning The board main clock xtal frequency has not been defined. -# define BOARD_FREQ_MAINCK_XTAL (12000000UL) + #warning The board main clock xtal frequency has not been defined. + #define BOARD_FREQ_MAINCK_XTAL (12000000UL) #endif #ifndef BOARD_FREQ_MAINCK_BYPASS -# warning The board main clock bypass frequency has not been defined. -# define BOARD_FREQ_MAINCK_BYPASS (12000000UL) + #warning The board main clock bypass frequency has not been defined. + #define BOARD_FREQ_MAINCK_BYPASS (12000000UL) #endif #ifndef BOARD_OSC_STARTUP_US -# warning The board main clock xtal startup time has not been defined. -# define BOARD_OSC_STARTUP_US (15625UL) + #warning The board main clock xtal startup time has not been defined. + #define BOARD_OSC_STARTUP_US (15625UL) #endif /** @@ -115,122 +115,116 @@ extern "C" { #define OSC_MAINCK_BYPASS_HZ BOARD_FREQ_MAINCK_BYPASS //!< External bypass oscillator. //@} -static inline void osc_enable(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - break; - - case OSC_SLCK_32K_XTAL: - pmc_switch_sclk_to_32kxtal(PMC_OSC_XTAL); - break; - - case OSC_SLCK_32K_BYPASS: - pmc_switch_sclk_to_32kxtal(PMC_OSC_BYPASS); - break; - - - case OSC_MAINCK_4M_RC: - pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_4_MHz); - break; - - case OSC_MAINCK_8M_RC: - pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_8_MHz); - break; +static inline void osc_enable(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + break; + + case OSC_SLCK_32K_XTAL: + pmc_switch_sclk_to_32kxtal(PMC_OSC_XTAL); + break; + + case OSC_SLCK_32K_BYPASS: + pmc_switch_sclk_to_32kxtal(PMC_OSC_BYPASS); + break; + + case OSC_MAINCK_4M_RC: + pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_4_MHz); + break; + + case OSC_MAINCK_8M_RC: + pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_8_MHz); + break; + + case OSC_MAINCK_12M_RC: + pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_12_MHz); + break; + + case OSC_MAINCK_XTAL: + pmc_switch_mainck_to_xtal(PMC_OSC_XTAL/*, + pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, + OSC_SLCK_32K_RC_HZ)*/); + break; + + case OSC_MAINCK_BYPASS: + pmc_switch_mainck_to_xtal(PMC_OSC_BYPASS/*, + pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, + OSC_SLCK_32K_RC_HZ)*/); + break; + } +} - case OSC_MAINCK_12M_RC: - pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_12_MHz); - break; +static inline void osc_disable(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + case OSC_SLCK_32K_XTAL: + case OSC_SLCK_32K_BYPASS: + break; + + case OSC_MAINCK_4M_RC: + case OSC_MAINCK_8M_RC: + case OSC_MAINCK_12M_RC: + pmc_osc_disable_fastrc(); + break; + + case OSC_MAINCK_XTAL: + pmc_osc_disable_xtal(PMC_OSC_XTAL); + break; + + case OSC_MAINCK_BYPASS: + pmc_osc_disable_xtal(PMC_OSC_BYPASS); + break; + } +} +static inline bool osc_is_ready(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + return 1; - case OSC_MAINCK_XTAL: - pmc_switch_mainck_to_xtal(PMC_OSC_XTAL/*, - pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, - OSC_SLCK_32K_RC_HZ)*/); - break; + case OSC_SLCK_32K_XTAL: + case OSC_SLCK_32K_BYPASS: + return pmc_osc_is_ready_32kxtal(); - case OSC_MAINCK_BYPASS: - pmc_switch_mainck_to_xtal(PMC_OSC_BYPASS/*, - pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, - OSC_SLCK_32K_RC_HZ)*/); - break; - } -} - -static inline void osc_disable(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - case OSC_SLCK_32K_XTAL: - case OSC_SLCK_32K_BYPASS: - break; - - case OSC_MAINCK_4M_RC: - case OSC_MAINCK_8M_RC: - case OSC_MAINCK_12M_RC: - pmc_osc_disable_fastrc(); - break; - - case OSC_MAINCK_XTAL: - pmc_osc_disable_xtal(PMC_OSC_XTAL); - break; - - case OSC_MAINCK_BYPASS: - pmc_osc_disable_xtal(PMC_OSC_BYPASS); - break; - } -} + case OSC_MAINCK_4M_RC: + case OSC_MAINCK_8M_RC: + case OSC_MAINCK_12M_RC: + case OSC_MAINCK_XTAL: + case OSC_MAINCK_BYPASS: + return pmc_osc_is_ready_mainck(); + } -static inline bool osc_is_ready(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - return 1; - - case OSC_SLCK_32K_XTAL: - case OSC_SLCK_32K_BYPASS: - return pmc_osc_is_ready_32kxtal(); - - case OSC_MAINCK_4M_RC: - case OSC_MAINCK_8M_RC: - case OSC_MAINCK_12M_RC: - case OSC_MAINCK_XTAL: - case OSC_MAINCK_BYPASS: - return pmc_osc_is_ready_mainck(); - } - - return 0; + return 0; } -static inline uint32_t osc_get_rate(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - return OSC_SLCK_32K_RC_HZ; +static inline uint32_t osc_get_rate(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + return OSC_SLCK_32K_RC_HZ; - case OSC_SLCK_32K_XTAL: - return BOARD_FREQ_SLCK_XTAL; + case OSC_SLCK_32K_XTAL: + return BOARD_FREQ_SLCK_XTAL; - case OSC_SLCK_32K_BYPASS: - return BOARD_FREQ_SLCK_BYPASS; + case OSC_SLCK_32K_BYPASS: + return BOARD_FREQ_SLCK_BYPASS; - case OSC_MAINCK_4M_RC: - return OSC_MAINCK_4M_RC_HZ; + case OSC_MAINCK_4M_RC: + return OSC_MAINCK_4M_RC_HZ; - case OSC_MAINCK_8M_RC: - return OSC_MAINCK_8M_RC_HZ; + case OSC_MAINCK_8M_RC: + return OSC_MAINCK_8M_RC_HZ; - case OSC_MAINCK_12M_RC: - return OSC_MAINCK_12M_RC_HZ; + case OSC_MAINCK_12M_RC: + return OSC_MAINCK_12M_RC_HZ; - case OSC_MAINCK_XTAL: - return BOARD_FREQ_MAINCK_XTAL; + case OSC_MAINCK_XTAL: + return BOARD_FREQ_MAINCK_XTAL; - case OSC_MAINCK_BYPASS: - return BOARD_FREQ_MAINCK_BYPASS; - } + case OSC_MAINCK_BYPASS: + return BOARD_FREQ_MAINCK_BYPASS; + } - return 0; + return 0; } /** @@ -241,11 +235,10 @@ static inline uint32_t osc_get_rate(uint32_t ul_id) * * \param id A number identifying the oscillator to wait for. */ -static inline void osc_wait_ready(uint8_t id) -{ - while (!osc_is_ready(id)) { - /* Do nothing */ - } +static inline void osc_wait_ready(uint8_t id) { + while (!osc_is_ready(id)) { + /* Do nothing */ + } } //! @} diff --git a/Marlin/src/HAL/DUE/usb/pll.h b/Marlin/src/HAL/DUE/usb/pll.h index 8eaf27672b25..d25a1f65d09b 100644 --- a/Marlin/src/HAL/DUE/usb/pll.h +++ b/Marlin/src/HAL/DUE/usb/pll.h @@ -77,22 +77,22 @@ extern "C" { #define PLL_COUNT 0x3FU enum pll_source { - PLL_SRC_MAINCK_4M_RC = OSC_MAINCK_4M_RC, //!< Internal 4MHz RC oscillator. - PLL_SRC_MAINCK_8M_RC = OSC_MAINCK_8M_RC, //!< Internal 8MHz RC oscillator. - PLL_SRC_MAINCK_12M_RC = OSC_MAINCK_12M_RC, //!< Internal 12MHz RC oscillator. - PLL_SRC_MAINCK_XTAL = OSC_MAINCK_XTAL, //!< External crystal oscillator. - PLL_SRC_MAINCK_BYPASS = OSC_MAINCK_BYPASS, //!< External bypass oscillator. - PLL_NR_SOURCES, //!< Number of PLL sources. + PLL_SRC_MAINCK_4M_RC = OSC_MAINCK_4M_RC, //!< Internal 4MHz RC oscillator. + PLL_SRC_MAINCK_8M_RC = OSC_MAINCK_8M_RC, //!< Internal 8MHz RC oscillator. + PLL_SRC_MAINCK_12M_RC = OSC_MAINCK_12M_RC, //!< Internal 12MHz RC oscillator. + PLL_SRC_MAINCK_XTAL = OSC_MAINCK_XTAL, //!< External crystal oscillator. + PLL_SRC_MAINCK_BYPASS = OSC_MAINCK_BYPASS, //!< External bypass oscillator. + PLL_NR_SOURCES, //!< Number of PLL sources. }; struct pll_config { - uint32_t ctrl; + uint32_t ctrl; }; #define pll_get_default_rate(pll_id) \ - ((osc_get_rate(CONFIG_PLL##pll_id##_SOURCE) \ - * CONFIG_PLL##pll_id##_MUL) \ - / CONFIG_PLL##pll_id##_DIV) + ((osc_get_rate(CONFIG_PLL##pll_id##_SOURCE) \ + * CONFIG_PLL##pll_id##_MUL) \ + / CONFIG_PLL##pll_id##_DIV) /* Force UTMI PLL parameters (Hardware defined) */ #ifdef CONFIG_PLL1_SOURCE @@ -113,145 +113,130 @@ struct pll_config { * is hidden in this implementation. Use mul as mul effective value. */ static inline void pll_config_init(struct pll_config *p_cfg, - enum pll_source e_src, uint32_t ul_div, uint32_t ul_mul) -{ - uint32_t vco_hz; - - Assert(e_src < PLL_NR_SOURCES); - - if (ul_div == 0 && ul_mul == 0) { /* Must only be true for UTMI PLL */ - p_cfg->ctrl = CKGR_UCKR_UPLLCOUNT(PLL_COUNT); - } else { /* PLLA */ - /* Calculate internal VCO frequency */ - vco_hz = osc_get_rate(e_src) / ul_div; - Assert(vco_hz >= PLL_INPUT_MIN_HZ); - Assert(vco_hz <= PLL_INPUT_MAX_HZ); - - vco_hz *= ul_mul; - Assert(vco_hz >= PLL_OUTPUT_MIN_HZ); - Assert(vco_hz <= PLL_OUTPUT_MAX_HZ); - - /* PMC hardware will automatically make it mul+1 */ - p_cfg->ctrl = CKGR_PLLAR_MULA(ul_mul - 1) | CKGR_PLLAR_DIVA(ul_div) | CKGR_PLLAR_PLLACOUNT(PLL_COUNT); - } + enum pll_source e_src, uint32_t ul_div, uint32_t ul_mul) { + uint32_t vco_hz; + + Assert(e_src < PLL_NR_SOURCES); + + if (ul_div == 0 && ul_mul == 0) { /* Must only be true for UTMI PLL */ + p_cfg->ctrl = CKGR_UCKR_UPLLCOUNT(PLL_COUNT); + } + else { /* PLLA */ + /* Calculate internal VCO frequency */ + vco_hz = osc_get_rate(e_src) / ul_div; + Assert(vco_hz >= PLL_INPUT_MIN_HZ); + Assert(vco_hz <= PLL_INPUT_MAX_HZ); + + vco_hz *= ul_mul; + Assert(vco_hz >= PLL_OUTPUT_MIN_HZ); + Assert(vco_hz <= PLL_OUTPUT_MAX_HZ); + + /* PMC hardware will automatically make it mul+1 */ + p_cfg->ctrl = CKGR_PLLAR_MULA(ul_mul - 1) | CKGR_PLLAR_DIVA(ul_div) | CKGR_PLLAR_PLLACOUNT(PLL_COUNT); + } } -#define pll_config_defaults(cfg, pll_id) \ - pll_config_init(cfg, \ - CONFIG_PLL##pll_id##_SOURCE, \ - CONFIG_PLL##pll_id##_DIV, \ - CONFIG_PLL##pll_id##_MUL) - -static inline void pll_config_read(struct pll_config *p_cfg, uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); - - if (ul_pll_id == PLLA_ID) { - p_cfg->ctrl = PMC->CKGR_PLLAR; - } else { - p_cfg->ctrl = PMC->CKGR_UCKR; - } +#define pll_config_defaults(cfg, pll_id) \ + pll_config_init(cfg, \ + CONFIG_PLL##pll_id##_SOURCE, \ + CONFIG_PLL##pll_id##_DIV, \ + CONFIG_PLL##pll_id##_MUL) + +static inline void pll_config_read(struct pll_config *p_cfg, uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); + p_cfg->ctrl = ul_pll_id == PLLA_ID ? PMC->CKGR_PLLAR : PMC->CKGR_UCKR; } -static inline void pll_config_write(const struct pll_config *p_cfg, uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline void pll_config_write(const struct pll_config *p_cfg, uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - pmc_disable_pllack(); // Always stop PLL first! - PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; - } else { - PMC->CKGR_UCKR = p_cfg->ctrl; - } + if (ul_pll_id == PLLA_ID) { + pmc_disable_pllack(); // Always stop PLL first! + PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; + } + else + PMC->CKGR_UCKR = p_cfg->ctrl; } -static inline void pll_enable(const struct pll_config *p_cfg, uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline void pll_enable(const struct pll_config *p_cfg, uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - pmc_disable_pllack(); // Always stop PLL first! - PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; - } else { - PMC->CKGR_UCKR = p_cfg->ctrl | CKGR_UCKR_UPLLEN; - } + if (ul_pll_id == PLLA_ID) { + pmc_disable_pllack(); // Always stop PLL first! + PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; + } + else + PMC->CKGR_UCKR = p_cfg->ctrl | CKGR_UCKR_UPLLEN; } /** * \note This will only disable the selected PLL, not the underlying oscillator (mainck). */ -static inline void pll_disable(uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); - - if (ul_pll_id == PLLA_ID) { - pmc_disable_pllack(); - } else { - PMC->CKGR_UCKR &= ~CKGR_UCKR_UPLLEN; - } +static inline void pll_disable(uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); + + if (ul_pll_id == PLLA_ID) + pmc_disable_pllack(); + else + PMC->CKGR_UCKR &= ~CKGR_UCKR_UPLLEN; } -static inline uint32_t pll_is_locked(uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline uint32_t pll_is_locked(uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - return pmc_is_locked_pllack(); - } else { - return pmc_is_locked_upll(); - } + if (ul_pll_id == PLLA_ID) + return pmc_is_locked_pllack(); + else + return pmc_is_locked_upll(); } -static inline void pll_enable_source(enum pll_source e_src) -{ - switch (e_src) { - case PLL_SRC_MAINCK_4M_RC: - case PLL_SRC_MAINCK_8M_RC: - case PLL_SRC_MAINCK_12M_RC: - case PLL_SRC_MAINCK_XTAL: - case PLL_SRC_MAINCK_BYPASS: - osc_enable(e_src); - osc_wait_ready(e_src); - break; - - default: - Assert(false); - break; - } +static inline void pll_enable_source(enum pll_source e_src) { + switch (e_src) { + case PLL_SRC_MAINCK_4M_RC: + case PLL_SRC_MAINCK_8M_RC: + case PLL_SRC_MAINCK_12M_RC: + case PLL_SRC_MAINCK_XTAL: + case PLL_SRC_MAINCK_BYPASS: + osc_enable(e_src); + osc_wait_ready(e_src); + break; + + default: + Assert(false); + break; + } } -static inline void pll_enable_config_defaults(unsigned int ul_pll_id) -{ - struct pll_config pllcfg; - - if (pll_is_locked(ul_pll_id)) { - return; // Pll already running - } - switch (ul_pll_id) { -#ifdef CONFIG_PLL0_SOURCE - case 0: - pll_enable_source(CONFIG_PLL0_SOURCE); - pll_config_init(&pllcfg, - CONFIG_PLL0_SOURCE, - CONFIG_PLL0_DIV, - CONFIG_PLL0_MUL); - break; -#endif -#ifdef CONFIG_PLL1_SOURCE - case 1: - pll_enable_source(CONFIG_PLL1_SOURCE); - pll_config_init(&pllcfg, - CONFIG_PLL1_SOURCE, - CONFIG_PLL1_DIV, - CONFIG_PLL1_MUL); - break; -#endif - default: - Assert(false); - break; - } - pll_enable(&pllcfg, ul_pll_id); - while (!pll_is_locked(ul_pll_id)); +static inline void pll_enable_config_defaults(unsigned int ul_pll_id) { + struct pll_config pllcfg; + + if (pll_is_locked(ul_pll_id)) return; // Pll already running + + switch (ul_pll_id) { + #ifdef CONFIG_PLL0_SOURCE + case 0: + pll_enable_source(CONFIG_PLL0_SOURCE); + pll_config_init(&pllcfg, + CONFIG_PLL0_SOURCE, + CONFIG_PLL0_DIV, + CONFIG_PLL0_MUL); + break; + #endif + #ifdef CONFIG_PLL1_SOURCE + case 1: + pll_enable_source(CONFIG_PLL1_SOURCE); + pll_config_init(&pllcfg, + CONFIG_PLL1_SOURCE, + CONFIG_PLL1_DIV, + CONFIG_PLL1_MUL); + break; + #endif + default: + Assert(false); + break; + } + pll_enable(&pllcfg, ul_pll_id); + while (!pll_is_locked(ul_pll_id)); } /** @@ -264,15 +249,12 @@ static inline void pll_enable_config_defaults(unsigned int ul_pll_id) * \retval STATUS_OK The PLL is now locked. * \retval ERR_TIMEOUT Timed out waiting for PLL to become locked. */ -static inline int pll_wait_for_lock(unsigned int pll_id) -{ - Assert(pll_id < NR_PLLS); +static inline int pll_wait_for_lock(unsigned int pll_id) { + Assert(pll_id < NR_PLLS); - while (!pll_is_locked(pll_id)) { - /* Do nothing */ - } + while (!pll_is_locked(pll_id)) { /* Do nothing */ } - return 0; + return 0; } //! @} diff --git a/Marlin/src/HAL/DUE/usb/preprocessor.h b/Marlin/src/HAL/DUE/usb/preprocessor.h index c12d01cb642f..fe796c4fb83e 100644 --- a/Marlin/src/HAL/DUE/usb/preprocessor.h +++ b/Marlin/src/HAL/DUE/usb/preprocessor.h @@ -51,5 +51,4 @@ #include "stringz.h" #include "mrepeat.h" - #endif // _PREPROCESSOR_H_ diff --git a/Marlin/src/HAL/DUE/usb/sbc_protocol.h b/Marlin/src/HAL/DUE/usb/sbc_protocol.h index ab845739fd48..cdd4caa3cd50 100644 --- a/Marlin/src/HAL/DUE/usb/sbc_protocol.h +++ b/Marlin/src/HAL/DUE/usb/sbc_protocol.h @@ -57,7 +57,6 @@ #ifndef _SBC_PROTOCOL_H_ #define _SBC_PROTOCOL_H_ - /** * \ingroup usb_msc_protocol * \defgroup usb_sbc_protocol SCSI Block Commands protocol definitions @@ -81,82 +80,81 @@ //@{ enum scsi_sbc_mode { - SCSI_MS_MODE_RW_ERR_RECOV = 0x01, //!< Read-Write Error Recovery mode page - SCSI_MS_MODE_FORMAT_DEVICE = 0x03, //!< Format Device mode page - SCSI_MS_MODE_FLEXIBLE_DISK = 0x05, //!< Flexible Disk mode page - SCSI_MS_MODE_CACHING = 0x08, //!< Caching mode page + SCSI_MS_MODE_RW_ERR_RECOV = 0x01, //!< Read-Write Error Recovery mode page + SCSI_MS_MODE_FORMAT_DEVICE = 0x03, //!< Format Device mode page + SCSI_MS_MODE_FLEXIBLE_DISK = 0x05, //!< Flexible Disk mode page + SCSI_MS_MODE_CACHING = 0x08, //!< Caching mode page }; - //! \name SBC-2 Device-Specific Parameter //@{ -#define SCSI_MS_SBC_WP 0x80 //!< Write Protected -#define SCSI_MS_SBC_DPOFUA 0x10 //!< DPO and FUA supported +#define SCSI_MS_SBC_WP 0x80 //!< Write Protected +#define SCSI_MS_SBC_DPOFUA 0x10 //!< DPO and FUA supported //@} /** * \brief SBC-2 Short LBA mode parameter block descriptor */ struct sbc_slba_block_desc { - be32_t nr_blocks; //!< Number of Blocks - be32_t block_len; //!< Block Length -#define SBC_SLBA_BLOCK_LEN_MASK 0x00FFFFFFU //!< Mask reserved bits + be32_t nr_blocks; //!< Number of Blocks + be32_t block_len; //!< Block Length +#define SBC_SLBA_BLOCK_LEN_MASK 0x00FFFFFFU //!< Mask reserved bits }; /** * \brief SBC-2 Caching mode page */ struct sbc_caching_mode_page { - uint8_t page_code; - uint8_t page_length; - uint8_t flags2; -#define SBC_MP_CACHE_IC (1 << 7) //!< Initiator Control -#define SBC_MP_CACHE_ABPF (1 << 6) //!< Abort Pre-Fetch -#define SBC_MP_CACHE_CAP (1 << 5) //!< Catching Analysis Permitted -#define SBC_MP_CACHE_DISC (1 << 4) //!< Discontinuity -#define SBC_MP_CACHE_SIZE (1 << 3) //!< Size enable -#define SBC_MP_CACHE_WCE (1 << 2) //!< Write back Cache Enable -#define SBC_MP_CACHE_MF (1 << 1) //!< Multiplication Factor -#define SBC_MP_CACHE_RCD (1 << 0) //!< Read Cache Disable - uint8_t retention; - be16_t dis_pf_transfer_len; - be16_t min_prefetch; - be16_t max_prefetch; - be16_t max_prefetch_ceil; - uint8_t flags12; -#define SBC_MP_CACHE_FSW (1 << 7) //!< Force Sequential Write -#define SBC_MP_CACHE_LBCSS (1 << 6) //!< Logical Blk Cache Seg Sz -#define SBC_MP_CACHE_DRA (1 << 5) //!< Disable Read-Ahead -#define SBC_MP_CACHE_NV_DIS (1 << 0) //!< Non-Volatile Cache Disable - uint8_t nr_cache_segments; - be16_t cache_segment_size; - uint8_t reserved[4]; + uint8_t page_code; + uint8_t page_length; + uint8_t flags2; +#define SBC_MP_CACHE_IC (1 << 7) //!< Initiator Control +#define SBC_MP_CACHE_ABPF (1 << 6) //!< Abort Pre-Fetch +#define SBC_MP_CACHE_CAP (1 << 5) //!< Catching Analysis Permitted +#define SBC_MP_CACHE_DISC (1 << 4) //!< Discontinuity +#define SBC_MP_CACHE_SIZE (1 << 3) //!< Size enable +#define SBC_MP_CACHE_WCE (1 << 2) //!< Write back Cache Enable +#define SBC_MP_CACHE_MF (1 << 1) //!< Multiplication Factor +#define SBC_MP_CACHE_RCD (1 << 0) //!< Read Cache Disable + uint8_t retention; + be16_t dis_pf_transfer_len; + be16_t min_prefetch; + be16_t max_prefetch; + be16_t max_prefetch_ceil; + uint8_t flags12; +#define SBC_MP_CACHE_FSW (1 << 7) //!< Force Sequential Write +#define SBC_MP_CACHE_LBCSS (1 << 6) //!< Logical Blk Cache Seg Sz +#define SBC_MP_CACHE_DRA (1 << 5) //!< Disable Read-Ahead +#define SBC_MP_CACHE_NV_DIS (1 << 0) //!< Non-Volatile Cache Disable + uint8_t nr_cache_segments; + be16_t cache_segment_size; + uint8_t reserved[4]; }; /** * \brief SBC-2 Read-Write Error Recovery mode page */ struct sbc_rdwr_error_recovery_mode_page { - uint8_t page_code; - uint8_t page_length; -#define SPC_MP_RW_ERR_RECOV_PAGE_LENGTH 0x0A - uint8_t flags1; -#define SBC_MP_RW_ERR_RECOV_AWRE (1 << 7) -#define SBC_MP_RW_ERR_RECOV_ARRE (1 << 6) -#define SBC_MP_RW_ERR_RECOV_TB (1 << 5) -#define SBC_MP_RW_ERR_RECOV_RC (1 << 4) -#define SBC_MP_RW_ERR_RECOV_ERR (1 << 3) -#define SBC_MP_RW_ERR_RECOV_PER (1 << 2) -#define SBC_MP_RW_ERR_RECOV_DTE (1 << 1) -#define SBC_MP_RW_ERR_RECOV_DCR (1 << 0) - uint8_t read_retry_count; - uint8_t correction_span; - uint8_t head_offset_count; - uint8_t data_strobe_offset_count; - uint8_t flags2; - uint8_t write_retry_count; - uint8_t flags3; - be16_t recovery_time_limit; + uint8_t page_code; + uint8_t page_length; + #define SPC_MP_RW_ERR_RECOV_PAGE_LENGTH 0x0A + uint8_t flags1; + #define SBC_MP_RW_ERR_RECOV_AWRE (1 << 7) + #define SBC_MP_RW_ERR_RECOV_ARRE (1 << 6) + #define SBC_MP_RW_ERR_RECOV_TB (1 << 5) + #define SBC_MP_RW_ERR_RECOV_RC (1 << 4) + #define SBC_MP_RW_ERR_RECOV_ERR (1 << 3) + #define SBC_MP_RW_ERR_RECOV_PER (1 << 2) + #define SBC_MP_RW_ERR_RECOV_DTE (1 << 1) + #define SBC_MP_RW_ERR_RECOV_DCR (1 << 0) + uint8_t read_retry_count; + uint8_t correction_span; + uint8_t head_offset_count; + uint8_t data_strobe_offset_count; + uint8_t flags2; + uint8_t write_retry_count; + uint8_t flags3; + be16_t recovery_time_limit; }; //@} @@ -164,8 +162,8 @@ struct sbc_rdwr_error_recovery_mode_page { * \brief SBC-2 READ CAPACITY (10) parameter data */ struct sbc_read_capacity10_data { - be32_t max_lba; //!< LBA of last logical block - be32_t block_len; //!< Number of bytes in the last logical block + be32_t max_lba; //!< LBA of last logical block + be32_t block_len; //!< Number of bytes in the last logical block }; //@} diff --git a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp index 34cc256b30ff..65a926ff362b 100644 --- a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp +++ b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.cpp @@ -6,7 +6,7 @@ #include "../../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../../../sd/cardreader.h" extern "C" { @@ -138,5 +138,5 @@ Ctrl_status sd_mmc_spi_usb_write_10(uint32_t addr, uint16_t nb_sector) { #endif // ACCESS_USB == true -#endif // SDSUPPORT +#endif // HAS_MEDIA #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h index 553fd3c29a88..c0d3c925e80a 100644 --- a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h +++ b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h @@ -45,7 +45,6 @@ * Support and FAQ: visit Atmel Support */ - #ifndef _SD_MMC_SPI_MEM_H_ #define _SD_MMC_SPI_MEM_H_ @@ -63,17 +62,14 @@ #error sd_mmc_spi_mem.h is #included although SD_MMC_SPI_MEM is disabled #endif - #include "ctrl_access.h" - //_____ D E F I N I T I O N S ______________________________________________ #define SD_MMC_REMOVED 0 #define SD_MMC_INSERTED 1 #define SD_MMC_REMOVING 2 - //---- CONTROL FUNCTIONS ---- //! //! @brief This function initializes the hw/sw resources required to drive the SD_MMC_SPI. @@ -133,7 +129,6 @@ extern bool sd_mmc_spi_wr_protect(void); //! extern bool sd_mmc_spi_removal(void); - //---- ACCESS DATA FUNCTIONS ---- #if ACCESS_USB == true diff --git a/Marlin/src/HAL/DUE/usb/spc_protocol.h b/Marlin/src/HAL/DUE/usb/spc_protocol.h index d67cc5c78803..808c388f4fc4 100644 --- a/Marlin/src/HAL/DUE/usb/spc_protocol.h +++ b/Marlin/src/HAL/DUE/usb/spc_protocol.h @@ -59,23 +59,23 @@ //! \name SCSI commands defined by SPC-2 //@{ -#define SPC_TEST_UNIT_READY 0x00 -#define SPC_REQUEST_SENSE 0x03 -#define SPC_INQUIRY 0x12 -#define SPC_MODE_SELECT6 0x15 -#define SPC_MODE_SENSE6 0x1A -#define SPC_SEND_DIAGNOSTIC 0x1D -#define SPC_PREVENT_ALLOW_MEDIUM_REMOVAL 0x1E -#define SPC_MODE_SENSE10 0x5A -#define SPC_REPORT_LUNS 0xA0 +#define SPC_TEST_UNIT_READY 0x00 +#define SPC_REQUEST_SENSE 0x03 +#define SPC_INQUIRY 0x12 +#define SPC_MODE_SELECT6 0x15 +#define SPC_MODE_SENSE6 0x1A +#define SPC_SEND_DIAGNOSTIC 0x1D +#define SPC_PREVENT_ALLOW_MEDIUM_REMOVAL 0x1E +#define SPC_MODE_SENSE10 0x5A +#define SPC_REPORT_LUNS 0xA0 //@} //! \brief May be set in byte 0 of the INQUIRY CDB //@{ //! Enable Vital Product Data -#define SCSI_INQ_REQ_EVPD 0x01 +#define SCSI_INQ_REQ_EVPD 0x01 //! Command Support Data specified by the PAGE OR OPERATION CODE field -#define SCSI_INQ_REQ_CMDT 0x02 +#define SCSI_INQ_REQ_CMDT 0x02 //@} COMPILER_PACK_SET(1) @@ -84,110 +84,110 @@ COMPILER_PACK_SET(1) * \brief SCSI Standard Inquiry data structure */ struct scsi_inquiry_data { - uint8_t pq_pdt; //!< Peripheral Qual / Peripheral Dev Type -#define SCSI_INQ_PQ_CONNECTED 0x00 //!< Peripheral connected -#define SCSI_INQ_PQ_NOT_CONN 0x20 //!< Peripheral not connected -#define SCSI_INQ_PQ_NOT_SUPP 0x60 //!< Peripheral not supported -#define SCSI_INQ_DT_DIR_ACCESS 0x00 //!< Direct Access (SBC) -#define SCSI_INQ_DT_SEQ_ACCESS 0x01 //!< Sequential Access -#define SCSI_INQ_DT_PRINTER 0x02 //!< Printer -#define SCSI_INQ_DT_PROCESSOR 0x03 //!< Processor device -#define SCSI_INQ_DT_WRITE_ONCE 0x04 //!< Write-once device -#define SCSI_INQ_DT_CD_DVD 0x05 //!< CD/DVD device -#define SCSI_INQ_DT_OPTICAL 0x07 //!< Optical Memory -#define SCSI_INQ_DT_MC 0x08 //!< Medium Changer -#define SCSI_INQ_DT_ARRAY 0x0C //!< Storage Array Controller -#define SCSI_INQ_DT_ENCLOSURE 0x0D //!< Enclosure Services -#define SCSI_INQ_DT_RBC 0x0E //!< Simplified Direct Access -#define SCSI_INQ_DT_OCRW 0x0F //!< Optical card reader/writer -#define SCSI_INQ_DT_BCC 0x10 //!< Bridge Controller Commands -#define SCSI_INQ_DT_OSD 0x11 //!< Object-based Storage -#define SCSI_INQ_DT_NONE 0x1F //!< No Peripheral - uint8_t flags1; //!< Flags (byte 1) -#define SCSI_INQ_RMB 0x80 //!< Removable Medium - uint8_t version; //!< Version -#define SCSI_INQ_VER_NONE 0x00 //!< No standards conformance -#define SCSI_INQ_VER_SPC 0x03 //!< SCSI Primary Commands (link to SBC) -#define SCSI_INQ_VER_SPC2 0x04 //!< SCSI Primary Commands - 2 (link to SBC-2) -#define SCSI_INQ_VER_SPC3 0x05 //!< SCSI Primary Commands - 3 (link to SBC-2) -#define SCSI_INQ_VER_SPC4 0x06 //!< SCSI Primary Commands - 4 (link to SBC-3) - uint8_t flags3; //!< Flags (byte 3) -#define SCSI_INQ_NORMACA 0x20 //!< Normal ACA Supported -#define SCSI_INQ_HISUP 0x10 //!< Hierarchal LUN addressing -#define SCSI_INQ_RSP_SPC2 0x02 //!< SPC-2 / SPC-3 response format - uint8_t addl_len; //!< Additional Length (n-4) -#define SCSI_INQ_ADDL_LEN(tot) ((tot)-5) //!< Total length is \a tot - uint8_t flags5; //!< Flags (byte 5) -#define SCSI_INQ_SCCS 0x80 - uint8_t flags6; //!< Flags (byte 6) -#define SCSI_INQ_BQUE 0x80 -#define SCSI_INQ_ENCSERV 0x40 -#define SCSI_INQ_MULTIP 0x10 -#define SCSI_INQ_MCHGR 0x08 -#define SCSI_INQ_ADDR16 0x01 - uint8_t flags7; //!< Flags (byte 7) -#define SCSI_INQ_WBUS16 0x20 -#define SCSI_INQ_SYNC 0x10 -#define SCSI_INQ_LINKED 0x08 -#define SCSI_INQ_CMDQUE 0x02 - uint8_t vendor_id[8]; //!< T10 Vendor Identification - uint8_t product_id[16]; //!< Product Identification - uint8_t product_rev[4]; //!< Product Revision Level + uint8_t pq_pdt; //!< Peripheral Qual / Peripheral Dev Type + #define SCSI_INQ_PQ_CONNECTED 0x00 //!< Peripheral connected + #define SCSI_INQ_PQ_NOT_CONN 0x20 //!< Peripheral not connected + #define SCSI_INQ_PQ_NOT_SUPP 0x60 //!< Peripheral not supported + #define SCSI_INQ_DT_DIR_ACCESS 0x00 //!< Direct Access (SBC) + #define SCSI_INQ_DT_SEQ_ACCESS 0x01 //!< Sequential Access + #define SCSI_INQ_DT_PRINTER 0x02 //!< Printer + #define SCSI_INQ_DT_PROCESSOR 0x03 //!< Processor device + #define SCSI_INQ_DT_WRITE_ONCE 0x04 //!< Write-once device + #define SCSI_INQ_DT_CD_DVD 0x05 //!< CD/DVD device + #define SCSI_INQ_DT_OPTICAL 0x07 //!< Optical Memory + #define SCSI_INQ_DT_MC 0x08 //!< Medium Changer + #define SCSI_INQ_DT_ARRAY 0x0C //!< Storage Array Controller + #define SCSI_INQ_DT_ENCLOSURE 0x0D //!< Enclosure Services + #define SCSI_INQ_DT_RBC 0x0E //!< Simplified Direct Access + #define SCSI_INQ_DT_OCRW 0x0F //!< Optical card reader/writer + #define SCSI_INQ_DT_BCC 0x10 //!< Bridge Controller Commands + #define SCSI_INQ_DT_OSD 0x11 //!< Object-based Storage + #define SCSI_INQ_DT_NONE 0x1F //!< No Peripheral + uint8_t flags1; //!< Flags (byte 1) + #define SCSI_INQ_RMB 0x80 //!< Removable Medium + uint8_t version; //!< Version + #define SCSI_INQ_VER_NONE 0x00 //!< No standards conformance + #define SCSI_INQ_VER_SPC 0x03 //!< SCSI Primary Commands (link to SBC) + #define SCSI_INQ_VER_SPC2 0x04 //!< SCSI Primary Commands - 2 (link to SBC-2) + #define SCSI_INQ_VER_SPC3 0x05 //!< SCSI Primary Commands - 3 (link to SBC-2) + #define SCSI_INQ_VER_SPC4 0x06 //!< SCSI Primary Commands - 4 (link to SBC-3) + uint8_t flags3; //!< Flags (byte 3) + #define SCSI_INQ_NORMACA 0x20 //!< Normal ACA Supported + #define SCSI_INQ_HISUP 0x10 //!< Hierarchal LUN addressing + #define SCSI_INQ_RSP_SPC2 0x02 //!< SPC-2 / SPC-3 response format + uint8_t addl_len; //!< Additional Length (n-4) + #define SCSI_INQ_ADDL_LEN(tot) ((tot)-5) //!< Total length is \a tot + uint8_t flags5; //!< Flags (byte 5) + #define SCSI_INQ_SCCS 0x80 + uint8_t flags6; //!< Flags (byte 6) + #define SCSI_INQ_BQUE 0x80 + #define SCSI_INQ_ENCSERV 0x40 + #define SCSI_INQ_MULTIP 0x10 + #define SCSI_INQ_MCHGR 0x08 + #define SCSI_INQ_ADDR16 0x01 + uint8_t flags7; //!< Flags (byte 7) + #define SCSI_INQ_WBUS16 0x20 + #define SCSI_INQ_SYNC 0x10 + #define SCSI_INQ_LINKED 0x08 + #define SCSI_INQ_CMDQUE 0x02 + uint8_t vendor_id[8]; //!< T10 Vendor Identification + uint8_t product_id[16]; //!< Product Identification + uint8_t product_rev[4]; //!< Product Revision Level }; /** * \brief SCSI Standard Request sense data structure */ struct scsi_request_sense_data { - /* 1st byte: REQUEST SENSE response flags*/ - uint8_t valid_reponse_code; -#define SCSI_SENSE_VALID 0x80 //!< Indicates the INFORMATION field contains valid information -#define SCSI_SENSE_RESPONSE_CODE_MASK 0x7F -#define SCSI_SENSE_CURRENT 0x70 //!< Response code 70h (current errors) -#define SCSI_SENSE_DEFERRED 0x71 - - /* 2nd byte */ - uint8_t obsolete; - - /* 3rd byte */ - uint8_t sense_flag_key; -#define SCSI_SENSE_FILEMARK 0x80 //!< Indicates that the current command has read a filemark or setmark. -#define SCSI_SENSE_EOM 0x40 //!< Indicates that an end-of-medium condition exists. -#define SCSI_SENSE_ILI 0x20 //!< Indicates that the requested logical block length did not match the logical block length of the data on the medium. -#define SCSI_SENSE_RESERVED 0x10 //!< Reserved -#define SCSI_SENSE_KEY(x) (x&0x0F) //!< Sense Key - - /* 4th to 7th bytes - INFORMATION field */ - uint8_t information[4]; - - /* 8th byte - ADDITIONAL SENSE LENGTH field */ - uint8_t AddSenseLen; -#define SCSI_SENSE_ADDL_LEN(total_len) ((total_len) - 8) - - /* 9th to 12th byte - COMMAND-SPECIFIC INFORMATION field */ - uint8_t CmdSpecINFO[4]; - - /* 13th byte - ADDITIONAL SENSE CODE field */ - uint8_t AddSenseCode; - - /* 14th byte - ADDITIONAL SENSE CODE QUALIFIER field */ - uint8_t AddSnsCodeQlfr; - - /* 15th byte - FIELD REPLACEABLE UNIT CODE field */ - uint8_t FldReplUnitCode; - - /* 16th byte */ - uint8_t SenseKeySpec[3]; -#define SCSI_SENSE_SKSV 0x80 //!< Indicates the SENSE-KEY SPECIFIC field contains valid information + /* 1st byte: REQUEST SENSE response flags*/ + uint8_t valid_reponse_code; + #define SCSI_SENSE_VALID 0x80 //!< Indicates the INFORMATION field contains valid information + #define SCSI_SENSE_RESPONSE_CODE_MASK 0x7F + #define SCSI_SENSE_CURRENT 0x70 //!< Response code 70h (current errors) + #define SCSI_SENSE_DEFERRED 0x71 + + /* 2nd byte */ + uint8_t obsolete; + + /* 3rd byte */ + uint8_t sense_flag_key; + #define SCSI_SENSE_FILEMARK 0x80 //!< Indicates that the current command has read a filemark or setmark. + #define SCSI_SENSE_EOM 0x40 //!< Indicates that an end-of-medium condition exists. + #define SCSI_SENSE_ILI 0x20 //!< Indicates that the requested logical block length did not match the logical block length of the data on the medium. + #define SCSI_SENSE_RESERVED 0x10 //!< Reserved + #define SCSI_SENSE_KEY(x) (x&0x0F) //!< Sense Key + + /* 4th to 7th bytes - INFORMATION field */ + uint8_t information[4]; + + /* 8th byte - ADDITIONAL SENSE LENGTH field */ + uint8_t AddSenseLen; + #define SCSI_SENSE_ADDL_LEN(total_len) ((total_len) - 8) + + /* 9th to 12th byte - COMMAND-SPECIFIC INFORMATION field */ + uint8_t CmdSpecINFO[4]; + + /* 13th byte - ADDITIONAL SENSE CODE field */ + uint8_t AddSenseCode; + + /* 14th byte - ADDITIONAL SENSE CODE QUALIFIER field */ + uint8_t AddSnsCodeQlfr; + + /* 15th byte - FIELD REPLACEABLE UNIT CODE field */ + uint8_t FldReplUnitCode; + + /* 16th byte */ + uint8_t SenseKeySpec[3]; + #define SCSI_SENSE_SKSV 0x80 //!< Indicates the SENSE-KEY SPECIFIC field contains valid information }; COMPILER_PACK_RESET() /* Vital Product Data page codes */ enum scsi_vpd_page_code { - SCSI_VPD_SUPPORTED_PAGES = 0x00, - SCSI_VPD_UNIT_SERIAL_NUMBER = 0x80, - SCSI_VPD_DEVICE_IDENTIFICATION = 0x83, + SCSI_VPD_SUPPORTED_PAGES = 0x00, + SCSI_VPD_UNIT_SERIAL_NUMBER = 0x80, + SCSI_VPD_DEVICE_IDENTIFICATION = 0x83, }; #define SCSI_VPD_HEADER_SIZE 4 @@ -200,37 +200,36 @@ enum scsi_vpd_page_code { #define SCSI_VPD_ID_TYPE_T10 1 - /* Sense keys */ enum scsi_sense_key { - SCSI_SK_NO_SENSE = 0x0, - SCSI_SK_RECOVERED_ERROR = 0x1, - SCSI_SK_NOT_READY = 0x2, - SCSI_SK_MEDIUM_ERROR = 0x3, - SCSI_SK_HARDWARE_ERROR = 0x4, - SCSI_SK_ILLEGAL_REQUEST = 0x5, - SCSI_SK_UNIT_ATTENTION = 0x6, - SCSI_SK_DATA_PROTECT = 0x7, - SCSI_SK_BLANK_CHECK = 0x8, - SCSI_SK_VENDOR_SPECIFIC = 0x9, - SCSI_SK_COPY_ABORTED = 0xA, - SCSI_SK_ABORTED_COMMAND = 0xB, - SCSI_SK_VOLUME_OVERFLOW = 0xD, - SCSI_SK_MISCOMPARE = 0xE, + SCSI_SK_NO_SENSE = 0x0, + SCSI_SK_RECOVERED_ERROR = 0x1, + SCSI_SK_NOT_READY = 0x2, + SCSI_SK_MEDIUM_ERROR = 0x3, + SCSI_SK_HARDWARE_ERROR = 0x4, + SCSI_SK_ILLEGAL_REQUEST = 0x5, + SCSI_SK_UNIT_ATTENTION = 0x6, + SCSI_SK_DATA_PROTECT = 0x7, + SCSI_SK_BLANK_CHECK = 0x8, + SCSI_SK_VENDOR_SPECIFIC = 0x9, + SCSI_SK_COPY_ABORTED = 0xA, + SCSI_SK_ABORTED_COMMAND = 0xB, + SCSI_SK_VOLUME_OVERFLOW = 0xD, + SCSI_SK_MISCOMPARE = 0xE, }; /* Additional Sense Code / Additional Sense Code Qualifier pairs */ enum scsi_asc_ascq { - SCSI_ASC_NO_ADDITIONAL_SENSE_INFO = 0x0000, - SCSI_ASC_LU_NOT_READY_REBUILD_IN_PROGRESS = 0x0405, - SCSI_ASC_WRITE_ERROR = 0x0C00, - SCSI_ASC_UNRECOVERED_READ_ERROR = 0x1100, - SCSI_ASC_INVALID_COMMAND_OPERATION_CODE = 0x2000, - SCSI_ASC_INVALID_FIELD_IN_CDB = 0x2400, - SCSI_ASC_WRITE_PROTECTED = 0x2700, - SCSI_ASC_NOT_READY_TO_READY_CHANGE = 0x2800, - SCSI_ASC_MEDIUM_NOT_PRESENT = 0x3A00, - SCSI_ASC_INTERNAL_TARGET_FAILURE = 0x4400, + SCSI_ASC_NO_ADDITIONAL_SENSE_INFO = 0x0000, + SCSI_ASC_LU_NOT_READY_REBUILD_IN_PROGRESS = 0x0405, + SCSI_ASC_WRITE_ERROR = 0x0C00, + SCSI_ASC_UNRECOVERED_READ_ERROR = 0x1100, + SCSI_ASC_INVALID_COMMAND_OPERATION_CODE = 0x2000, + SCSI_ASC_INVALID_FIELD_IN_CDB = 0x2400, + SCSI_ASC_WRITE_PROTECTED = 0x2700, + SCSI_ASC_NOT_READY_TO_READY_CHANGE = 0x2800, + SCSI_ASC_MEDIUM_NOT_PRESENT = 0x3A00, + SCSI_ASC_INTERNAL_TARGET_FAILURE = 0x4400, }; /** @@ -240,9 +239,9 @@ enum scsi_asc_ascq { * that are applicable to all SCSI devices. */ enum scsi_spc_mode { - SCSI_MS_MODE_VENDOR_SPEC = 0x00, - SCSI_MS_MODE_INFEXP = 0x1C, // Informational exceptions control page - SCSI_MS_MODE_ALL = 0x3F, + SCSI_MS_MODE_VENDOR_SPEC = 0x00, + SCSI_MS_MODE_INFEXP = 0x1C, // Informational exceptions control page + SCSI_MS_MODE_ALL = 0x3F, }; /** @@ -250,51 +249,45 @@ enum scsi_spc_mode { * See chapter 8.3.8 */ struct spc_control_page_info_execpt { - uint8_t page_code; - uint8_t page_length; -#define SPC_MP_INFEXP_PAGE_LENGTH 0x0A - uint8_t flags1; -#define SPC_MP_INFEXP_PERF (1<<7) //!< Initiator Control -#define SPC_MP_INFEXP_EBF (1<<5) //!< Caching Analysis Permitted -#define SPC_MP_INFEXP_EWASC (1<<4) //!< Discontinuity -#define SPC_MP_INFEXP_DEXCPT (1<<3) //!< Size enable -#define SPC_MP_INFEXP_TEST (1<<2) //!< Writeback Cache Enable -#define SPC_MP_INFEXP_LOGERR (1<<0) //!< Log errors bit - uint8_t mrie; -#define SPC_MP_INFEXP_MRIE_NO_REPORT 0x00 -#define SPC_MP_INFEXP_MRIE_ASYNC_EVENT 0x01 -#define SPC_MP_INFEXP_MRIE_GEN_UNIT 0x02 -#define SPC_MP_INFEXP_MRIE_COND_RECOV_ERROR 0x03 -#define SPC_MP_INFEXP_MRIE_UNCOND_RECOV_ERROR 0x04 -#define SPC_MP_INFEXP_MRIE_NO_SENSE 0x05 -#define SPC_MP_INFEXP_MRIE_ONLY_REPORT 0x06 - be32_t interval_timer; - be32_t report_count; + uint8_t page_code; + uint8_t page_length; + #define SPC_MP_INFEXP_PAGE_LENGTH 0x0A + uint8_t flags1; + #define SPC_MP_INFEXP_PERF (1<<7) //!< Initiator Control + #define SPC_MP_INFEXP_EBF (1<<5) //!< Caching Analysis Permitted + #define SPC_MP_INFEXP_EWASC (1<<4) //!< Discontinuity + #define SPC_MP_INFEXP_DEXCPT (1<<3) //!< Size enable + #define SPC_MP_INFEXP_TEST (1<<2) //!< Writeback Cache Enable + #define SPC_MP_INFEXP_LOGERR (1<<0) //!< Log errors bit + uint8_t mrie; + #define SPC_MP_INFEXP_MRIE_NO_REPORT 0x00 + #define SPC_MP_INFEXP_MRIE_ASYNC_EVENT 0x01 + #define SPC_MP_INFEXP_MRIE_GEN_UNIT 0x02 + #define SPC_MP_INFEXP_MRIE_COND_RECOV_ERROR 0x03 + #define SPC_MP_INFEXP_MRIE_UNCOND_RECOV_ERROR 0x04 + #define SPC_MP_INFEXP_MRIE_NO_SENSE 0x05 + #define SPC_MP_INFEXP_MRIE_ONLY_REPORT 0x06 + be32_t interval_timer; + be32_t report_count; }; - enum scsi_spc_mode_sense_pc { - SCSI_MS_SENSE_PC_CURRENT = 0, - SCSI_MS_SENSE_PC_CHANGEABLE = 1, - SCSI_MS_SENSE_PC_DEFAULT = 2, - SCSI_MS_SENSE_PC_SAVED = 3, + SCSI_MS_SENSE_PC_CURRENT = 0, + SCSI_MS_SENSE_PC_CHANGEABLE = 1, + SCSI_MS_SENSE_PC_DEFAULT = 2, + SCSI_MS_SENSE_PC_SAVED = 3, }; - - -static inline bool scsi_mode_sense_dbd_is_set(const uint8_t * cdb) -{ - return (cdb[1] >> 3) & 1; +static inline bool scsi_mode_sense_dbd_is_set(const uint8_t * cdb) { + return (cdb[1] >> 3) & 1; } -static inline uint8_t scsi_mode_sense_get_page_code(const uint8_t * cdb) -{ - return cdb[2] & 0x3F; +static inline uint8_t scsi_mode_sense_get_page_code(const uint8_t * cdb) { + return cdb[2] & 0x3F; } -static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb) -{ - return cdb[2] >> 6; +static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb) { + return cdb[2] >> 6; } /** @@ -302,10 +295,10 @@ static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb) * SENSE(6) */ struct scsi_mode_param_header6 { - uint8_t mode_data_length; //!< Number of bytes after this - uint8_t medium_type; //!< Medium Type - uint8_t device_specific_parameter; //!< Defined by command set - uint8_t block_descriptor_length; //!< Length of block descriptors + uint8_t mode_data_length; //!< Number of bytes after this + uint8_t medium_type; //!< Medium Type + uint8_t device_specific_parameter; //!< Defined by command set + uint8_t block_descriptor_length; //!< Length of block descriptors }; /** @@ -313,23 +306,23 @@ struct scsi_mode_param_header6 { * SENSE(10) */ struct scsi_mode_param_header10 { - be16_t mode_data_length; //!< Number of bytes after this - uint8_t medium_type; //!< Medium Type - uint8_t device_specific_parameter; //!< Defined by command set - uint8_t flags4; //!< LONGLBA in bit 0 - uint8_t reserved; - be16_t block_descriptor_length; //!< Length of block descriptors + be16_t mode_data_length; //!< Number of bytes after this + uint8_t medium_type; //!< Medium Type + uint8_t device_specific_parameter; //!< Defined by command set + uint8_t flags4; //!< LONGLBA in bit 0 + uint8_t reserved; + be16_t block_descriptor_length; //!< Length of block descriptors }; /** * \brief SCSI Page_0 Mode Page header (SPF not set) */ struct scsi_mode_page_0_header { - uint8_t page_code; -#define SCSI_PAGE_CODE_PS (1 << 7) //!< Parameters Saveable -#define SCSI_PAGE_CODE_SPF (1 << 6) //!< SubPage Format - uint8_t page_length; //!< Number of bytes after this -#define SCSI_MS_PAGE_LEN(total) ((total) - 2) + uint8_t page_code; +#define SCSI_PAGE_CODE_PS (1 << 7) //!< Parameters Saveable +#define SCSI_PAGE_CODE_SPF (1 << 6) //!< SubPage Format + uint8_t page_length; //!< Number of bytes after this +#define SCSI_MS_PAGE_LEN(total) ((total) - 2) }; //@} diff --git a/Marlin/src/HAL/DUE/usb/sysclk.h b/Marlin/src/HAL/DUE/usb/sysclk.h index 16db8c86d373..4001366868a0 100644 --- a/Marlin/src/HAL/DUE/usb/sysclk.h +++ b/Marlin/src/HAL/DUE/usb/sysclk.h @@ -71,7 +71,7 @@ * \subsection sysclk_quickstart_use_case_1_setup_steps Initialization code * Add to the application initialization code: * \code - sysclk_init(); + sysclk_init(); \endcode * * \subsection sysclk_quickstart_use_case_1_setup_steps_workflow Workflow @@ -82,15 +82,15 @@ * Add or uncomment the following in your conf_clock.h header file, commenting out all other * definitions of the same symbol(s): * \code - #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLLACK + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLLACK - // Fpll0 = (Fclk * PLL_mul) / PLL_div - #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL - #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) - #define CONFIG_PLL0_DIV 1 + // Fpll0 = (Fclk * PLL_mul) / PLL_div + #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL + #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) + #define CONFIG_PLL0_DIV 1 - // Fbus = Fsys / BUS_div - #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 + // Fbus = Fsys / BUS_div + #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 \endcode * * \subsection sysclk_quickstart_use_case_1_example_workflow Workflow @@ -100,14 +100,14 @@ * \code #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL \endcode * -# Configure the PLL module to multiply the external fast crystal oscillator frequency up to 84MHz: * \code - #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) - #define CONFIG_PLL0_DIV 1 + #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) + #define CONFIG_PLL0_DIV 1 \endcode * \note For user boards, \c BOARD_FREQ_MAINCK_XTAL should be defined in the board \c conf_board.h configuration * file as the frequency of the fast crystal attached to the microcontroller. * -# Configure the main clock to run at the full 84MHz, disable scaling of the main system clock speed: * \code - #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 + #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 \endcode * \note Some dividers are powers of two, while others are integer division factors. Refer to the * formulas in the conf_clock.h template commented above each division define. @@ -136,7 +136,7 @@ extern "C" { * initialization. */ #ifndef CONFIG_SYSCLK_SOURCE -# define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_4M_RC + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_4M_RC #endif /** * \def CONFIG_SYSCLK_PRES @@ -149,7 +149,7 @@ extern "C" { * after initialization. */ #ifndef CONFIG_SYSCLK_PRES -# define CONFIG_SYSCLK_PRES 0 + #define CONFIG_SYSCLK_PRES 0 #endif //@} @@ -197,7 +197,7 @@ extern "C" { * USB is not required. */ #ifdef __DOXYGEN__ -# define CONFIG_USBCLK_SOURCE + #define CONFIG_USBCLK_SOURCE #endif /** @@ -209,10 +209,9 @@ extern "C" { * defined. */ #ifdef __DOXYGEN__ -# define CONFIG_USBCLK_DIV + #define CONFIG_USBCLK_DIV #endif - extern void sysclk_enable_usb(void); extern void sysclk_disable_usb(void); diff --git a/Marlin/src/HAL/DUE/usb/udc.c b/Marlin/src/HAL/DUE/usb/udc.c index 60bf0cfff35c..f6a4243d1d94 100644 --- a/Marlin/src/HAL/DUE/usb/udc.c +++ b/Marlin/src/HAL/DUE/usb/udc.c @@ -83,7 +83,6 @@ static usb_iface_desc_t UDC_DESC_STORAGE *udc_ptr_iface; //! @} - //! \name Internal structure to store the USB device main strings //! @{ diff --git a/Marlin/src/HAL/DUE/usb/udc.h b/Marlin/src/HAL/DUE/usb/udc.h index 8d92eb5c038a..aba08d956e84 100644 --- a/Marlin/src/HAL/DUE/usb/udc.h +++ b/Marlin/src/HAL/DUE/usb/udc.h @@ -144,15 +144,15 @@ extern "C" { * \code #define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode * User C file contains: * \code - // Authorize VBUS monitoring - if (!udc_include_vbus_monitoring()) { - // Implement custom VBUS monitoring via GPIO or other - } - Event_VBUS_present() // VBUS interrupt or GPIO interrupt or other - { - // Attach USB Device - udc_attach(); - } + // Authorize VBUS monitoring + if (!udc_include_vbus_monitoring()) { + // Implement custom VBUS monitoring via GPIO or other + } + Event_VBUS_present() // VBUS interrupt or GPIO interrupt or other + { + // Attach USB Device + udc_attach(); + } \endcode * * - Case of battery charging. conf_usb.h file contains define @@ -160,21 +160,20 @@ extern "C" { * \code #define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode * User C file contains: * \code - Event VBUS present() // VBUS interrupt or GPIO interrupt or .. - { - // Authorize battery charging, but wait key press to start USB. - } - Event Key press() - { - // Stop batteries charging - // Start USB - udc_attach(); - } + Event VBUS present() // VBUS interrupt or GPIO interrupt or .. + { + // Authorize battery charging, but wait key press to start USB. + } + Event Key press() + { + // Stop batteries charging + // Start USB + udc_attach(); + } \endcode */ -static inline bool udc_include_vbus_monitoring(void) -{ - return udd_include_vbus_monitoring(); +static inline bool udc_include_vbus_monitoring(void) { + return udd_include_vbus_monitoring(); } /*! \brief Start the USB Device stack @@ -192,32 +191,26 @@ void udc_stop(void); * then it will attach device when an acceptable Vbus * level from the host is detected. */ -static inline void udc_attach(void) -{ - udd_attach(); +static inline void udc_attach(void) { + udd_attach(); } - /** * \brief Detaches the device from the bus * * The driver must remove pull-up on USB line D- or D+. */ -static inline void udc_detach(void) -{ - udd_detach(); +static inline void udc_detach(void) { + udd_detach(); } - /*! \brief The USB driver sends a resume signal called \e "Upstream Resume" * This is authorized only when the remote wakeup feature is enabled by host. */ -static inline void udc_remotewakeup(void) -{ - udd_send_remotewakeup(); +static inline void udc_remotewakeup(void) { + udd_send_remotewakeup(); } - /** * \brief Returns a pointer on the current interface descriptor * @@ -296,23 +289,23 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * * for AVR and SAM3/4 devices, add to the initialization code: * \code - sysclk_init(); - irq_initialize_vectors(); - cpu_irq_enable(); - board_init(); - sleepmgr_init(); // Optional + sysclk_init(); + irq_initialize_vectors(); + cpu_irq_enable(); + board_init(); + sleepmgr_init(); // Optional \endcode * * For SAMD devices, add to the initialization code: * \code - system_init(); - irq_initialize_vectors(); - cpu_irq_enable(); - sleepmgr_init(); // Optional + system_init(); + irq_initialize_vectors(); + cpu_irq_enable(); + sleepmgr_init(); // Optional \endcode * Add to the main IDLE loop: * \code - sleepmgr_enter_sleep(); // Optional + sleepmgr_enter_sleep(); // Optional \endcode * */ @@ -324,20 +317,20 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * * Content of conf_usb.h: * \code - #define USB_DEVICE_VENDOR_ID 0x03EB - #define USB_DEVICE_PRODUCT_ID 0xXXXX - #define USB_DEVICE_MAJOR_VERSION 1 - #define USB_DEVICE_MINOR_VERSION 0 - #define USB_DEVICE_POWER 100 - #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED + #define USB_DEVICE_VENDOR_ID 0x03EB + #define USB_DEVICE_PRODUCT_ID 0xXXXX + #define USB_DEVICE_MAJOR_VERSION 1 + #define USB_DEVICE_MINOR_VERSION 0 + #define USB_DEVICE_POWER 100 + #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED \endcode * * Add to application C-file: * \code - void usb_init(void) - { - udc_start(); - } + void usb_init(void) + { + udc_start(); + } \endcode */ @@ -349,17 +342,17 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * -# Ensure that conf_usb.h is available and contains the following configuration * which is the main USB device configuration: * - \code // Vendor ID provided by USB org (ATMEL 0x03EB) - #define USB_DEVICE_VENDOR_ID 0x03EB // Type Word - // Product ID (Atmel PID referenced in usb_atmel.h) - #define USB_DEVICE_PRODUCT_ID 0xXXXX // Type Word - // Major version of the device - #define USB_DEVICE_MAJOR_VERSION 1 // Type Byte - // Minor version of the device - #define USB_DEVICE_MINOR_VERSION 0 // Type Byte - // Maximum device power (mA) - #define USB_DEVICE_POWER 100 // Type 9-bits - // USB attributes to enable features - #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED // Flags \endcode + #define USB_DEVICE_VENDOR_ID 0x03EB // Type Word + // Product ID (Atmel PID referenced in usb_atmel.h) + #define USB_DEVICE_PRODUCT_ID 0xXXXX // Type Word + // Major version of the device + #define USB_DEVICE_MAJOR_VERSION 1 // Type Byte + // Minor version of the device + #define USB_DEVICE_MINOR_VERSION 0 // Type Byte + // Maximum device power (mA) + #define USB_DEVICE_POWER 100 // Type 9-bits + // USB attributes to enable features + #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED // Flags \endcode * -# Call the USB device stack start function to enable stack and start USB: * - \code udc_start(); \endcode * \note In case of USB dual roles (Device and Host) managed through USB OTG connector @@ -372,90 +365,90 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * * Content of XMEGA conf_clock.h: * \code - // Configuration based on internal RC: - // USB clock need of 48Mhz - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_RCOSC - #define CONFIG_OSC_RC32_CAL 48000000UL - #define CONFIG_OSC_AUTOCAL_RC32MHZ_REF_OSC OSC_ID_USBSOF - // CPU clock need of clock > 12MHz to run with USB (Here 24MHz) - #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_RC32MHZ - #define CONFIG_SYSCLK_PSADIV SYSCLK_PSADIV_2 - #define CONFIG_SYSCLK_PSBCDIV SYSCLK_PSBCDIV_1_1 + // Configuration based on internal RC: + // USB clock need of 48Mhz + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_RCOSC + #define CONFIG_OSC_RC32_CAL 48000000UL + #define CONFIG_OSC_AUTOCAL_RC32MHZ_REF_OSC OSC_ID_USBSOF + // CPU clock need of clock > 12MHz to run with USB (Here 24MHz) + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_RC32MHZ + #define CONFIG_SYSCLK_PSADIV SYSCLK_PSADIV_2 + #define CONFIG_SYSCLK_PSBCDIV SYSCLK_PSBCDIV_1_1 \endcode * * Content of conf_clock.h for AT32UC3A0, AT32UC3A1, AT32UC3B devices (USBB): * \code - // Configuration based on 12MHz external OSC: - #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 - #define CONFIG_PLL1_MUL 8 - #define CONFIG_PLL1_DIV 2 - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 - #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) + // Configuration based on 12MHz external OSC: + #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 + #define CONFIG_PLL1_MUL 8 + #define CONFIG_PLL1_DIV 2 + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 + #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) \endcode * * Content of conf_clock.h for AT32UC3A3, AT32UC3A4 devices (USBB with high speed support): * \code - // Configuration based on 12MHz external OSC: - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_OSC0 - #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) + // Configuration based on 12MHz external OSC: + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_OSC0 + #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) \endcode * * Content of conf_clock.h for AT32UC3C, ATUCXXD, ATUCXXL3U, ATUCXXL4U devices (USBC): * \code - // Configuration based on 12MHz external OSC: - #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 - #define CONFIG_PLL1_MUL 8 - #define CONFIG_PLL1_DIV 2 - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 - #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) - // CPU clock need of clock > 25MHz to run with USBC - #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLL1 + // Configuration based on 12MHz external OSC: + #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 + #define CONFIG_PLL1_MUL 8 + #define CONFIG_PLL1_DIV 2 + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 + #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) + // CPU clock need of clock > 25MHz to run with USBC + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLL1 \endcode * * Content of conf_clock.h for SAM3S, SAM3SD, SAM4S devices (UPD: USB Peripheral Device): * \code - // PLL1 (B) Options (Fpll = (Fclk * PLL_mul) / PLL_div) - #define CONFIG_PLL1_SOURCE PLL_SRC_MAINCK_XTAL - #define CONFIG_PLL1_MUL 16 - #define CONFIG_PLL1_DIV 2 - // USB Clock Source Options (Fusb = FpllX / USB_div) - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 - #define CONFIG_USBCLK_DIV 2 + // PLL1 (B) Options (Fpll = (Fclk * PLL_mul) / PLL_div) + #define CONFIG_PLL1_SOURCE PLL_SRC_MAINCK_XTAL + #define CONFIG_PLL1_MUL 16 + #define CONFIG_PLL1_DIV 2 + // USB Clock Source Options (Fusb = FpllX / USB_div) + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 + #define CONFIG_USBCLK_DIV 2 \endcode * * Content of conf_clock.h for SAM3U device (UPDHS: USB Peripheral Device High Speed): * \code - // USB Clock Source fixed at UPLL. + // USB Clock Source fixed at UPLL. \endcode * * Content of conf_clock.h for SAM3X, SAM3A devices (UOTGHS: USB OTG High Speed): * \code - // USB Clock Source fixed at UPLL. - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_UPLL - #define CONFIG_USBCLK_DIV 1 + // USB Clock Source fixed at UPLL. + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_UPLL + #define CONFIG_USBCLK_DIV 1 \endcode * * Content of conf_clocks.h for SAMD devices (USB): * \code - // System clock bus configuration - # define CONF_CLOCK_FLASH_WAIT_STATES 2 - - // USB Clock Source fixed at DFLL. - // SYSTEM_CLOCK_SOURCE_DFLL configuration - Digital Frequency Locked Loop - # define CONF_CLOCK_DFLL_ENABLE true - # define CONF_CLOCK_DFLL_LOOP_MODE SYSTEM_CLOCK_DFLL_LOOP_MODE_USB_RECOVERY - # define CONF_CLOCK_DFLL_ON_DEMAND true - - // Set this to true to configure the GCLK when running clocks_init. - // If set to false, none of the GCLK generators will be configured in clocks_init(). - # define CONF_CLOCK_CONFIGURE_GCLK true - - // Configure GCLK generator 0 (Main Clock) - # define CONF_CLOCK_GCLK_0_ENABLE true - # define CONF_CLOCK_GCLK_0_RUN_IN_STANDBY true - # define CONF_CLOCK_GCLK_0_CLOCK_SOURCE SYSTEM_CLOCK_SOURCE_DFLL - # define CONF_CLOCK_GCLK_0_PRESCALER 1 - # define CONF_CLOCK_GCLK_0_OUTPUT_ENABLE false + // System clock bus configuration + # define CONF_CLOCK_FLASH_WAIT_STATES 2 + + // USB Clock Source fixed at DFLL. + // SYSTEM_CLOCK_SOURCE_DFLL configuration - Digital Frequency Locked Loop + # define CONF_CLOCK_DFLL_ENABLE true + # define CONF_CLOCK_DFLL_LOOP_MODE SYSTEM_CLOCK_DFLL_LOOP_MODE_USB_RECOVERY + # define CONF_CLOCK_DFLL_ON_DEMAND true + + // Set this to true to configure the GCLK when running clocks_init. + // If set to false, none of the GCLK generators will be configured in clocks_init(). + # define CONF_CLOCK_CONFIGURE_GCLK true + + // Configure GCLK generator 0 (Main Clock) + # define CONF_CLOCK_GCLK_0_ENABLE true + # define CONF_CLOCK_GCLK_0_RUN_IN_STANDBY true + # define CONF_CLOCK_GCLK_0_CLOCK_SOURCE SYSTEM_CLOCK_SOURCE_DFLL + # define CONF_CLOCK_GCLK_0_PRESCALER 1 + # define CONF_CLOCK_GCLK_0_OUTPUT_ENABLE false \endcode */ @@ -474,34 +467,34 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_1_usage_code Example code * Content of conf_usb.h: * \code - #if // Low speed - #define USB_DEVICE_LOW_SPEED - // #define USB_DEVICE_HS_SUPPORT + #if // Low speed + #define USB_DEVICE_LOW_SPEED + // #define USB_DEVICE_HS_SUPPORT - #elif // Full speed - // #define USB_DEVICE_LOW_SPEED - // #define USB_DEVICE_HS_SUPPORT + #elif // Full speed + // #define USB_DEVICE_LOW_SPEED + // #define USB_DEVICE_HS_SUPPORT - #elif // High speed - // #define USB_DEVICE_LOW_SPEED - #define USB_DEVICE_HS_SUPPORT + #elif // High speed + // #define USB_DEVICE_LOW_SPEED + #define USB_DEVICE_HS_SUPPORT - #endif + #endif \endcode * * \subsection udc_use_case_1_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required for a USB device low speed (1.5Mbit/s): * - \code #define USB_DEVICE_LOW_SPEED - //#define USB_DEVICE_HS_SUPPORT \endcode + //#define USB_DEVICE_HS_SUPPORT \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB device full speed (12Mbit/s): * - \code //#define USB_DEVICE_LOW_SPEED - //#define USB_DEVICE_HS_SUPPORT \endcode + //#define USB_DEVICE_HS_SUPPORT \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB device high speed (480Mbit/s): * - \code //#define USB_DEVICE_LOW_SPEED - #define USB_DEVICE_HS_SUPPORT \endcode + #define USB_DEVICE_HS_SUPPORT \endcode */ /** @@ -518,20 +511,20 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_2_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" - #define USB_DEVICE_PRODUCT_NAME "Product name" - #define USB_DEVICE_SERIAL_NAME "12...EF" + #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" + #define USB_DEVICE_PRODUCT_NAME "Product name" + #define USB_DEVICE_SERIAL_NAME "12...EF" \endcode * * \subsection udc_use_case_2_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required to enable different USB strings: * - \code // Static ASCII name for the manufacture - #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" \endcode + #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" \endcode * - \code // Static ASCII name for the product - #define USB_DEVICE_PRODUCT_NAME "Product name" \endcode + #define USB_DEVICE_PRODUCT_NAME "Product name" \endcode * - \code // Static ASCII name to enable and set a serial number - #define USB_DEVICE_SERIAL_NAME "12...EF" \endcode + #define USB_DEVICE_SERIAL_NAME "12...EF" \endcode */ /** @@ -548,42 +541,42 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_3_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_ATTR \ - (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) - #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() - extern void my_callback_remotewakeup_enable(void); - #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() - extern void my_callback_remotewakeup_disable(void); + #define USB_DEVICE_ATTR \ + (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) + #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() + extern void my_callback_remotewakeup_enable(void); + #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() + extern void my_callback_remotewakeup_disable(void); \endcode * * Add to application C-file: * \code - void my_callback_remotewakeup_enable(void) - { - // Enable application wakeup events (e.g. enable GPIO interrupt) - } - void my_callback_remotewakeup_disable(void) - { - // Disable application wakeup events (e.g. disable GPIO interrupt) - } - - void my_interrupt_event(void) - { - udc_remotewakeup(); - } + void my_callback_remotewakeup_enable(void) + { + // Enable application wakeup events (e.g. enable GPIO interrupt) + } + void my_callback_remotewakeup_disable(void) + { + // Disable application wakeup events (e.g. disable GPIO interrupt) + } + + void my_interrupt_event(void) + { + udc_remotewakeup(); + } \endcode * * \subsection udc_use_case_3_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required to enable remote wakeup feature: * - \code // Authorizes the remote wakeup feature - #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) \endcode + #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) \endcode * - \code // Define callback called when the host enables the remotewakeup feature - #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() - extern void my_callback_remotewakeup_enable(void); \endcode + #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() + extern void my_callback_remotewakeup_enable(void); \endcode * - \code // Define callback called when the host disables the remotewakeup feature - #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() - extern void my_callback_remotewakeup_disable(void); \endcode + #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() + extern void my_callback_remotewakeup_disable(void); \endcode * -# Send a remote wakeup (USB upstream): * - \code udc_remotewakeup(); \endcode */ @@ -603,40 +596,40 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_5_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) - #define UDC_SUSPEND_EVENT() user_callback_suspend_action() - extern void user_callback_suspend_action(void) - #define UDC_RESUME_EVENT() user_callback_resume_action() - extern void user_callback_resume_action(void) + #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) + #define UDC_SUSPEND_EVENT() user_callback_suspend_action() + extern void user_callback_suspend_action(void) + #define UDC_RESUME_EVENT() user_callback_resume_action() + extern void user_callback_resume_action(void) \endcode * * Add to application C-file: * \code - void user_callback_suspend_action(void) - { - // Disable hardware component to reduce power consumption - } - void user_callback_resume_action(void) - { - // Re-enable hardware component - } + void user_callback_suspend_action(void) + { + // Disable hardware component to reduce power consumption + } + void user_callback_resume_action(void) + { + // Re-enable hardware component + } \endcode * * \subsection udc_use_case_5_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters: * - \code // Authorizes the BUS power feature - #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) \endcode + #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) \endcode * - \code // Define callback called when the host suspend the USB line - #define UDC_SUSPEND_EVENT() user_callback_suspend_action() - extern void user_callback_suspend_action(void); \endcode + #define UDC_SUSPEND_EVENT() user_callback_suspend_action() + extern void user_callback_suspend_action(void); \endcode * - \code // Define callback called when the host or device resume the USB line - #define UDC_RESUME_EVENT() user_callback_resume_action() - extern void user_callback_resume_action(void); \endcode + #define UDC_RESUME_EVENT() user_callback_resume_action() + extern void user_callback_resume_action(void); \endcode * -# Reduce power consumption in suspend mode (max. 2.5mA on Vbus): * - \code void user_callback_suspend_action(void) - { - turn_off_components(); - } \endcode + { + turn_off_components(); + } \endcode */ /** @@ -654,44 +647,42 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_6_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_SERIAL_NAME - #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number - #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 - extern uint8_t serial_number[]; + #define USB_DEVICE_SERIAL_NAME + #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number + #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 + extern uint8_t serial_number[]; \endcode * * Add to application C-file: * \code - uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; + uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; - void init_build_usb_serial_number(void) - { - serial_number[0] = 'A'; - serial_number[1] = 'B'; - ... - serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; - } \endcode + void init_build_usb_serial_number(void) + { + serial_number[0] = 'A'; + serial_number[1] = 'B'; + ... + serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; + } \endcode * * \subsection udc_use_case_6_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required to enable a USB serial number strings dynamically: * - \code #define USB_DEVICE_SERIAL_NAME // Define this empty - #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number // Give serial array pointer - #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 // Give size of serial array - extern uint8_t serial_number[]; // Declare external serial array \endcode + #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number // Give serial array pointer + #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 // Give size of serial array + extern uint8_t serial_number[]; // Declare external serial array \endcode * -# Before start USB stack, initialize the serial array * - \code - uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; - - void init_build_usb_serial_number(void) - { - serial_number[0] = 'A'; - serial_number[1] = 'B'; - ... - serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; - } \endcode + uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; + + void init_build_usb_serial_number(void) + { + serial_number[0] = 'A'; + serial_number[1] = 'B'; + ... + serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; + } \endcode */ - - #endif // _UDC_H_ diff --git a/Marlin/src/HAL/DUE/usb/udc_desc.h b/Marlin/src/HAL/DUE/usb/udc_desc.h index 052ca08eca78..f1f328d035c3 100644 --- a/Marlin/src/HAL/DUE/usb/udc_desc.h +++ b/Marlin/src/HAL/DUE/usb/udc_desc.h @@ -78,50 +78,47 @@ extern "C" { * For Mega application used "code". */ #define UDC_DESC_STORAGE - // Descriptor storage in internal RAM + // Descriptor storage in internal RAM #if (defined UDC_DATA_USE_HRAM_SUPPORT) -# if defined(__GNUC__) -# define UDC_DATA(x) COMPILER_WORD_ALIGNED __attribute__((__section__(".data_hram0"))) -# define UDC_BSS(x) COMPILER_ALIGNED(x) __attribute__((__section__(".bss_hram0"))) -# elif defined(__ICCAVR32__) -# define UDC_DATA(x) COMPILER_ALIGNED(x) __data32 -# define UDC_BSS(x) COMPILER_ALIGNED(x) __data32 -# endif + #if defined(__GNUC__) + #define UDC_DATA(x) COMPILER_WORD_ALIGNED __attribute__((__section__(".data_hram0"))) + #define UDC_BSS(x) COMPILER_ALIGNED(x) __attribute__((__section__(".bss_hram0"))) +#elif defined(__ICCAVR32__) + #define UDC_DATA(x) COMPILER_ALIGNED(x) __data32 + #define UDC_BSS(x) COMPILER_ALIGNED(x) __data32 +#endif #else -# define UDC_DATA(x) COMPILER_ALIGNED(x) -# define UDC_BSS(x) COMPILER_ALIGNED(x) + #define UDC_DATA(x) COMPILER_ALIGNED(x) + #define UDC_BSS(x) COMPILER_ALIGNED(x) #endif - - /** * \brief Configuration descriptor and UDI link for one USB speed */ typedef struct { - //! USB configuration descriptor - usb_conf_desc_t UDC_DESC_STORAGE *desc; - //! Array of UDI API pointer - udi_api_t UDC_DESC_STORAGE *UDC_DESC_STORAGE * udi_apis; + //! USB configuration descriptor + usb_conf_desc_t UDC_DESC_STORAGE *desc; + //! Array of UDI API pointer + udi_api_t UDC_DESC_STORAGE *UDC_DESC_STORAGE * udi_apis; } udc_config_speed_t; - /** * \brief All information about the USB Device */ typedef struct { - //! USB device descriptor for low or full speed - usb_dev_desc_t UDC_DESC_STORAGE *confdev_lsfs; - //! USB configuration descriptor and UDI API pointers for low or full speed - udc_config_speed_t UDC_DESC_STORAGE *conf_lsfs; -#ifdef USB_DEVICE_HS_SUPPORT - //! USB device descriptor for high speed - usb_dev_desc_t UDC_DESC_STORAGE *confdev_hs; - //! USB device qualifier, only use in high speed mode - usb_dev_qual_desc_t UDC_DESC_STORAGE *qualifier; - //! USB configuration descriptor and UDI API pointers for high speed - udc_config_speed_t UDC_DESC_STORAGE *conf_hs; -#endif - usb_dev_bos_desc_t UDC_DESC_STORAGE *conf_bos; + //! USB device descriptor for low or full speed + usb_dev_desc_t UDC_DESC_STORAGE *confdev_lsfs; + //! USB configuration descriptor and UDI API pointers for low or full speed + udc_config_speed_t UDC_DESC_STORAGE *conf_lsfs; + #ifdef USB_DEVICE_HS_SUPPORT + //! USB device descriptor for high speed + usb_dev_desc_t UDC_DESC_STORAGE *confdev_hs; + //! USB device qualifier, only use in high speed mode + usb_dev_qual_desc_t UDC_DESC_STORAGE *qualifier; + //! USB configuration descriptor and UDI API pointers for high speed + udc_config_speed_t UDC_DESC_STORAGE *conf_hs; + #endif + usb_dev_bos_desc_t UDC_DESC_STORAGE *conf_bos; } udc_config_t; //! Global variables of USB Device Descriptor and UDI links diff --git a/Marlin/src/HAL/DUE/usb/udd.h b/Marlin/src/HAL/DUE/usb/udd.h index 319d8842f744..4e482784e163 100644 --- a/Marlin/src/HAL/DUE/usb/udd.h +++ b/Marlin/src/HAL/DUE/usb/udd.h @@ -71,8 +71,8 @@ typedef uint8_t udd_ep_id_t; //! \brief Endpoint transfer status //! Returned in parameters of callback register via udd_ep_run routine. typedef enum { - UDD_EP_TRANSFER_OK = 0, - UDD_EP_TRANSFER_ABORT = 1, + UDD_EP_TRANSFER_OK = 0, + UDD_EP_TRANSFER_ABORT = 1, } udd_ep_status_t; /** @@ -82,41 +82,37 @@ typedef enum { * It can be updated by udc_process_setup() from UDC or *setup() from UDIs. */ typedef struct { - //! Data received in USB SETUP packet - //! Note: The swap of "req.wValues" from uin16_t to le16_t is done by UDD. - usb_setup_req_t req; + //! Data received in USB SETUP packet + //! Note: The swap of "req.wValues" from uin16_t to le16_t is done by UDD. + usb_setup_req_t req; - //! Point to buffer to send or fill with data following SETUP packet - //! This buffer must be word align for DATA IN phase (use prefix COMPILER_WORD_ALIGNED for buffer) - uint8_t *payload; + //! Point to buffer to send or fill with data following SETUP packet + //! This buffer must be word align for DATA IN phase (use prefix COMPILER_WORD_ALIGNED for buffer) + uint8_t *payload; - //! Size of buffer to send or fill, and content the number of byte transferred - uint16_t payload_size; + //! Size of buffer to send or fill, and content the number of byte transferred + uint16_t payload_size; - //! Callback called after reception of ZLP from setup request - void (*callback)(void); + //! Callback called after reception of ZLP from setup request + void (*callback)(void); - //! Callback called when the buffer given (.payload) is full or empty. - //! This one return false to abort data transfer, or true with a new buffer in .payload. - bool (*over_under_run)(void); + //! Callback called when the buffer given (.payload) is full or empty. + //! This one return false to abort data transfer, or true with a new buffer in .payload. + bool (*over_under_run)(void); } udd_ctrl_request_t; extern udd_ctrl_request_t udd_g_ctrlreq; //! Return true if the setup request \a udd_g_ctrlreq indicates IN data transfer -#define Udd_setup_is_in() \ - (USB_REQ_DIR_IN == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) +#define Udd_setup_is_in() (USB_REQ_DIR_IN == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) //! Return true if the setup request \a udd_g_ctrlreq indicates OUT data transfer -#define Udd_setup_is_out() \ - (USB_REQ_DIR_OUT == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) +#define Udd_setup_is_out() (USB_REQ_DIR_OUT == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) //! Return the type of the SETUP request \a udd_g_ctrlreq. \see usb_reqtype. -#define Udd_setup_type() \ - (udd_g_ctrlreq.req.bmRequestType & USB_REQ_TYPE_MASK) +#define Udd_setup_type() (udd_g_ctrlreq.req.bmRequestType & USB_REQ_TYPE_MASK) //! Return the recipient of the SETUP request \a udd_g_ctrlreq. \see usb_recipient -#define Udd_setup_recipient() \ - (udd_g_ctrlreq.req.bmRequestType & USB_REQ_RECIP_MASK) +#define Udd_setup_recipient() (udd_g_ctrlreq.req.bmRequestType & USB_REQ_RECIP_MASK) /** * \brief End of halt callback function type. @@ -134,8 +130,7 @@ typedef void (*udd_callback_halt_cleared_t)(void); * \param status UDD_EP_TRANSFER_ABORT, if transfer is aborted * \param n number of data transferred */ -typedef void (*udd_callback_trans_t) (udd_ep_status_t status, - iram_size_t nb_transferred, udd_ep_id_t ep); +typedef void (*udd_callback_trans_t) (udd_ep_status_t status, iram_size_t nb_transferred, udd_ep_id_t ep); /** * \brief Authorizes the VBUS event @@ -218,7 +213,6 @@ void udd_send_remotewakeup(void); */ void udd_set_setup_payload( uint8_t *payload, uint16_t payload_size ); - /** * \name Endpoint Management * @@ -239,8 +233,7 @@ void udd_set_setup_payload( uint8_t *payload, uint16_t payload_size ); * * \return \c 1 if the endpoint is enabled, otherwise \c 0. */ -bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, - uint16_t MaxEndpointSize); +bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, uint16_t MaxEndpointSize); /** * \brief Disables an endpoint @@ -294,8 +287,7 @@ bool udd_ep_clear_halt(udd_ep_id_t ep); * * \return \c 1 if the register is accepted, otherwise \c 0. */ -bool udd_ep_wait_stall_clear(udd_ep_id_t ep, - udd_callback_halt_cleared_t callback); +bool udd_ep_wait_stall_clear(udd_ep_id_t ep, udd_callback_halt_cleared_t callback); /** * \brief Allows to receive or send data on an endpoint @@ -321,9 +313,8 @@ bool udd_ep_wait_stall_clear(udd_ep_id_t ep, * * \return \c 1 if function was successfully done, otherwise \c 0. */ -bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, - uint8_t * buf, iram_size_t buf_size, - udd_callback_trans_t callback); +bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, uint8_t * buf, iram_size_t buf_size, udd_callback_trans_t callback); + /** * \brief Aborts transfer on going on endpoint * @@ -339,7 +330,6 @@ void udd_ep_abort(udd_ep_id_t ep); //@} - /** * \name High speed test mode management * @@ -352,7 +342,6 @@ void udd_test_mode_se0_nak(void); void udd_test_mode_packet(void); //@} - /** * \name UDC callbacks to provide for UDD * diff --git a/Marlin/src/HAL/DUE/usb/udi.h b/Marlin/src/HAL/DUE/usb/udi.h index febf03b7181e..bc5de086f3ce 100644 --- a/Marlin/src/HAL/DUE/usb/udi.h +++ b/Marlin/src/HAL/DUE/usb/udi.h @@ -72,57 +72,57 @@ extern "C" { * selected by UDC. */ typedef struct { - /** - * \brief Enable the interface. - * - * This function is called when the host selects a configuration - * to which this interface belongs through a Set Configuration - * request, and when the host selects an alternate setting of - * this interface through a Set Interface request. - * - * \return \c 1 if function was successfully done, otherwise \c 0. - */ - bool (*enable)(void); + /** + * \brief Enable the interface. + * + * This function is called when the host selects a configuration + * to which this interface belongs through a Set Configuration + * request, and when the host selects an alternate setting of + * this interface through a Set Interface request. + * + * \return \c 1 if function was successfully done, otherwise \c 0. + */ + bool (*enable)(void); - /** - * \brief Disable the interface. - * - * This function is called when this interface is currently - * active, and - * - the host selects any configuration through a Set - * Configuration request, or - * - the host issues a USB reset, or - * - the device is detached from the host (i.e. Vbus is no - * longer present) - */ - void (*disable)(void); + /** + * \brief Disable the interface. + * + * This function is called when this interface is currently + * active, and + * - the host selects any configuration through a Set + * Configuration request, or + * - the host issues a USB reset, or + * - the device is detached from the host (i.e. Vbus is no + * longer present) + */ + void (*disable)(void); - /** - * \brief Handle a control request directed at an interface. - * - * This function is called when this interface is currently - * active and the host sends a SETUP request - * with this interface as the recipient. - * - * Use udd_g_ctrlreq to decode and response to SETUP request. - * - * \return \c 1 if this interface supports the SETUP request, otherwise \c 0. - */ - bool (*setup)(void); + /** + * \brief Handle a control request directed at an interface. + * + * This function is called when this interface is currently + * active and the host sends a SETUP request + * with this interface as the recipient. + * + * Use udd_g_ctrlreq to decode and response to SETUP request. + * + * \return \c 1 if this interface supports the SETUP request, otherwise \c 0. + */ + bool (*setup)(void); - /** - * \brief Returns the current setting of the selected interface. - * - * This function is called when UDC when know alternate setting of selected interface. - * - * \return alternate setting of selected interface - */ - uint8_t (*getsetting)(void); + /** + * \brief Returns the current setting of the selected interface. + * + * This function is called when UDC when know alternate setting of selected interface. + * + * \return alternate setting of selected interface + */ + uint8_t (*getsetting)(void); - /** - * \brief To signal that a SOF is occurred - */ - void (*sof_notify)(void); + /** + * \brief To signal that a SOF is occurred + */ + void (*sof_notify)(void); } udi_api_t; //@} diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc.c b/Marlin/src/HAL/DUE/usb/udi_cdc.c index 89debe57f130..26788570c619 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc.c +++ b/Marlin/src/HAL/DUE/usb/udi_cdc.c @@ -457,7 +457,6 @@ void udi_cdc_data_sof_notify(void) #endif } - // ------------------------ //------- Internal routines to control serial line @@ -520,7 +519,6 @@ static void udi_cdc_ctrl_state_change(uint8_t port, bool b_set, le16_t bit_mask) udi_cdc_ctrl_state_notify(port, ep_comm); } - static void udi_cdc_ctrl_state_notify(uint8_t port, udd_ep_id_t ep) { #if UDI_CDC_PORT_NB == 1 // To optimize code @@ -542,7 +540,6 @@ static void udi_cdc_ctrl_state_notify(uint8_t port, udd_ep_id_t ep) } } - static void udi_cdc_serial_state_msg_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep) { uint8_t port; @@ -578,11 +575,9 @@ static void udi_cdc_serial_state_msg_sent(udd_ep_status_t status, iram_size_t n, udi_cdc_ctrl_state_notify(port, ep); } - // ------------------------ //------- Internal routines to process data transfer - static bool udi_cdc_rx_start(uint8_t port) { irqflags_t flags; @@ -632,7 +627,6 @@ static bool udi_cdc_rx_start(uint8_t port) udi_cdc_data_received); } - static void udi_cdc_data_received(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep) { uint8_t buf_sel_trans; @@ -668,7 +662,6 @@ static void udi_cdc_data_received(udd_ep_status_t status, iram_size_t n, udd_ep_ udi_cdc_rx_start(port); } - static void udi_cdc_data_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep) { uint8_t port; @@ -700,7 +693,6 @@ static void udi_cdc_data_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t udi_cdc_tx_send(port); } - static void udi_cdc_tx_send(uint8_t port) { irqflags_t flags; @@ -780,11 +772,9 @@ static void udi_cdc_tx_send(uint8_t port) udi_cdc_data_sent); } - // ------------------------ //------- Application interface - //------- Application interface void udi_cdc_ctrl_signal_dcd(bool b_set) diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc.h b/Marlin/src/HAL/DUE/usb/udi_cdc.h index b61845011aa2..e9c6abbbb2f2 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc.h +++ b/Marlin/src/HAL/DUE/usb/udi_cdc.h @@ -92,21 +92,20 @@ extern UDC_DESC_STORAGE udi_api_t udi_api_cdc_data; * descriptors for the CDC Communication Class interface. */ typedef struct { - //! Standard interface descriptor - usb_iface_desc_t iface; - //! CDC Header functional descriptor - usb_cdc_hdr_desc_t header; - //! CDC Abstract Control Model functional descriptor - usb_cdc_acm_desc_t acm; - //! CDC Union functional descriptor - usb_cdc_union_desc_t union_desc; - //! CDC Call Management functional descriptor - usb_cdc_call_mgmt_desc_t call_mgmt; - //! Notification endpoint descriptor - usb_ep_desc_t ep_notify; + //! Standard interface descriptor + usb_iface_desc_t iface; + //! CDC Header functional descriptor + usb_cdc_hdr_desc_t header; + //! CDC Abstract Control Model functional descriptor + usb_cdc_acm_desc_t acm; + //! CDC Union functional descriptor + usb_cdc_union_desc_t union_desc; + //! CDC Call Management functional descriptor + usb_cdc_call_mgmt_desc_t call_mgmt; + //! Notification endpoint descriptor + usb_ep_desc_t ep_notify; } udi_cdc_comm_desc_t; - /** * \brief Data Class interface descriptor * @@ -114,14 +113,13 @@ typedef struct { * CDC Data Class interface. */ typedef struct { - //! Standard interface descriptor - usb_iface_desc_t iface; - //! Data IN/OUT endpoint descriptors - usb_ep_desc_t ep_in; - usb_ep_desc_t ep_out; + //! Standard interface descriptor + usb_iface_desc_t iface; + //! Data IN/OUT endpoint descriptors + usb_ep_desc_t ep_in; + usb_ep_desc_t ep_out; } udi_cdc_data_desc_t; - //! CDC communication endpoints size for all speeds #define UDI_CDC_COMM_EP_SIZE 64 //! CDC data endpoints size for FS speed (8B, 16B, 32B, 64B) @@ -136,13 +134,13 @@ typedef struct { //@{ //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_0 -#define UDI_CDC_IAD_STRING_ID_0 0 + #define UDI_CDC_IAD_STRING_ID_0 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_0 -#define UDI_CDC_COMM_STRING_ID_0 0 + #define UDI_CDC_COMM_STRING_ID_0 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_0 -#define UDI_CDC_DATA_STRING_ID_0 0 + #define UDI_CDC_DATA_STRING_ID_0 0 #endif #define UDI_CDC_IAD_DESC_0 UDI_CDC_IAD_DESC(0) #define UDI_CDC_COMM_DESC_0 UDI_CDC_COMM_DESC(0) @@ -151,13 +149,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_1 -#define UDI_CDC_IAD_STRING_ID_1 0 + #define UDI_CDC_IAD_STRING_ID_1 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_1 -#define UDI_CDC_COMM_STRING_ID_1 0 + #define UDI_CDC_COMM_STRING_ID_1 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_1 -#define UDI_CDC_DATA_STRING_ID_1 0 + #define UDI_CDC_DATA_STRING_ID_1 0 #endif #define UDI_CDC_IAD_DESC_1 UDI_CDC_IAD_DESC(1) #define UDI_CDC_COMM_DESC_1 UDI_CDC_COMM_DESC(1) @@ -166,13 +164,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_2 -#define UDI_CDC_IAD_STRING_ID_2 0 + #define UDI_CDC_IAD_STRING_ID_2 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_2 -#define UDI_CDC_COMM_STRING_ID_2 0 + #define UDI_CDC_COMM_STRING_ID_2 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_2 -#define UDI_CDC_DATA_STRING_ID_2 0 + #define UDI_CDC_DATA_STRING_ID_2 0 #endif #define UDI_CDC_IAD_DESC_2 UDI_CDC_IAD_DESC(2) #define UDI_CDC_COMM_DESC_2 UDI_CDC_COMM_DESC(2) @@ -181,13 +179,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_3 -#define UDI_CDC_IAD_STRING_ID_3 0 + #define UDI_CDC_IAD_STRING_ID_3 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_3 -#define UDI_CDC_COMM_STRING_ID_3 0 + #define UDI_CDC_COMM_STRING_ID_3 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_3 -#define UDI_CDC_DATA_STRING_ID_3 0 + #define UDI_CDC_DATA_STRING_ID_3 0 #endif #define UDI_CDC_IAD_DESC_3 UDI_CDC_IAD_DESC(3) #define UDI_CDC_COMM_DESC_3 UDI_CDC_COMM_DESC(3) @@ -196,13 +194,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_4 -#define UDI_CDC_IAD_STRING_ID_4 0 + #define UDI_CDC_IAD_STRING_ID_4 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_4 -#define UDI_CDC_COMM_STRING_ID_4 0 + #define UDI_CDC_COMM_STRING_ID_4 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_4 -#define UDI_CDC_DATA_STRING_ID_4 0 + #define UDI_CDC_DATA_STRING_ID_4 0 #endif #define UDI_CDC_IAD_DESC_4 UDI_CDC_IAD_DESC(4) #define UDI_CDC_COMM_DESC_4 UDI_CDC_COMM_DESC(4) @@ -211,13 +209,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_5 -#define UDI_CDC_IAD_STRING_ID_5 0 + #define UDI_CDC_IAD_STRING_ID_5 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_5 -#define UDI_CDC_COMM_STRING_ID_5 0 + #define UDI_CDC_COMM_STRING_ID_5 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_5 -#define UDI_CDC_DATA_STRING_ID_5 0 + #define UDI_CDC_DATA_STRING_ID_5 0 #endif #define UDI_CDC_IAD_DESC_5 UDI_CDC_IAD_DESC(5) #define UDI_CDC_COMM_DESC_5 UDI_CDC_COMM_DESC(5) @@ -226,13 +224,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_6 -#define UDI_CDC_IAD_STRING_ID_6 0 + #define UDI_CDC_IAD_STRING_ID_6 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_6 -#define UDI_CDC_COMM_STRING_ID_6 0 + #define UDI_CDC_COMM_STRING_ID_6 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_6 -#define UDI_CDC_DATA_STRING_ID_6 0 + #define UDI_CDC_DATA_STRING_ID_6 0 #endif #define UDI_CDC_IAD_DESC_6 UDI_CDC_IAD_DESC(6) #define UDI_CDC_COMM_DESC_6 UDI_CDC_COMM_DESC(6) @@ -240,7 +238,6 @@ typedef struct { #define UDI_CDC_DATA_DESC_6_HS UDI_CDC_DATA_DESC_HS(6) //@} - //! Content of CDC IAD interface descriptor for all speeds #define UDI_CDC_IAD_DESC(port) { \ .bLength = sizeof(usb_iad_desc_t),\ @@ -270,7 +267,7 @@ typedef struct { .call_mgmt.bDescriptorType = CDC_CS_INTERFACE,\ .call_mgmt.bDescriptorSubtype = CDC_SCS_CALL_MGMT,\ .call_mgmt.bmCapabilities = \ - CDC_CALL_MGMT_SUPPORTED | CDC_CALL_MGMT_OVER_DCI,\ + CDC_CALL_MGMT_SUPPORTED | CDC_CALL_MGMT_OVER_DCI,\ .acm.bFunctionLength = sizeof(usb_cdc_acm_desc_t),\ .acm.bDescriptorType = CDC_CS_INTERFACE,\ .acm.bDescriptorSubtype = CDC_SCS_ACM,\ @@ -610,40 +607,37 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * \subsection udi_cdc_basic_use_case_usage_code Example code * Content of conf_usb.h: * \code - #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() - extern bool my_callback_cdc_enable(void); - #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() - extern void my_callback_cdc_disable(void); - #define UDI_CDC_LOW_RATE - - #define UDI_CDC_DEFAULT_RATE 115200 - #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 - #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE - #define UDI_CDC_DEFAULT_DATABITS 8 - - #include "udi_cdc_conf.h" // At the end of conf_usb.h file + #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() + extern bool my_callback_cdc_enable(void); + #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() + extern void my_callback_cdc_disable(void); + #define UDI_CDC_LOW_RATE + + #define UDI_CDC_DEFAULT_RATE 115200 + #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 + #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE + #define UDI_CDC_DEFAULT_DATABITS 8 + + #include "udi_cdc_conf.h" // At the end of conf_usb.h file \endcode * * Add to application C-file: * \code - static bool my_flag_autorize_cdc_transfert = false; - bool my_callback_cdc_enable(void) - { - my_flag_autorize_cdc_transfert = true; - return true; - } - void my_callback_cdc_disable(void) - { - my_flag_autorize_cdc_transfert = false; - } - - void task(void) - { - if (my_flag_autorize_cdc_transfert) { - udi_cdc_putc('A'); - udi_cdc_getc(); - } - } + static bool my_flag_autorize_cdc_transfert = false; + bool my_callback_cdc_enable(void) { + my_flag_autorize_cdc_transfert = true; + return true; + } + void my_callback_cdc_disable(void) { + my_flag_autorize_cdc_transfert = false; + } + + void task(void) { + if (my_flag_autorize_cdc_transfert) { + udi_cdc_putc('A'); + udi_cdc_getc(); + } + } \endcode * * \subsection udi_cdc_basic_use_case_setup_flow Workflow @@ -652,14 +646,14 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * - \code #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for CDC \endcode * \note The USB serial number is mandatory when a CDC interface is used. * - \code #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() - extern bool my_callback_cdc_enable(void); \endcode + extern bool my_callback_cdc_enable(void); \endcode * \note After the device enumeration (detecting and identifying USB devices), * the USB host starts the device configuration. When the USB CDC interface * from the device is accepted by the host, the USB host enables this interface and the * UDI_CDC_ENABLE_EXT() callback function is called and return true. * Thus, when this event is received, the data transfer on CDC interface are authorized. * - \code #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() - extern void my_callback_cdc_disable(void); \endcode + extern void my_callback_cdc_disable(void); \endcode * \note When the USB device is unplugged or is reset by the USB host, the USB * interface is disabled and the UDI_CDC_DISABLE_EXT() callback function * is called. Thus, the data transfer must be stopped on CDC interface. @@ -667,19 +661,19 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * \note Define it when the transfer CDC Device to Host is a low rate * (<512000 bauds) to reduce CDC buffers size. * - \code #define UDI_CDC_DEFAULT_RATE 115200 - #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 - #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE - #define UDI_CDC_DEFAULT_DATABITS 8 \endcode + #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 + #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE + #define UDI_CDC_DEFAULT_DATABITS 8 \endcode * \note Default configuration of communication port at startup. * -# Send or wait data on CDC line: * - \code // Waits and gets a value on CDC line - int udi_cdc_getc(void); - // Reads a RAM buffer on CDC line - iram_size_t udi_cdc_read_buf(int *buf, iram_size_t size); - // Puts a byte on CDC line - int udi_cdc_putc(int value); - // Writes a RAM buffer on CDC line - iram_size_t udi_cdc_write_buf(const int *buf, iram_size_t size); \endcode + int udi_cdc_getc(void); + // Reads a RAM buffer on CDC line + iram_size_t udi_cdc_read_buf(int *buf, iram_size_t size); + // Puts a byte on CDC line + int udi_cdc_putc(int value); + // Writes a RAM buffer on CDC line + iram_size_t udi_cdc_write_buf(const int *buf, iram_size_t size); \endcode * * \section udi_cdc_use_cases Advanced use cases * For more advanced use of the UDI CDC module, see the following use cases: @@ -713,90 +707,90 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * \subsection udi_cdc_use_case_composite_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_EP_CTRL_SIZE 64 - #define USB_DEVICE_NB_INTERFACE (X+2) - #define USB_DEVICE_MAX_EP (X+3) - - #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX - #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX - #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint - #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 - #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 - - #define UDI_COMPOSITE_DESC_T \ - usb_iad_desc_t udi_cdc_iad; \ - udi_cdc_comm_desc_t udi_cdc_comm; \ - udi_cdc_data_desc_t udi_cdc_data; \ - ... - #define UDI_COMPOSITE_DESC_FS \ - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ - ... - #define UDI_COMPOSITE_DESC_HS \ - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ - ... - #define UDI_COMPOSITE_API \ - &udi_api_cdc_comm, \ - &udi_api_cdc_data, \ - ... + #define USB_DEVICE_EP_CTRL_SIZE 64 + #define USB_DEVICE_NB_INTERFACE (X+2) + #define USB_DEVICE_MAX_EP (X+3) + + #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX + #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX + #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint + #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 + #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 + + #define UDI_COMPOSITE_DESC_T \ + usb_iad_desc_t udi_cdc_iad; \ + udi_cdc_comm_desc_t udi_cdc_comm; \ + udi_cdc_data_desc_t udi_cdc_data; \ + ... + #define UDI_COMPOSITE_DESC_FS \ + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ + ... + #define UDI_COMPOSITE_DESC_HS \ + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ + ... + #define UDI_COMPOSITE_API \ + &udi_api_cdc_comm, \ + &udi_api_cdc_data, \ + ... \endcode * * \subsection udi_cdc_use_case_composite_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required for a USB composite device configuration: * - \code // Endpoint control size, This must be: - // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) - // - 64 for a high speed device - #define USB_DEVICE_EP_CTRL_SIZE 64 - // Total Number of interfaces on this USB device. - // Add 2 for CDC. - #define USB_DEVICE_NB_INTERFACE (X+2) - // Total number of endpoints on this USB device. - // This must include each endpoint for each interface. - // Add 3 for CDC. - #define USB_DEVICE_MAX_EP (X+3) \endcode + // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) + // - 64 for a high speed device + #define USB_DEVICE_EP_CTRL_SIZE 64 + // Total Number of interfaces on this USB device. + // Add 2 for CDC. + #define USB_DEVICE_NB_INTERFACE (X+2) + // Total number of endpoints on this USB device. + // This must include each endpoint for each interface. + // Add 3 for CDC. + #define USB_DEVICE_MAX_EP (X+3) \endcode * -# Ensure that conf_usb.h contains the description of * composite device: * - \code // The endpoint numbers chosen by you for the CDC. - // The endpoint numbers starting from 1. - #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX - #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX - #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint - // The interface index of an interface starting from 0 - #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 - #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 \endcode + // The endpoint numbers starting from 1. + #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX + #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX + #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint + // The interface index of an interface starting from 0 + #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 + #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB composite device configuration: * - \code // USB Interfaces descriptor structure - #define UDI_COMPOSITE_DESC_T \ - ... - usb_iad_desc_t udi_cdc_iad; \ - udi_cdc_comm_desc_t udi_cdc_comm; \ - udi_cdc_data_desc_t udi_cdc_data; \ - ... - // USB Interfaces descriptor value for Full Speed - #define UDI_COMPOSITE_DESC_FS \ - ... - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ - ... - // USB Interfaces descriptor value for High Speed - #define UDI_COMPOSITE_DESC_HS \ - ... - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ - ... - // USB Interface APIs - #define UDI_COMPOSITE_API \ - ... - &udi_api_cdc_comm, \ - &udi_api_cdc_data, \ - ... \endcode + #define UDI_COMPOSITE_DESC_T \ + ... + usb_iad_desc_t udi_cdc_iad; \ + udi_cdc_comm_desc_t udi_cdc_comm; \ + udi_cdc_data_desc_t udi_cdc_data; \ + ... + // USB Interfaces descriptor value for Full Speed + #define UDI_COMPOSITE_DESC_FS \ + ... + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ + ... + // USB Interfaces descriptor value for High Speed + #define UDI_COMPOSITE_DESC_HS \ + ... + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ + ... + // USB Interface APIs + #define UDI_COMPOSITE_API \ + ... + &udi_api_cdc_comm, \ + &udi_api_cdc_data, \ + ... \endcode * - \note The descriptors order given in the four lists above must be the * same as the order defined by all interface indexes. The interface index * orders are defined through UDI_X_IFACE_NUMBER defines.\n diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c b/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c index 97c334e2a854..bcae362cef8f 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c +++ b/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c @@ -51,7 +51,7 @@ #include "udc_desc.h" #include "udi_cdc.h" -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA /** * \defgroup udi_cdc_group_single_desc USB device descriptors for a single interface @@ -109,7 +109,6 @@ UDC_DESC_STORAGE usb_dev_desc_t udc_device_desc = { .bNumConfigurations = 1 }; - #ifdef USB_DEVICE_HS_SUPPORT //! USB Device Qualifier Descriptor for HS COMPILER_WORD_ALIGNED @@ -256,6 +255,6 @@ UDC_DESC_STORAGE udc_config_t udc_config = { //@} //@} -#endif // SDSUPPORT +#endif // HAS_MEDIA #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/usb/udi_composite_desc.c b/Marlin/src/HAL/DUE/usb/udi_composite_desc.c index da74fbe60dfe..8fa5acbb3f72 100644 --- a/Marlin/src/HAL/DUE/usb/udi_composite_desc.c +++ b/Marlin/src/HAL/DUE/usb/udi_composite_desc.c @@ -50,7 +50,7 @@ #include "udd.h" #include "udc_desc.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA /** * \defgroup udi_group_desc Descriptors for a USB Device @@ -93,7 +93,6 @@ UDC_DESC_STORAGE usb_dev_desc_t udc_device_desc = { .bNumConfigurations = 1 }; - #ifdef USB_DEVICE_HS_SUPPORT //! USB Device Qualifier Descriptor for HS COMPILER_WORD_ALIGNED @@ -147,7 +146,6 @@ UDC_DESC_STORAGE udc_desc_t udc_desc_hs = { }; #endif - /** * \name UDC structures which contains all USB Device definitions */ @@ -189,4 +187,4 @@ UDC_DESC_STORAGE udc_config_t udc_config = { #endif // ARDUINO_ARCH_SAM -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/HAL/DUE/usb/udi_msc.c b/Marlin/src/HAL/DUE/usb/udi_msc.c index dd3404877210..56664f4bf7c6 100644 --- a/Marlin/src/HAL/DUE/usb/udi_msc.c +++ b/Marlin/src/HAL/DUE/usb/udi_msc.c @@ -57,7 +57,7 @@ #include "ctrl_access.h" #include -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #ifndef UDI_MSC_NOTIFY_TRANS_EXT # define UDI_MSC_NOTIFY_TRANS_EXT() @@ -86,7 +86,6 @@ UDC_DESC_STORAGE udi_api_t udi_api_msc = { }; //@} - /** * \ingroup udi_msc_group * \defgroup udi_msc_group_internal Implementation of UDI MSC @@ -137,7 +136,6 @@ volatile bool udi_msc_b_reset_trans = true; //@} - /** * \name Internal routines */ @@ -190,7 +188,6 @@ static void udi_msc_cbw_received(udd_ep_status_t status, static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag); //@} - /** * \name Routines to process small data packet */ @@ -217,7 +214,6 @@ static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, udd_ep_id_t ep); //@} - /** * \name Routines to process CSW packet */ @@ -250,7 +246,6 @@ static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, udd_ep_id_t ep); //@} - /** * \name Routines manage sense data */ @@ -307,7 +302,6 @@ static void udi_msc_sense_fail_cdb_invalid(void); static void udi_msc_sense_command_invalid(void); //@} - /** * \name Routines manage SCSI Commands */ @@ -372,9 +366,7 @@ static void udi_msc_sbc_trans(bool b_read); //@} - -bool udi_msc_enable(void) -{ +bool udi_msc_enable(void) { uint8_t lun; udi_msc_b_trans_req = false; udi_msc_b_cbw_invalid = false; @@ -397,18 +389,14 @@ bool udi_msc_enable(void) return true; } - -void udi_msc_disable(void) -{ +void udi_msc_disable(void) { udi_msc_b_trans_req = false; udi_msc_b_ack_trans = true; udi_msc_b_reset_trans = true; UDI_MSC_DISABLE_EXT(); } - -bool udi_msc_setup(void) -{ +bool udi_msc_setup(void) { if (Udd_setup_is_in()) { // Requests Interface GET if (Udd_setup_type() == USB_REQ_TYPE_CLASS) { @@ -451,17 +439,14 @@ bool udi_msc_setup(void) return false; // Not supported request } -uint8_t udi_msc_getsetting(void) -{ +uint8_t udi_msc_getsetting(void) { return 0; // MSC don't have multiple alternate setting } - // ------------------------ //------- Routines to process CBW packet -static void udi_msc_cbw_invalid(void) -{ +static void udi_msc_cbw_invalid(void) { if (!udi_msc_b_cbw_invalid) return; // Don't re-stall endpoint if error reset by setup udd_ep_set_halt(UDI_MSC_EP_OUT); @@ -469,8 +454,7 @@ static void udi_msc_cbw_invalid(void) udd_ep_wait_stall_clear(UDI_MSC_EP_OUT, udi_msc_cbw_invalid); } -static void udi_msc_csw_invalid(void) -{ +static void udi_msc_csw_invalid(void) { if (!udi_msc_b_cbw_invalid) return; // Don't re-stall endpoint if error reset by setup udd_ep_set_halt(UDI_MSC_EP_IN); @@ -478,8 +462,7 @@ static void udi_msc_csw_invalid(void) udd_ep_wait_stall_clear(UDI_MSC_EP_IN, udi_msc_csw_invalid); } -static void udi_msc_cbw_wait(void) -{ +static void udi_msc_cbw_wait(void) { // Register buffer and callback on OUT endpoint if (!udd_ep_run(UDI_MSC_EP_OUT, true, (uint8_t *) & udi_msc_cbw, @@ -490,10 +473,8 @@ static void udi_msc_cbw_wait(void) } } - static void udi_msc_cbw_received(udd_ep_status_t status, - iram_size_t nb_received, udd_ep_id_t ep) -{ + iram_size_t nb_received, udd_ep_id_t ep) { UNUSED(ep); // Check status of transfer if (UDD_EP_TRANSFER_OK != status) { @@ -582,9 +563,7 @@ static void udi_msc_cbw_received(udd_ep_status_t status, } } - -static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag) -{ +static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag) { /* * The following cases should result in a phase error: * - Case 2: Hn < Di @@ -612,12 +591,10 @@ static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag) return true; } - // ------------------------ //------- Routines to process small data packet -static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size) -{ +static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size) { // Sends data on IN endpoint if (!udd_ep_run(UDI_MSC_EP_IN, true, buffer, buf_size, udi_msc_data_sent)) { @@ -627,10 +604,8 @@ static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size) } } - static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, - udd_ep_id_t ep) -{ + udd_ep_id_t ep) { UNUSED(ep); if (UDD_EP_TRANSFER_OK != status) { // Error protocol @@ -644,12 +619,10 @@ static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, udi_msc_csw_process(); } - // ------------------------ //------- Routines to process CSW packet -static void udi_msc_csw_process(void) -{ +static void udi_msc_csw_process(void) { if (0 != udi_msc_csw.dCSWDataResidue) { // Residue not NULL // then STALL next request from USB host on corresponding endpoint @@ -664,9 +637,7 @@ static void udi_msc_csw_process(void) udi_msc_csw_send(); } - -void udi_msc_csw_send(void) -{ +void udi_msc_csw_send(void) { // Sends CSW on IN endpoint if (!udd_ep_run(UDI_MSC_EP_IN, false, (uint8_t *) & udi_msc_csw, @@ -678,10 +649,8 @@ void udi_msc_csw_send(void) } } - static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, - udd_ep_id_t ep) -{ + udd_ep_id_t ep) { UNUSED(ep); UNUSED(status); UNUSED(nb_sent); @@ -690,20 +659,17 @@ static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, udi_msc_cbw_wait(); } - // ------------------------ //------- Routines manage sense data -static void udi_msc_clear_sense(void) -{ +static void udi_msc_clear_sense(void) { memset((uint8_t*)&udi_msc_sense, 0, sizeof(struct scsi_request_sense_data)); udi_msc_sense.valid_reponse_code = SCSI_SENSE_VALID | SCSI_SENSE_CURRENT; udi_msc_sense.AddSenseLen = SCSI_SENSE_ADDL_LEN(sizeof(udi_msc_sense)); } static void udi_msc_sense_fail(uint8_t sense_key, uint16_t add_sense, - uint32_t lba) -{ + uint32_t lba) { udi_msc_clear_sense(); udi_msc_csw.bCSWStatus = USB_CSW_STATUS_FAIL; udi_msc_sense.sense_flag_key = sense_key; @@ -715,53 +681,39 @@ static void udi_msc_sense_fail(uint8_t sense_key, uint16_t add_sense, udi_msc_sense.AddSnsCodeQlfr = add_sense; } -static void udi_msc_sense_pass(void) -{ +static void udi_msc_sense_pass(void) { udi_msc_clear_sense(); udi_msc_csw.bCSWStatus = USB_CSW_STATUS_PASS; } - -static void udi_msc_sense_fail_not_present(void) -{ +static void udi_msc_sense_fail_not_present(void) { udi_msc_sense_fail(SCSI_SK_NOT_READY, SCSI_ASC_MEDIUM_NOT_PRESENT, 0); } -static void udi_msc_sense_fail_busy_or_change(void) -{ - udi_msc_sense_fail(SCSI_SK_UNIT_ATTENTION, - SCSI_ASC_NOT_READY_TO_READY_CHANGE, 0); +static void udi_msc_sense_fail_busy_or_change(void) { + udi_msc_sense_fail(SCSI_SK_UNIT_ATTENTION, SCSI_ASC_NOT_READY_TO_READY_CHANGE, 0); } -static void udi_msc_sense_fail_hardware(void) -{ - udi_msc_sense_fail(SCSI_SK_HARDWARE_ERROR, - SCSI_ASC_NO_ADDITIONAL_SENSE_INFO, 0); +static void udi_msc_sense_fail_hardware(void) { + udi_msc_sense_fail(SCSI_SK_HARDWARE_ERROR, SCSI_ASC_NO_ADDITIONAL_SENSE_INFO, 0); } -static void udi_msc_sense_fail_protected(void) -{ +static void udi_msc_sense_fail_protected(void) { udi_msc_sense_fail(SCSI_SK_DATA_PROTECT, SCSI_ASC_WRITE_PROTECTED, 0); } -static void udi_msc_sense_fail_cdb_invalid(void) -{ - udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, - SCSI_ASC_INVALID_FIELD_IN_CDB, 0); +static void udi_msc_sense_fail_cdb_invalid(void) { + udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, SCSI_ASC_INVALID_FIELD_IN_CDB, 0); } -static void udi_msc_sense_command_invalid(void) -{ - udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, - SCSI_ASC_INVALID_COMMAND_OPERATION_CODE, 0); +static void udi_msc_sense_command_invalid(void) { + udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, SCSI_ASC_INVALID_COMMAND_OPERATION_CODE, 0); } - // ------------------------ //------- Routines manage SCSI Commands -static void udi_msc_spc_requestsense(void) -{ +static void udi_msc_spc_requestsense(void) { uint8_t length = udi_msc_cbw.CDB[4]; // Can't send more than sense data length @@ -774,9 +726,7 @@ static void udi_msc_spc_requestsense(void) udi_msc_data_send((uint8_t*)&udi_msc_sense, length); } - -static void udi_msc_spc_inquiry(void) -{ +static void udi_msc_spc_inquiry(void) { uint8_t length, i; UDC_DATA(4) // Constant inquiry data for all LUNs @@ -835,9 +785,7 @@ static void udi_msc_spc_inquiry(void) udi_msc_data_send((uint8_t *) & udi_msc_inquiry_data, length); } - -static bool udi_msc_spc_testunitready_global(void) -{ +static bool udi_msc_spc_testunitready_global(void) { switch (mem_test_unit_ready(udi_msc_cbw.bCBWLUN)) { case CTRL_GOOD: return true; // Don't change sense data @@ -855,9 +803,7 @@ static bool udi_msc_spc_testunitready_global(void) return false; } - -static void udi_msc_spc_testunitready(void) -{ +static void udi_msc_spc_testunitready(void) { if (udi_msc_spc_testunitready_global()) { // LUN ready, then update sense data with status pass udi_msc_sense_pass(); @@ -866,9 +812,7 @@ static void udi_msc_spc_testunitready(void) udi_msc_csw_process(); } - -static void udi_msc_spc_mode_sense(bool b_sense10) -{ +static void udi_msc_spc_mode_sense(bool b_sense10) { // Union of all mode sense structures union sense_6_10 { struct { @@ -943,9 +887,7 @@ static void udi_msc_spc_mode_sense(bool b_sense10) udi_msc_data_send((uint8_t *) & sense, request_lgt); } - -static void udi_msc_spc_prevent_allow_medium_removal(void) -{ +static void udi_msc_spc_prevent_allow_medium_removal(void) { uint8_t prevent = udi_msc_cbw.CDB[4]; if (0 == prevent) { udi_msc_sense_pass(); @@ -955,9 +897,7 @@ static void udi_msc_spc_prevent_allow_medium_removal(void) udi_msc_csw_process(); } - -static void udi_msc_sbc_start_stop(void) -{ +static void udi_msc_sbc_start_stop(void) { bool start = 0x1 & udi_msc_cbw.CDB[4]; bool loej = 0x2 & udi_msc_cbw.CDB[4]; if (loej) { @@ -967,9 +907,7 @@ static void udi_msc_sbc_start_stop(void) udi_msc_csw_process(); } - -static void udi_msc_sbc_read_capacity(void) -{ +static void udi_msc_sbc_read_capacity(void) { UDC_BSS(4) static struct sbc_read_capacity10_data udi_msc_capacity; if (!udi_msc_cbw_validate(sizeof(udi_msc_capacity), @@ -1003,9 +941,7 @@ static void udi_msc_sbc_read_capacity(void) sizeof(udi_msc_capacity)); } - -static void udi_msc_sbc_trans(bool b_read) -{ +static void udi_msc_sbc_trans(bool b_read) { uint32_t trans_size; if (!b_read) { @@ -1038,9 +974,7 @@ static void udi_msc_sbc_trans(bool b_read) UDI_MSC_NOTIFY_TRANS_EXT(); } - -bool udi_msc_process_trans(void) -{ +bool udi_msc_process_trans(void) { Ctrl_status status; if (!udi_msc_b_trans_req) @@ -1084,10 +1018,8 @@ bool udi_msc_process_trans(void) return true; } - static void udi_msc_trans_ack(udd_ep_status_t status, iram_size_t n, - udd_ep_id_t ep) -{ + udd_ep_id_t ep) { UNUSED(ep); UNUSED(n); // Update variable to signal the end of transfer @@ -1095,10 +1027,8 @@ static void udi_msc_trans_ack(udd_ep_status_t status, iram_size_t n, udi_msc_b_ack_trans = true; } - bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, - void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)) -{ + void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)) { if (!udi_msc_b_ack_trans) return false; // No possible, transfer on going @@ -1127,6 +1057,6 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, //@} -#endif // SDSUPPORT +#endif // HAS_MEDIA #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/usb/udi_msc.h b/Marlin/src/HAL/DUE/usb/udi_msc.h index 730dbc8eec56..0ede4d6a8346 100644 --- a/Marlin/src/HAL/DUE/usb/udi_msc.h +++ b/Marlin/src/HAL/DUE/usb/udi_msc.h @@ -77,9 +77,9 @@ extern UDC_DESC_STORAGE udi_api_t udi_api_msc; //! Interface descriptor structure for MSC typedef struct { - usb_iface_desc_t iface; - usb_ep_desc_t ep_in; - usb_ep_desc_t ep_out; + usb_iface_desc_t iface; + usb_ep_desc_t ep_in; + usb_ep_desc_t ep_out; } udi_msc_desc_t; //! By default no string associated to this interface @@ -94,32 +94,32 @@ typedef struct { //! Content of MSC interface descriptor for all speeds #define UDI_MSC_DESC \ - .iface.bLength = sizeof(usb_iface_desc_t),\ - .iface.bDescriptorType = USB_DT_INTERFACE,\ - .iface.bInterfaceNumber = UDI_MSC_IFACE_NUMBER,\ - .iface.bAlternateSetting = 0,\ - .iface.bNumEndpoints = 2,\ - .iface.bInterfaceClass = MSC_CLASS,\ - .iface.bInterfaceSubClass = MSC_SUBCLASS_TRANSPARENT,\ - .iface.bInterfaceProtocol = MSC_PROTOCOL_BULK,\ - .iface.iInterface = UDI_MSC_STRING_ID,\ - .ep_in.bLength = sizeof(usb_ep_desc_t),\ - .ep_in.bDescriptorType = USB_DT_ENDPOINT,\ - .ep_in.bEndpointAddress = UDI_MSC_EP_IN,\ - .ep_in.bmAttributes = USB_EP_TYPE_BULK,\ - .ep_in.bInterval = 0,\ - .ep_out.bLength = sizeof(usb_ep_desc_t),\ - .ep_out.bDescriptorType = USB_DT_ENDPOINT,\ - .ep_out.bEndpointAddress = UDI_MSC_EP_OUT,\ - .ep_out.bmAttributes = USB_EP_TYPE_BULK,\ - .ep_out.bInterval = 0, + .iface.bLength = sizeof(usb_iface_desc_t),\ + .iface.bDescriptorType = USB_DT_INTERFACE,\ + .iface.bInterfaceNumber = UDI_MSC_IFACE_NUMBER,\ + .iface.bAlternateSetting = 0,\ + .iface.bNumEndpoints = 2,\ + .iface.bInterfaceClass = MSC_CLASS,\ + .iface.bInterfaceSubClass = MSC_SUBCLASS_TRANSPARENT,\ + .iface.bInterfaceProtocol = MSC_PROTOCOL_BULK,\ + .iface.iInterface = UDI_MSC_STRING_ID,\ + .ep_in.bLength = sizeof(usb_ep_desc_t),\ + .ep_in.bDescriptorType = USB_DT_ENDPOINT,\ + .ep_in.bEndpointAddress = UDI_MSC_EP_IN,\ + .ep_in.bmAttributes = USB_EP_TYPE_BULK,\ + .ep_in.bInterval = 0,\ + .ep_out.bLength = sizeof(usb_ep_desc_t),\ + .ep_out.bDescriptorType = USB_DT_ENDPOINT,\ + .ep_out.bEndpointAddress = UDI_MSC_EP_OUT,\ + .ep_out.bmAttributes = USB_EP_TYPE_BULK,\ + .ep_out.bInterval = 0, //! Content of MSC interface descriptor for full speed only #define UDI_MSC_DESC_FS {\ - UDI_MSC_DESC \ - .ep_in.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ - .ep_out.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ - } + UDI_MSC_DESC \ + .ep_in.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ + .ep_out.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ + } //! Content of MSC interface descriptor for high speed only #define UDI_MSC_DESC_HS {\ @@ -129,7 +129,6 @@ typedef struct { } //@} - /** * \ingroup udi_group * \defgroup udi_msc_group USB Device Interface (UDI) for Mass Storage Class (MSC) @@ -163,14 +162,13 @@ bool udi_msc_process_trans(void); * \return \c 1 if function was successfully done, otherwise \c 0. */ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, - void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)); + void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)); //@} #ifdef __cplusplus } #endif - /** * \page udi_msc_quickstart Quick start guide for USB device Mass Storage module (UDI MSC) * @@ -200,35 +198,32 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * \subsection udi_msc_basic_use_case_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC - #define UDI_MSC_GLOBAL_VENDOR_ID \ - 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' - #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ - '1', '.', '0', '0' - #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() - extern bool my_callback_msc_enable(void); - #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() - extern void my_callback_msc_disable(void); - #include "udi_msc_conf.h" // At the end of conf_usb.h file + #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC + #define UDI_MSC_GLOBAL_VENDOR_ID \ + 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' + #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ + '1', '.', '0', '0' + #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() + extern bool my_callback_msc_enable(void); + #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() + extern void my_callback_msc_disable(void); + #include "udi_msc_conf.h" // At the end of conf_usb.h file \endcode * * Add to application C-file: * \code - static bool my_flag_autorize_msc_transfert = false; - bool my_callback_msc_enable(void) - { - my_flag_autorize_msc_transfert = true; - return true; - } - void my_callback_msc_disable(void) - { - my_flag_autorize_msc_transfert = false; - } + static bool my_flag_autorize_msc_transfert = false; + bool my_callback_msc_enable(void) { + my_flag_autorize_msc_transfert = true; + return true; + } + void my_callback_msc_disable(void) { + my_flag_autorize_msc_transfert = false; + } - void task(void) - { - udi_msc_process_trans(); - } + void task(void) { + udi_msc_process_trans(); + } \endcode * * \subsection udi_msc_basic_use_case_setup_flow Workflow @@ -237,14 +232,14 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * - \code #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC \endcode * \note The USB serial number is mandatory when a MSC interface is used. * - \code //! Vendor name and Product version of MSC interface - #define UDI_MSC_GLOBAL_VENDOR_ID \ - 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' - #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ - '1', '.', '0', '0' \endcode + #define UDI_MSC_GLOBAL_VENDOR_ID \ + 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' + #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ + '1', '.', '0', '0' \endcode * \note The USB MSC interface requires a vendor ID (8 ASCII characters) * and a product version (4 ASCII characters). * - \code #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() - extern bool my_callback_msc_enable(void); \endcode + extern bool my_callback_msc_enable(void); \endcode * \note After the device enumeration (detecting and identifying USB devices), * the USB host starts the device configuration. When the USB MSC interface * from the device is accepted by the host, the USB host enables this interface and the @@ -252,7 +247,7 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * Thus, when this event is received, the tasks which call * udi_msc_process_trans() must be enabled. * - \code #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() - extern void my_callback_msc_disable(void); \endcode + extern void my_callback_msc_disable(void); \endcode * \note When the USB device is unplugged or is reset by the USB host, the USB * interface is disabled and the UDI_MSC_DISABLE_EXT() callback function * is called. Thus, it is recommended to disable the task which is called udi_msc_process_trans(). @@ -261,15 +256,15 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * must be done outside USB interrupt routine. This is done in the MSC process * ("udi_msc_process_trans()") called by main loop: * - \code * void task(void) { - udi_msc_process_trans(); - } \endcode + udi_msc_process_trans(); + } \endcode * -# The MSC speed depends on task periodicity. To get the best speed * the notification callback "UDI_MSC_NOTIFY_TRANS_EXT" can be used to wakeup * this task (Example, through a mutex): * - \code #define UDI_MSC_NOTIFY_TRANS_EXT() msc_notify_trans() - void msc_notify_trans(void) { - wakeup_my_task(); - } \endcode + void msc_notify_trans(void) { + wakeup_my_task(); + } \endcode * * \section udi_msc_use_cases Advanced use cases * For more advanced use of the UDI MSC module, see the following use cases: @@ -302,72 +297,72 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * \subsection udi_msc_use_case_composite_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_EP_CTRL_SIZE 64 - #define USB_DEVICE_NB_INTERFACE (X+1) - #define USB_DEVICE_MAX_EP (X+2) + #define USB_DEVICE_EP_CTRL_SIZE 64 + #define USB_DEVICE_NB_INTERFACE (X+1) + #define USB_DEVICE_MAX_EP (X+2) - #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) - #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) - #define UDI_MSC_IFACE_NUMBER X + #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) + #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) + #define UDI_MSC_IFACE_NUMBER X - #define UDI_COMPOSITE_DESC_T \ - udi_msc_desc_t udi_msc; \ - ... - #define UDI_COMPOSITE_DESC_FS \ - .udi_msc = UDI_MSC_DESC, \ - ... - #define UDI_COMPOSITE_DESC_HS \ - .udi_msc = UDI_MSC_DESC, \ - ... - #define UDI_COMPOSITE_API \ - &udi_api_msc, \ - ... + #define UDI_COMPOSITE_DESC_T \ + udi_msc_desc_t udi_msc; \ + ... + #define UDI_COMPOSITE_DESC_FS \ + .udi_msc = UDI_MSC_DESC, \ + ... + #define UDI_COMPOSITE_DESC_HS \ + .udi_msc = UDI_MSC_DESC, \ + ... + #define UDI_COMPOSITE_API \ + &udi_api_msc, \ + ... \endcode * * \subsection udi_msc_use_case_composite_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required for a USB composite device configuration: * - \code // Endpoint control size, This must be: - // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) - // - 64 for a high speed device - #define USB_DEVICE_EP_CTRL_SIZE 64 - // Total Number of interfaces on this USB device. - // Add 1 for MSC. - #define USB_DEVICE_NB_INTERFACE (X+1) - // Total number of endpoints on this USB device. - // This must include each endpoint for each interface. - // Add 2 for MSC. - #define USB_DEVICE_MAX_EP (X+2) \endcode + // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) + // - 64 for a high speed device + #define USB_DEVICE_EP_CTRL_SIZE 64 + // Total Number of interfaces on this USB device. + // Add 1 for MSC. + #define USB_DEVICE_NB_INTERFACE (X+1) + // Total number of endpoints on this USB device. + // This must include each endpoint for each interface. + // Add 2 for MSC. + #define USB_DEVICE_MAX_EP (X+2) \endcode * -# Ensure that conf_usb.h contains the description of * composite device: * - \code // The endpoint numbers chosen by you for the MSC. - // The endpoint numbers starting from 1. - #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) - #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) - // The interface index of an interface starting from 0 - #define UDI_MSC_IFACE_NUMBER X \endcode + // The endpoint numbers starting from 1. + #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) + #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) + // The interface index of an interface starting from 0 + #define UDI_MSC_IFACE_NUMBER X \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB composite device configuration: * - \code // USB Interfaces descriptor structure - #define UDI_COMPOSITE_DESC_T \ - ... - udi_msc_desc_t udi_msc; \ - ... - // USB Interfaces descriptor value for Full Speed - #define UDI_COMPOSITE_DESC_FS \ - ... - .udi_msc = UDI_MSC_DESC_FS, \ - ... - // USB Interfaces descriptor value for High Speed - #define UDI_COMPOSITE_DESC_HS \ - ... - .udi_msc = UDI_MSC_DESC_HS, \ - ... - // USB Interface APIs - #define UDI_COMPOSITE_API \ - ... - &udi_api_msc, \ - ... \endcode + #define UDI_COMPOSITE_DESC_T \ + ... + udi_msc_desc_t udi_msc; \ + ... + // USB Interfaces descriptor value for Full Speed + #define UDI_COMPOSITE_DESC_FS \ + ... + .udi_msc = UDI_MSC_DESC_FS, \ + ... + // USB Interfaces descriptor value for High Speed + #define UDI_COMPOSITE_DESC_HS \ + ... + .udi_msc = UDI_MSC_DESC_HS, \ + ... + // USB Interface APIs + #define UDI_COMPOSITE_API \ + ... + &udi_api_msc, \ + ... \endcode * - \note The descriptors order given in the four lists above must be the * same as the order defined by all interface indexes. The interface index * orders are defined through UDI_X_IFACE_NUMBER defines. diff --git a/Marlin/src/HAL/DUE/usb/uotghs_device_due.c b/Marlin/src/HAL/DUE/usb/uotghs_device_due.c index c7e8f8d99135..6c0b133e01e8 100644 --- a/Marlin/src/HAL/DUE/usb/uotghs_device_due.c +++ b/Marlin/src/HAL/DUE/usb/uotghs_device_due.c @@ -276,7 +276,6 @@ # endif #endif - /** * \name Power management routine. */ @@ -293,7 +292,6 @@ static bool udd_b_idle; //! State of sleep manager static bool udd_b_sleep_initialized = false; - /*! \brief Authorize or not the CPU powerdown mode * * \param b_enable true to authorize idle mode @@ -321,7 +319,6 @@ static void udd_sleep_mode(bool b_idle) //@} - /** * \name Control endpoint low level management routine. * @@ -393,7 +390,6 @@ static void udd_ctrl_send_zlp_out(void); //! \brief Call callback associated to setup request static void udd_ctrl_endofrequest(void); - /** * \brief Main interrupt routine for control endpoint * @@ -405,7 +401,6 @@ static bool udd_ctrl_interrupt(void); //@} - /** * \name Management of bulk/interrupt/isochronous endpoints * @@ -443,7 +438,6 @@ typedef struct { uint8_t stall_requested:1; } udd_ep_job_t; - //! Array to register a job on bulk/interrupt/isochronous endpoint static udd_ep_job_t udd_ep_job[USB_DEVICE_MAX_EP]; @@ -505,7 +499,6 @@ static bool udd_ep_interrupt(void); #endif // (0!=USB_DEVICE_MAX_EP) //@} - // ------------------------ //--- INTERNAL ROUTINES TO MANAGED GLOBAL EVENTS @@ -642,13 +635,11 @@ ISR(UDD_USB_INT_FUN) return; } - bool udd_include_vbus_monitoring(void) { return true; } - void udd_enable(void) { irqflags_t flags; @@ -735,7 +726,6 @@ void udd_enable(void) cpu_irq_restore(flags); } - void udd_disable(void) { irqflags_t flags; @@ -776,7 +766,6 @@ void udd_disable(void) cpu_irq_restore(flags); } - void udd_attach(void) { irqflags_t flags; @@ -817,7 +806,6 @@ void udd_attach(void) cpu_irq_restore(flags); } - void udd_detach(void) { otg_unfreeze_clock(); @@ -828,7 +816,6 @@ void udd_detach(void) udd_sleep_mode(false); } - bool udd_is_high_speed(void) { #ifdef USB_DEVICE_HS_SUPPORT @@ -838,7 +825,6 @@ bool udd_is_high_speed(void) #endif } - void udd_set_address(uint8_t address) { udd_disable_address(); @@ -846,13 +832,11 @@ void udd_set_address(uint8_t address) udd_enable_address(); } - uint8_t udd_getaddress(void) { return udd_get_configured_address(); } - uint16_t udd_get_frame_number(void) { return udd_frame_number(); @@ -875,14 +859,12 @@ void udd_send_remotewakeup(void) } } - void udd_set_setup_payload(uint8_t *payload, uint16_t payload_size) { udd_g_ctrlreq.payload = payload; udd_g_ctrlreq.payload_size = payload_size; } - #if (0 != USB_DEVICE_MAX_EP) bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, uint16_t MaxEndpointSize) @@ -1006,7 +988,6 @@ bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, return true; } - void udd_ep_free(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; @@ -1019,14 +1000,12 @@ void udd_ep_free(udd_ep_id_t ep) udd_ep_job[ep_index - 1].stall_requested = false; } - bool udd_ep_is_halted(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; return Is_udd_endpoint_stall_requested(ep_index); } - bool udd_ep_set_halt(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; @@ -1067,7 +1046,6 @@ bool udd_ep_set_halt(udd_ep_id_t ep) return true; } - bool udd_ep_clear_halt(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; @@ -1108,7 +1086,6 @@ bool udd_ep_clear_halt(udd_ep_id_t ep) return true; } - bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, uint8_t * buf, iram_size_t buf_size, udd_callback_trans_t callback) @@ -1175,7 +1152,6 @@ bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, #endif } - void udd_ep_abort(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; @@ -1204,7 +1180,6 @@ void udd_ep_abort(udd_ep_id_t ep) udd_ep_abort_job(ep); } - bool udd_ep_wait_stall_clear(udd_ep_id_t ep, udd_callback_halt_cleared_t callback) { @@ -1239,7 +1214,6 @@ bool udd_ep_wait_stall_clear(udd_ep_id_t ep, } #endif // (0 != USB_DEVICE_MAX_EP) - #ifdef USB_DEVICE_HS_SUPPORT void udd_test_mode_j(void) @@ -1248,20 +1222,17 @@ void udd_test_mode_j(void) udd_enable_hs_test_mode_j(); } - void udd_test_mode_k(void) { udd_enable_hs_test_mode(); udd_enable_hs_test_mode_k(); } - void udd_test_mode_se0_nak(void) { udd_enable_hs_test_mode(); } - void udd_test_mode_packet(void) { uint8_t i; @@ -1305,8 +1276,6 @@ void udd_test_mode_packet(void) } #endif // USB_DEVICE_HS_SUPPORT - - // ------------------------ //--- INTERNAL ROUTINES TO MANAGED THE CONTROL ENDPOINT @@ -1356,7 +1325,6 @@ static void udd_ctrl_init(void) udd_ep_control_state = UDD_EPCTRL_SETUP; } - static void udd_ctrl_setup_received(void) { irqflags_t flags; @@ -1418,7 +1386,6 @@ static void udd_ctrl_setup_received(void) } } - static void udd_ctrl_in_sent(void) { static bool b_shortpacket = false; @@ -1502,7 +1469,6 @@ static void udd_ctrl_in_sent(void) cpu_irq_restore(flags); } - static void udd_ctrl_out_received(void) { irqflags_t flags; @@ -1593,7 +1559,6 @@ static void udd_ctrl_out_received(void) cpu_irq_restore(flags); } - static void udd_ctrl_underflow(void) { if (Is_udd_out_received(0)) @@ -1610,7 +1575,6 @@ static void udd_ctrl_underflow(void) } } - static void udd_ctrl_overflow(void) { if (Is_udd_in_send(0)) @@ -1626,7 +1590,6 @@ static void udd_ctrl_overflow(void) } } - static void udd_ctrl_stall_data(void) { // Stall all packets on IN & OUT control endpoint @@ -1634,7 +1597,6 @@ static void udd_ctrl_stall_data(void) udd_enable_stall_handshake(0); } - static void udd_ctrl_send_zlp_in(void) { irqflags_t flags; @@ -1652,7 +1614,6 @@ static void udd_ctrl_send_zlp_in(void) cpu_irq_restore(flags); } - static void udd_ctrl_send_zlp_out(void) { irqflags_t flags; @@ -1668,7 +1629,6 @@ static void udd_ctrl_send_zlp_out(void) cpu_irq_restore(flags); } - static void udd_ctrl_endofrequest(void) { // If a callback is registered then call it @@ -1677,7 +1637,6 @@ static void udd_ctrl_endofrequest(void) } } - static bool udd_ctrl_interrupt(void) { @@ -1728,7 +1687,6 @@ static bool udd_ctrl_interrupt(void) return false; } - // ------------------------ //--- INTERNAL ROUTINES TO MANAGED THE BULK/INTERRUPT/ISOCHRONOUS ENDPOINTS @@ -1743,7 +1701,6 @@ static void udd_ep_job_table_reset(void) } } - static void udd_ep_job_table_kill(void) { uint8_t i; @@ -1754,7 +1711,6 @@ static void udd_ep_job_table_kill(void) } } - static void udd_ep_abort_job(udd_ep_id_t ep) { ep &= USB_EP_ADDR_MASK; @@ -1763,7 +1719,6 @@ static void udd_ep_abort_job(udd_ep_id_t ep) udd_ep_finish_job(&udd_ep_job[ep - 1], true, ep); } - static void udd_ep_finish_job(udd_ep_job_t * ptr_job, bool b_abort, uint8_t ep_num) { if (ptr_job->busy == false) { @@ -1834,7 +1789,6 @@ static void udd_ep_trans_done(udd_ep_id_t ep) udd_dma_ctrl |= UOTGHS_DEVDMACONTROL_END_BUFFIT | UOTGHS_DEVDMACONTROL_CHANN_ENB; - // Disable IRQs to have a short sequence // between read of EOT_STA and DMA enable flags = cpu_irq_save(); diff --git a/Marlin/src/HAL/DUE/usb/uotghs_device_due.h b/Marlin/src/HAL/DUE/usb/uotghs_device_due.h index 6df26d63dfd4..99ad492c1f55 100644 --- a/Marlin/src/HAL/DUE/usb/uotghs_device_due.h +++ b/Marlin/src/HAL/DUE/usb/uotghs_device_due.h @@ -129,7 +129,6 @@ extern "C" { #define Is_udd_vbus_transition() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_VBUSTI)) //! @} - //! @name UOTGHS device attach control //! These macros manage the UOTGHS Device attach. //! @{ @@ -141,7 +140,6 @@ extern "C" { #define Is_udd_detached() (Tst_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_DETACH)) //! @} - //! @name UOTGHS device bus events control //! These macros manage the UOTGHS Device bus events. //! @{ @@ -246,7 +244,6 @@ extern "C" { #define udd_get_configured_address() (Rd_bitfield(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_UADD_Msk)) //! @} - //! @name UOTGHS Device endpoint drivers //! These macros manage the common features of the endpoints. //! @{ @@ -330,7 +327,6 @@ extern "C" { #define udd_data_toggle(ep) (Rd_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_DTSEQ_Msk)) //! @} - //! @name UOTGHS Device control endpoint //! These macros control the endpoints. //! @{ @@ -530,7 +526,6 @@ extern "C" { //! Tests if IN sending interrupt is enabled #define Is_udd_in_send_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_TXINE)) - //! Get 64-, 32-, 16- or 8-bit access to FIFO data register of selected endpoint. //! @param ep Endpoint of which to access FIFO data register //! @param scale Data scale in bits: 64, 32, 16 or 8 @@ -652,7 +647,6 @@ typedef struct { //! @} //! @} - /// @cond 0 /**INDENT-OFF**/ #ifdef __cplusplus diff --git a/Marlin/src/HAL/DUE/usb/uotghs_otg.h b/Marlin/src/HAL/DUE/usb/uotghs_otg.h index eca5e938bbe1..8c12a3e29199 100644 --- a/Marlin/src/HAL/DUE/usb/uotghs_otg.h +++ b/Marlin/src/HAL/DUE/usb/uotghs_otg.h @@ -53,7 +53,6 @@ extern "C" { #endif - //! \ingroup usb_group //! \defgroup otg_group UOTGHS OTG Driver //! UOTGHS low-level driver for OTG features @@ -74,7 +73,6 @@ bool otg_dual_enable(void); */ void otg_dual_disable(void); - //! @name UOTGHS OTG ID pin management //! The ID pin come from the USB OTG connector (A and B receptable) and //! allows to select the USB mode host or device. @@ -127,13 +125,13 @@ void otg_dual_disable(void); //! These macros allows to enable/disable pad and UOTGHS hardware //! @{ //! Reset USB macro -#define otg_reset() \ - do { \ - UOTGHS->UOTGHS_CTRL = 0; \ - while( UOTGHS->UOTGHS_SR & 0x3FFF) {\ - UOTGHS->UOTGHS_SCR = 0xFFFFFFFF;\ - } \ - } while (0) +#define otg_reset() \ + do { \ + UOTGHS->UOTGHS_CTRL = 0; \ + while( UOTGHS->UOTGHS_SR & 0x3FFF) { \ + UOTGHS->UOTGHS_SCR = 0xFFFFFFFF; \ + } \ + } while (0) //! Enable USB macro #define otg_enable() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_USBE)) //! Disable USB macro @@ -157,15 +155,14 @@ void otg_dual_disable(void); //! Configure time-out of specified OTG timer #define otg_configure_timeout(timer, timeout) (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ - Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ - Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk, timeout),\ - Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK)) + Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ + Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk, timeout),\ + Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK)) //! Get configured time-out of specified OTG timer #define otg_get_timeout(timer) (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ - Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ - Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ - Rd_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk)) - + Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ + Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ + Rd_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk)) //! Get the dual-role device state of the internal USB finite state machine of the UOTGHS controller #define otg_get_fsm_drd_state() (Rd_bitfield(UOTGHS->UOTGHS_FSM, UOTGHS_FSM_DRDSTATE_Msk)) diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol.h b/Marlin/src/HAL/DUE/usb/usb_protocol.h index ea51a8689649..9bf0a1ba60c1 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol.h @@ -108,17 +108,17 @@ * \brief Standard USB requests (bRequest) */ enum usb_reqid { - USB_REQ_GET_STATUS = 0, - USB_REQ_CLEAR_FEATURE = 1, - USB_REQ_SET_FEATURE = 3, - USB_REQ_SET_ADDRESS = 5, - USB_REQ_GET_DESCRIPTOR = 6, - USB_REQ_SET_DESCRIPTOR = 7, - USB_REQ_GET_CONFIGURATION = 8, - USB_REQ_SET_CONFIGURATION = 9, - USB_REQ_GET_INTERFACE = 10, - USB_REQ_SET_INTERFACE = 11, - USB_REQ_SYNCH_FRAME = 12, + USB_REQ_GET_STATUS = 0, + USB_REQ_CLEAR_FEATURE = 1, + USB_REQ_SET_FEATURE = 3, + USB_REQ_SET_ADDRESS = 5, + USB_REQ_GET_DESCRIPTOR = 6, + USB_REQ_SET_DESCRIPTOR = 7, + USB_REQ_GET_CONFIGURATION = 8, + USB_REQ_SET_CONFIGURATION = 9, + USB_REQ_GET_INTERFACE = 10, + USB_REQ_SET_INTERFACE = 11, + USB_REQ_SYNCH_FRAME = 12, }; /** @@ -126,9 +126,9 @@ enum usb_reqid { * */ enum usb_device_status { - USB_DEV_STATUS_BUS_POWERED = 0, - USB_DEV_STATUS_SELF_POWERED = 1, - USB_DEV_STATUS_REMOTEWAKEUP = 2 + USB_DEV_STATUS_BUS_POWERED = 0, + USB_DEV_STATUS_SELF_POWERED = 1, + USB_DEV_STATUS_REMOTEWAKEUP = 2 }; /** @@ -136,7 +136,7 @@ enum usb_device_status { * */ enum usb_interface_status { - USB_IFACE_STATUS_RESERVED = 0 + USB_IFACE_STATUS_RESERVED = 0 }; /** @@ -144,7 +144,7 @@ enum usb_interface_status { * */ enum usb_endpoint_status { - USB_EP_STATUS_HALTED = 1, + USB_EP_STATUS_HALTED = 1, }; /** @@ -153,11 +153,11 @@ enum usb_endpoint_status { * \note valid for SetFeature request. */ enum usb_device_feature { - USB_DEV_FEATURE_REMOTE_WAKEUP = 1, //!< Remote wakeup enabled - USB_DEV_FEATURE_TEST_MODE = 2, //!< USB test mode - USB_DEV_FEATURE_OTG_B_HNP_ENABLE = 3, - USB_DEV_FEATURE_OTG_A_HNP_SUPPORT = 4, - USB_DEV_FEATURE_OTG_A_ALT_HNP_SUPPORT = 5 + USB_DEV_FEATURE_REMOTE_WAKEUP = 1, //!< Remote wakeup enabled + USB_DEV_FEATURE_TEST_MODE = 2, //!< USB test mode + USB_DEV_FEATURE_OTG_B_HNP_ENABLE = 3, + USB_DEV_FEATURE_OTG_A_HNP_SUPPORT = 4, + USB_DEV_FEATURE_OTG_A_ALT_HNP_SUPPORT = 5 }; /** @@ -166,54 +166,54 @@ enum usb_device_feature { * \note valid for USB_DEV_FEATURE_TEST_MODE request. */ enum usb_device_hs_test_mode { - USB_DEV_TEST_MODE_J = 1, - USB_DEV_TEST_MODE_K = 2, - USB_DEV_TEST_MODE_SE0_NAK = 3, - USB_DEV_TEST_MODE_PACKET = 4, - USB_DEV_TEST_MODE_FORCE_ENABLE = 5, + USB_DEV_TEST_MODE_J = 1, + USB_DEV_TEST_MODE_K = 2, + USB_DEV_TEST_MODE_SE0_NAK = 3, + USB_DEV_TEST_MODE_PACKET = 4, + USB_DEV_TEST_MODE_FORCE_ENABLE = 5, }; /** * \brief Standard USB endpoint feature/status flags */ enum usb_endpoint_feature { - USB_EP_FEATURE_HALT = 0, + USB_EP_FEATURE_HALT = 0, }; /** * \brief Standard USB Test Mode Selectors */ enum usb_test_mode_selector { - USB_TEST_J = 0x01, - USB_TEST_K = 0x02, - USB_TEST_SE0_NAK = 0x03, - USB_TEST_PACKET = 0x04, - USB_TEST_FORCE_ENABLE = 0x05, + USB_TEST_J = 0x01, + USB_TEST_K = 0x02, + USB_TEST_SE0_NAK = 0x03, + USB_TEST_PACKET = 0x04, + USB_TEST_FORCE_ENABLE = 0x05, }; /** * \brief Standard USB descriptor types */ enum usb_descriptor_type { - USB_DT_DEVICE = 1, - USB_DT_CONFIGURATION = 2, - USB_DT_STRING = 3, - USB_DT_INTERFACE = 4, - USB_DT_ENDPOINT = 5, - USB_DT_DEVICE_QUALIFIER = 6, - USB_DT_OTHER_SPEED_CONFIGURATION = 7, - USB_DT_INTERFACE_POWER = 8, - USB_DT_OTG = 9, - USB_DT_IAD = 0x0B, - USB_DT_BOS = 0x0F, - USB_DT_DEVICE_CAPABILITY = 0x10, + USB_DT_DEVICE = 1, + USB_DT_CONFIGURATION = 2, + USB_DT_STRING = 3, + USB_DT_INTERFACE = 4, + USB_DT_ENDPOINT = 5, + USB_DT_DEVICE_QUALIFIER = 6, + USB_DT_OTHER_SPEED_CONFIGURATION = 7, + USB_DT_INTERFACE_POWER = 8, + USB_DT_OTG = 9, + USB_DT_IAD = 0x0B, + USB_DT_BOS = 0x0F, + USB_DT_DEVICE_CAPABILITY = 0x10, }; /** * \brief USB Device Capability types */ enum usb_capability_type { - USB_DC_USB20_EXTENSION = 0x02, + USB_DC_USB20_EXTENSION = 0x02, }; /** @@ -221,7 +221,7 @@ enum usb_capability_type { * To fill bmAttributes field of usb_capa_ext_desc_t structure. */ enum usb_capability_extension_attr { - USB_DC_EXT_LPM = 0x00000002, + USB_DC_EXT_LPM = 0x00000002, }; #define HIRD_50_US 0 @@ -254,18 +254,18 @@ enum usb_capability_extension_attr { * \brief Standard USB endpoint transfer types */ enum usb_ep_type { - USB_EP_TYPE_CONTROL = 0x00, - USB_EP_TYPE_ISOCHRONOUS = 0x01, - USB_EP_TYPE_BULK = 0x02, - USB_EP_TYPE_INTERRUPT = 0x03, - USB_EP_TYPE_MASK = 0x03, + USB_EP_TYPE_CONTROL = 0x00, + USB_EP_TYPE_ISOCHRONOUS = 0x01, + USB_EP_TYPE_BULK = 0x02, + USB_EP_TYPE_INTERRUPT = 0x03, + USB_EP_TYPE_MASK = 0x03, }; /** * \brief Standard USB language IDs for string descriptors */ enum usb_langid { - USB_LANGID_EN_US = 0x0409, //!< English (United States) + USB_LANGID_EN_US = 0x0409, //!< English (United States) }; /** @@ -308,31 +308,31 @@ COMPILER_PACK_SET(1) * The data payload of SETUP packets always follows this structure. */ typedef struct { - uint8_t bmRequestType; - uint8_t bRequest; - le16_t wValue; - le16_t wIndex; - le16_t wLength; + uint8_t bmRequestType; + uint8_t bRequest; + le16_t wValue; + le16_t wIndex; + le16_t wLength; } usb_setup_req_t; /** * \brief Standard USB device descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t bcdUSB; - uint8_t bDeviceClass; - uint8_t bDeviceSubClass; - uint8_t bDeviceProtocol; - uint8_t bMaxPacketSize0; - le16_t idVendor; - le16_t idProduct; - le16_t bcdDevice; - uint8_t iManufacturer; - uint8_t iProduct; - uint8_t iSerialNumber; - uint8_t bNumConfigurations; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t bcdUSB; + uint8_t bDeviceClass; + uint8_t bDeviceSubClass; + uint8_t bDeviceProtocol; + uint8_t bMaxPacketSize0; + le16_t idVendor; + le16_t idProduct; + le16_t bcdDevice; + uint8_t iManufacturer; + uint8_t iProduct; + uint8_t iSerialNumber; + uint8_t bNumConfigurations; } usb_dev_desc_t; /** @@ -344,15 +344,15 @@ typedef struct { * the device was operating at full speed.) */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t bcdUSB; - uint8_t bDeviceClass; - uint8_t bDeviceSubClass; - uint8_t bDeviceProtocol; - uint8_t bMaxPacketSize0; - uint8_t bNumConfigurations; - uint8_t bReserved; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t bcdUSB; + uint8_t bDeviceClass; + uint8_t bDeviceSubClass; + uint8_t bDeviceProtocol; + uint8_t bMaxPacketSize0; + uint8_t bNumConfigurations; + uint8_t bReserved; } usb_dev_qual_desc_t; /** @@ -368,23 +368,22 @@ typedef struct { * The descriptor type in the GetDescriptor() request is set to BOS. */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t wTotalLength; - uint8_t bNumDeviceCaps; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t wTotalLength; + uint8_t bNumDeviceCaps; } usb_dev_bos_desc_t; - /** * \brief USB Device Capabilities - USB 2.0 Extension Descriptor structure * * Defines the set of USB 1.1-specific device level capabilities. */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - uint8_t bDevCapabilityType; - le32_t bmAttributes; + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bDevCapabilityType; + le32_t bmAttributes; } usb_dev_capa_ext_desc_t; /** @@ -393,40 +392,38 @@ typedef struct { * The BOS descriptor and capabilities descriptors for LPM. */ typedef struct { - usb_dev_bos_desc_t bos; - usb_dev_capa_ext_desc_t capa_ext; + usb_dev_bos_desc_t bos; + usb_dev_capa_ext_desc_t capa_ext; } usb_dev_lpm_desc_t; /** * \brief Standard USB Interface Association Descriptor structure */ typedef struct { - uint8_t bLength; //!< size of this descriptor in bytes - uint8_t bDescriptorType; //!< INTERFACE descriptor type - uint8_t bFirstInterface; //!< Number of interface - uint8_t bInterfaceCount; //!< value to select alternate setting - uint8_t bFunctionClass; //!< Class code assigned by the USB - uint8_t bFunctionSubClass;//!< Sub-class code assigned by the USB - uint8_t bFunctionProtocol;//!< Protocol code assigned by the USB - uint8_t iFunction; //!< Index of string descriptor + uint8_t bLength; //!< size of this descriptor in bytes + uint8_t bDescriptorType; //!< INTERFACE descriptor type + uint8_t bFirstInterface; //!< Number of interface + uint8_t bInterfaceCount; //!< value to select alternate setting + uint8_t bFunctionClass; //!< Class code assigned by the USB + uint8_t bFunctionSubClass;//!< Sub-class code assigned by the USB + uint8_t bFunctionProtocol;//!< Protocol code assigned by the USB + uint8_t iFunction; //!< Index of string descriptor } usb_association_desc_t; - /** * \brief Standard USB configuration descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t wTotalLength; - uint8_t bNumInterfaces; - uint8_t bConfigurationValue; - uint8_t iConfiguration; - uint8_t bmAttributes; - uint8_t bMaxPower; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t wTotalLength; + uint8_t bNumInterfaces; + uint8_t bConfigurationValue; + uint8_t iConfiguration; + uint8_t bmAttributes; + uint8_t bMaxPower; } usb_conf_desc_t; - #define USB_CONFIG_ATTR_MUST_SET (1 << 7) //!< Must always be set #define USB_CONFIG_ATTR_BUS_POWERED (0 << 6) //!< Bus-powered #define USB_CONFIG_ATTR_SELF_POWERED (1 << 6) //!< Self-powered @@ -438,55 +435,54 @@ typedef struct { * \brief Standard USB association descriptor structure */ typedef struct { - uint8_t bLength; //!< Size of this descriptor in bytes - uint8_t bDescriptorType; //!< Interface descriptor type - uint8_t bFirstInterface; //!< Number of interface - uint8_t bInterfaceCount; //!< value to select alternate setting - uint8_t bFunctionClass; //!< Class code assigned by the USB - uint8_t bFunctionSubClass; //!< Sub-class code assigned by the USB - uint8_t bFunctionProtocol; //!< Protocol code assigned by the USB - uint8_t iFunction; //!< Index of string descriptor + uint8_t bLength; //!< Size of this descriptor in bytes + uint8_t bDescriptorType; //!< Interface descriptor type + uint8_t bFirstInterface; //!< Number of interface + uint8_t bInterfaceCount; //!< value to select alternate setting + uint8_t bFunctionClass; //!< Class code assigned by the USB + uint8_t bFunctionSubClass; //!< Sub-class code assigned by the USB + uint8_t bFunctionProtocol; //!< Protocol code assigned by the USB + uint8_t iFunction; //!< Index of string descriptor } usb_iad_desc_t; /** * \brief Standard USB interface descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - uint8_t bInterfaceNumber; - uint8_t bAlternateSetting; - uint8_t bNumEndpoints; - uint8_t bInterfaceClass; - uint8_t bInterfaceSubClass; - uint8_t bInterfaceProtocol; - uint8_t iInterface; + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bInterfaceNumber; + uint8_t bAlternateSetting; + uint8_t bNumEndpoints; + uint8_t bInterfaceClass; + uint8_t bInterfaceSubClass; + uint8_t bInterfaceProtocol; + uint8_t iInterface; } usb_iface_desc_t; /** * \brief Standard USB endpoint descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - uint8_t bEndpointAddress; - uint8_t bmAttributes; - le16_t wMaxPacketSize; - uint8_t bInterval; + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bEndpointAddress; + uint8_t bmAttributes; + le16_t wMaxPacketSize; + uint8_t bInterval; } usb_ep_desc_t; - /** * \brief A standard USB string descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; + uint8_t bLength; + uint8_t bDescriptorType; } usb_str_desc_t; typedef struct { - usb_str_desc_t desc; - le16_t string[1]; + usb_str_desc_t desc; + le16_t string[1]; } usb_str_lgid_desc_t; COMPILER_PACK_RESET() diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h b/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h index d594db52e33b..769e7589bcc8 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h @@ -58,42 +58,42 @@ * \name Possible values of class */ //@{ -#define CDC_CLASS_DEVICE 0x02 //!< USB Communication Device Class -#define CDC_CLASS_COMM 0x02 //!< CDC Communication Class Interface -#define CDC_CLASS_DATA 0x0A //!< CDC Data Class Interface +#define CDC_CLASS_DEVICE 0x02 //!< USB Communication Device Class +#define CDC_CLASS_COMM 0x02 //!< CDC Communication Class Interface +#define CDC_CLASS_DATA 0x0A //!< CDC Data Class Interface #define CDC_CLASS_MULTI 0xEF //!< CDC Multi-interface Function //@} //! \name USB CDC Subclass IDs //@{ -#define CDC_SUBCLASS_DLCM 0x01 //!< Direct Line Control Model -#define CDC_SUBCLASS_ACM 0x02 //!< Abstract Control Model -#define CDC_SUBCLASS_TCM 0x03 //!< Telephone Control Model -#define CDC_SUBCLASS_MCCM 0x04 //!< Multi-Channel Control Model -#define CDC_SUBCLASS_CCM 0x05 //!< CAPI Control Model -#define CDC_SUBCLASS_ETH 0x06 //!< Ethernet Networking Control Model -#define CDC_SUBCLASS_ATM 0x07 //!< ATM Networking Control Model +#define CDC_SUBCLASS_DLCM 0x01 //!< Direct Line Control Model +#define CDC_SUBCLASS_ACM 0x02 //!< Abstract Control Model +#define CDC_SUBCLASS_TCM 0x03 //!< Telephone Control Model +#define CDC_SUBCLASS_MCCM 0x04 //!< Multi-Channel Control Model +#define CDC_SUBCLASS_CCM 0x05 //!< CAPI Control Model +#define CDC_SUBCLASS_ETH 0x06 //!< Ethernet Networking Control Model +#define CDC_SUBCLASS_ATM 0x07 //!< ATM Networking Control Model //@} //! \name USB CDC Communication Interface Protocol IDs //@{ -#define CDC_PROTOCOL_V25TER 0x01 //!< Common AT commands +#define CDC_PROTOCOL_V25TER 0x01 //!< Common AT commands //@} //! \name USB CDC Data Interface Protocol IDs //@{ -#define CDC_PROTOCOL_I430 0x30 //!< ISDN BRI -#define CDC_PROTOCOL_HDLC 0x31 //!< HDLC -#define CDC_PROTOCOL_TRANS 0x32 //!< Transparent -#define CDC_PROTOCOL_Q921M 0x50 //!< Q.921 management protocol -#define CDC_PROTOCOL_Q921 0x51 //!< Q.931 [sic] Data link protocol -#define CDC_PROTOCOL_Q921TM 0x52 //!< Q.921 TEI-multiplexor -#define CDC_PROTOCOL_V42BIS 0x90 //!< Data compression procedures -#define CDC_PROTOCOL_Q931 0x91 //!< Euro-ISDN protocol control -#define CDC_PROTOCOL_V120 0x92 //!< V.24 rate adaption to ISDN -#define CDC_PROTOCOL_CAPI20 0x93 //!< CAPI Commands -#define CDC_PROTOCOL_HOST 0xFD //!< Host based driver +#define CDC_PROTOCOL_I430 0x30 //!< ISDN BRI +#define CDC_PROTOCOL_HDLC 0x31 //!< HDLC +#define CDC_PROTOCOL_TRANS 0x32 //!< Transparent +#define CDC_PROTOCOL_Q921M 0x50 //!< Q.921 management protocol +#define CDC_PROTOCOL_Q921 0x51 //!< Q.931 [sic] Data link protocol +#define CDC_PROTOCOL_Q921TM 0x52 //!< Q.921 TEI-multiplexor +#define CDC_PROTOCOL_V42BIS 0x90 //!< Data compression procedures +#define CDC_PROTOCOL_Q931 0x91 //!< Euro-ISDN protocol control +#define CDC_PROTOCOL_V120 0x92 //!< V.24 rate adaption to ISDN +#define CDC_PROTOCOL_CAPI20 0x93 //!< CAPI Commands +#define CDC_PROTOCOL_HOST 0xFD //!< Host based driver /** * \brief Describes the Protocol Unit Functional Descriptors [sic] * on Communication Class Interface @@ -103,16 +103,16 @@ //! \name USB CDC Functional Descriptor Types //@{ -#define CDC_CS_INTERFACE 0x24 //!< Interface Functional Descriptor -#define CDC_CS_ENDPOINT 0x25 //!< Endpoint Functional Descriptor +#define CDC_CS_INTERFACE 0x24 //!< Interface Functional Descriptor +#define CDC_CS_ENDPOINT 0x25 //!< Endpoint Functional Descriptor //@} //! \name USB CDC Functional Descriptor Subtypes //@{ -#define CDC_SCS_HEADER 0x00 //!< Header Functional Descriptor -#define CDC_SCS_CALL_MGMT 0x01 //!< Call Management -#define CDC_SCS_ACM 0x02 //!< Abstract Control Management -#define CDC_SCS_UNION 0x06 //!< Union Functional Descriptor +#define CDC_SCS_HEADER 0x00 //!< Header Functional Descriptor +#define CDC_SCS_CALL_MGMT 0x01 //!< Call Management +#define CDC_SCS_ACM 0x02 //!< Abstract Control Management +#define CDC_SCS_UNION 0x06 //!< Union Functional Descriptor //@} //! \name USB CDC Request IDs @@ -168,42 +168,40 @@ COMPILER_PACK_SET(1) //! \name USB CDC Descriptors //@{ - //! CDC Header Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - le16_t bcdCDC; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + le16_t bcdCDC; } usb_cdc_hdr_desc_t; //! CDC Call Management Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - uint8_t bmCapabilities; - uint8_t bDataInterface; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + uint8_t bmCapabilities; + uint8_t bDataInterface; } usb_cdc_call_mgmt_desc_t; //! CDC ACM Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - uint8_t bmCapabilities; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + uint8_t bmCapabilities; } usb_cdc_acm_desc_t; //! CDC Union Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - uint8_t bMasterInterface; - uint8_t bSlaveInterface0; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + uint8_t bMasterInterface; + uint8_t bSlaveInterface0; } usb_cdc_union_desc_t; - //! \name USB CDC Call Management Capabilities //@{ //! Device handles call management itself @@ -235,24 +233,24 @@ typedef struct { //@{ //! Line Coding structure typedef struct { - le32_t dwDTERate; - uint8_t bCharFormat; - uint8_t bParityType; - uint8_t bDataBits; + le32_t dwDTERate; + uint8_t bCharFormat; + uint8_t bParityType; + uint8_t bDataBits; } usb_cdc_line_coding_t; //! Possible values of bCharFormat enum cdc_char_format { - CDC_STOP_BITS_1 = 0, //!< 1 stop bit - CDC_STOP_BITS_1_5 = 1, //!< 1.5 stop bits - CDC_STOP_BITS_2 = 2, //!< 2 stop bits + CDC_STOP_BITS_1 = 0, //!< 1 stop bit + CDC_STOP_BITS_1_5 = 1, //!< 1.5 stop bits + CDC_STOP_BITS_2 = 2, //!< 2 stop bits }; //! Possible values of bParityType enum cdc_parity { - CDC_PAR_NONE = 0, //!< No parity - CDC_PAR_ODD = 1, //!< Odd parity - CDC_PAR_EVEN = 2, //!< Even parity - CDC_PAR_MARK = 3, //!< Parity forced to 0 (space) - CDC_PAR_SPACE = 4, //!< Parity forced to 1 (mark) + CDC_PAR_NONE = 0, //!< No parity + CDC_PAR_ODD = 1, //!< Odd parity + CDC_PAR_EVEN = 2, //!< Even parity + CDC_PAR_MARK = 3, //!< Parity forced to 0 (space) + CDC_PAR_SPACE = 4, //!< Parity forced to 1 (mark) }; //@} @@ -262,7 +260,7 @@ enum cdc_parity { //! Control signal structure typedef struct { - uint16_t value; + uint16_t value; } usb_cdc_control_signal_t; //! \name Possible values in usb_cdc_control_signal_t @@ -278,16 +276,15 @@ typedef struct { //@} //@} - //! \name USB CDC notification message //@{ typedef struct { - uint8_t bmRequestType; - uint8_t bNotification; - le16_t wValue; - le16_t wIndex; - le16_t wLength; + uint8_t bmRequestType; + uint8_t bNotification; + le16_t wValue; + le16_t wIndex; + le16_t wLength; } usb_cdc_notify_msg_t; //! \name USB CDC serial state @@ -295,8 +292,8 @@ typedef struct { //! Hardware handshake support (cdc spec 1.1 chapter 6.3.5) typedef struct { - usb_cdc_notify_msg_t header; - le16_t value; + usb_cdc_notify_msg_t header; + le16_t value; } usb_cdc_notify_serial_state_t; //! \name Possible values in usb_cdc_notify_serial_state_t diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h index e1e59237d823..227a13dc533c 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h @@ -47,7 +47,6 @@ #ifndef _USB_PROTOCOL_MSC_H_ #define _USB_PROTOCOL_MSC_H_ - /** * \ingroup usb_protocol_group * \defgroup usb_msc_protocol USB Mass Storage Class (MSC) protocol definitions @@ -59,7 +58,7 @@ * \name Possible Class value */ //@{ -#define MSC_CLASS 0x08 +#define MSC_CLASS 0x08 //@} /** @@ -71,12 +70,12 @@ * operating systems like Windows XP. */ //@{ -#define MSC_SUBCLASS_RBC 0x01 //!< Reduced Block Commands -#define MSC_SUBCLASS_ATAPI 0x02 //!< CD/DVD devices -#define MSC_SUBCLASS_QIC_157 0x03 //!< Tape devices -#define MSC_SUBCLASS_UFI 0x04 //!< Floppy disk drives -#define MSC_SUBCLASS_SFF_8070I 0x05 //!< Floppy disk drives -#define MSC_SUBCLASS_TRANSPARENT 0x06 //!< Determined by INQUIRY +#define MSC_SUBCLASS_RBC 0x01 //!< Reduced Block Commands +#define MSC_SUBCLASS_ATAPI 0x02 //!< CD/DVD devices +#define MSC_SUBCLASS_QIC_157 0x03 //!< Tape devices +#define MSC_SUBCLASS_UFI 0x04 //!< Floppy disk drives +#define MSC_SUBCLASS_SFF_8070I 0x05 //!< Floppy disk drives +#define MSC_SUBCLASS_TRANSPARENT 0x06 //!< Determined by INQUIRY //@} /** @@ -84,21 +83,19 @@ * \note Only the BULK protocol should be used in new designs. */ //@{ -#define MSC_PROTOCOL_CBI 0x00 //!< Command/Bulk/Interrupt -#define MSC_PROTOCOL_CBI_ALT 0x01 //!< W/o command completion -#define MSC_PROTOCOL_BULK 0x50 //!< Bulk-only +#define MSC_PROTOCOL_CBI 0x00 //!< Command/Bulk/Interrupt +#define MSC_PROTOCOL_CBI_ALT 0x01 //!< W/o command completion +#define MSC_PROTOCOL_BULK 0x50 //!< Bulk-only //@} - /** * \brief MSC USB requests (bRequest) */ enum usb_reqid_msc { - USB_REQ_MSC_BULK_RESET = 0xFF, //!< Mass Storage Reset - USB_REQ_MSC_GET_MAX_LUN = 0xFE //!< Get Max LUN + USB_REQ_MSC_BULK_RESET = 0xFF, //!< Mass Storage Reset + USB_REQ_MSC_GET_MAX_LUN = 0xFE //!< Get Max LUN }; - COMPILER_PACK_SET(1) /** @@ -106,38 +103,37 @@ COMPILER_PACK_SET(1) */ //@{ struct usb_msc_cbw { - le32_t dCBWSignature; //!< Must contain 'USBC' - le32_t dCBWTag; //!< Unique command ID - le32_t dCBWDataTransferLength; //!< Number of bytes to transfer - uint8_t bmCBWFlags; //!< Direction in bit 7 - uint8_t bCBWLUN; //!< Logical Unit Number - uint8_t bCBWCBLength; //!< Number of valid CDB bytes - uint8_t CDB[16]; //!< SCSI Command Descriptor Block + le32_t dCBWSignature; //!< Must contain 'USBC' + le32_t dCBWTag; //!< Unique command ID + le32_t dCBWDataTransferLength; //!< Number of bytes to transfer + uint8_t bmCBWFlags; //!< Direction in bit 7 + uint8_t bCBWLUN; //!< Logical Unit Number + uint8_t bCBWCBLength; //!< Number of valid CDB bytes + uint8_t CDB[16]; //!< SCSI Command Descriptor Block }; -#define USB_CBW_SIGNATURE 0x55534243 //!< dCBWSignature value -#define USB_CBW_DIRECTION_IN (1<<7) //!< Data from device to host -#define USB_CBW_DIRECTION_OUT (0<<7) //!< Data from host to device -#define USB_CBW_LUN_MASK 0x0F //!< Valid bits in bCBWLUN -#define USB_CBW_LEN_MASK 0x1F //!< Valid bits in bCBWCBLength +#define USB_CBW_SIGNATURE 0x55534243 //!< dCBWSignature value +#define USB_CBW_DIRECTION_IN (1<<7) //!< Data from device to host +#define USB_CBW_DIRECTION_OUT (0<<7) //!< Data from host to device +#define USB_CBW_LUN_MASK 0x0F //!< Valid bits in bCBWLUN +#define USB_CBW_LEN_MASK 0x1F //!< Valid bits in bCBWCBLength //@} - /** * \name A Command Status Wrapper (CSW). */ //@{ struct usb_msc_csw { - le32_t dCSWSignature; //!< Must contain 'USBS' - le32_t dCSWTag; //!< Same as dCBWTag - le32_t dCSWDataResidue; //!< Number of bytes not transferred - uint8_t bCSWStatus; //!< Status code + le32_t dCSWSignature; //!< Must contain 'USBS' + le32_t dCSWTag; //!< Same as dCBWTag + le32_t dCSWDataResidue; //!< Number of bytes not transferred + uint8_t bCSWStatus; //!< Status code }; -#define USB_CSW_SIGNATURE 0x55534253 //!< dCSWSignature value -#define USB_CSW_STATUS_PASS 0x00 //!< Command Passed -#define USB_CSW_STATUS_FAIL 0x01 //!< Command Failed -#define USB_CSW_STATUS_PE 0x02 //!< Phase Error +#define USB_CSW_SIGNATURE 0x55534253 //!< dCSWSignature value +#define USB_CSW_STATUS_PASS 0x00 //!< Command Passed +#define USB_CSW_STATUS_FAIL 0x01 //!< Command Failed +#define USB_CSW_STATUS_PE 0x02 //!< Phase Error //@} COMPILER_PACK_RESET() diff --git a/Marlin/src/HAL/DUE/usb/usb_task.c b/Marlin/src/HAL/DUE/usb/usb_task.c index 86ab27217abc..6f027f83a135 100644 --- a/Marlin/src/HAL/DUE/usb/usb_task.c +++ b/Marlin/src/HAL/DUE/usb/usb_task.c @@ -51,14 +51,14 @@ #include "conf_usb.h" #include "udc.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA static volatile bool main_b_msc_enable = false; #endif static volatile bool main_b_cdc_enable = false; static volatile bool main_b_dtr_active = false; void usb_task_idle(void) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA // Attend SD card access from the USB MSD -- Prioritize access to improve speed int delay = 2; while (main_b_msc_enable && --delay > 0) { @@ -70,7 +70,7 @@ void usb_task_idle(void) { #endif } -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA bool usb_task_msc_enable(void) { return ((main_b_msc_enable = true)); } void usb_task_msc_disable(void) { main_b_msc_enable = false; } bool usb_task_msc_isenabled(void) { return main_b_msc_enable; } @@ -206,13 +206,13 @@ static USB_MicrosoftExtendedPropertiesDescriptor microsoft_extended_properties_d bool usb_task_extra_string(void) { static uint8_t udi_msft_magic[] = "MSFT100\xEE"; static uint8_t udi_cdc_name[] = "CDC interface"; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA static uint8_t udi_msc_name[] = "MSC interface"; #endif struct extra_strings_desc_t { usb_str_desc_t header; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA le16_t string[Max(Max(sizeof(udi_cdc_name) - 1, sizeof(udi_msc_name) - 1), sizeof(udi_msft_magic) - 1)]; #else le16_t string[Max(sizeof(udi_cdc_name) - 1, sizeof(udi_msft_magic) - 1)]; @@ -231,7 +231,7 @@ bool usb_task_extra_string(void) { str_lgt = sizeof(udi_cdc_name) - 1; str = udi_cdc_name; break; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA case UDI_MSC_STRING_ID: str_lgt = sizeof(udi_msc_name) - 1; str = udi_msc_name; diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 46dd4e761b8c..4890972b0193 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -165,7 +165,7 @@ void MarlinHAL::init_board() { } void MarlinHAL::idletask() { - #if BOTH(WIFISUPPORT, OTASUPPORT) + #if ALL(WIFISUPPORT, OTASUPPORT) OTA_handle(); #endif TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask()); @@ -175,7 +175,7 @@ uint8_t MarlinHAL::get_reset_source() { return rtc_get_reset_reason(1); } void MarlinHAL::reboot() { ESP.restart(); } -void _delay_ms(int delay_ms) { delay(delay_ms); } +void _delay_ms(const int ms) { delay(ms); } // return free memory between end of heap (or end bss) and whatever is current int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); } diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 5dc9b2cfe2e8..0acb3676a2f9 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 @@ -169,7 +171,7 @@ void _delay_ms(const int ms); // MarlinHAL Class // ------------------------ -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 10 class MarlinHAL { diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp index 868ab1b6712d..e5302bb90553 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -53,7 +52,7 @@ static SPISettings spiConfig; // ------------------------ void spiBegin() { - #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_SS) + #if HAS_MEDIA && PIN_EXISTS(SD_SS) OUT_WRITE(SD_SS_PIN, HIGH); #endif } diff --git a/Marlin/src/HAL/ESP32/endstop_interrupts.h b/Marlin/src/HAL/ESP32/endstop_interrupts.h index 05368646101e..f2637d32524c 100644 --- a/Marlin/src/HAL/ESP32/endstop_interrupts.h +++ b/Marlin/src/HAL/ESP32/endstop_interrupts.h @@ -42,33 +42,33 @@ void ICACHE_RAM_ATTR endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); - TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN)); - TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN)); - TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN)); - TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN)); - TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN)); - TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/ESP32/i2s.cpp b/Marlin/src/HAL/ESP32/i2s.cpp index 63ceed4c9dcd..507414d9e042 100644 --- a/Marlin/src/HAL/ESP32/i2s.cpp +++ b/Marlin/src/HAL/ESP32/i2s.cpp @@ -134,8 +134,8 @@ static void IRAM_ATTR i2s_intr_handler_default(void *arg) { if (high_priority_task_awoken == pdTRUE) portYIELD_FROM_ISR(); - // clear interrupt - I2S0.int_clr.val = I2S0.int_st.val; //clear pending interrupt + // Clear pending interrupt + I2S0.int_clr.val = I2S0.int_st.val; } void stepperTask(void *parameter) { @@ -356,7 +356,7 @@ void i2s_push_sample() { // Every 4µs (when space in DMA buffer) toggle each expander PWM output using // the current duty cycle/frequency so they sync with any steps (once // through the DMA/FIFO buffers). PWM signal inversion handled by other functions - LOOP_L_N(p, MAX_EXPANDER_BITS) { + for (uint8_t p = 0; p < MAX_EXPANDER_BITS; ++p) { if (hal.pwm_pin_data[p].pwm_duty_ticks > 0) { // pin has active pwm? if (hal.pwm_pin_data[p].pwm_tick_count == 0) { if (TEST32(i2s_port_data, p)) { // hi->lo diff --git a/Marlin/src/HAL/ESP32/inc/SanityCheck.h b/Marlin/src/HAL/ESP32/inc/SanityCheck.h index 910918b9ea47..e6c364a6fe4c 100644 --- a/Marlin/src/HAL/ESP32/inc/SanityCheck.h +++ b/Marlin/src/HAL/ESP32/inc/SanityCheck.h @@ -40,7 +40,7 @@ #error "TMC220x Software Serial is not supported on ESP32." #endif -#if BOTH(WIFISUPPORT, ESP3D_WIFISUPPORT) +#if ALL(WIFISUPPORT, ESP3D_WIFISUPPORT) #error "Only enable one WiFi option, either WIFISUPPORT or ESP3D_WIFISUPPORT." #endif @@ -52,7 +52,7 @@ #error "FAST_PWM_FAN is not available on TinyBee." #endif -#if BOTH(I2S_STEPPER_STREAM, BABYSTEPPING) && DISABLED(INTEGRATED_BABYSTEPPING) +#if ALL(I2S_STEPPER_STREAM, BABYSTEPPING) && DISABLED(INTEGRATED_BABYSTEPPING) #error "BABYSTEPPING on I2S stream requires INTEGRATED_BABYSTEPPING." #endif @@ -60,10 +60,10 @@ #error "PULLDOWN pin mode is not available on ESP32 boards." #endif -#if BOTH(I2S_STEPPER_STREAM, LIN_ADVANCE) && DISABLED(EXPERIMENTAL_I2S_LA) +#if ALL(I2S_STEPPER_STREAM, LIN_ADVANCE) && DISABLED(EXPERIMENTAL_I2S_LA) #error "I2S stream is currently incompatible with LIN_ADVANCE." #endif -#if BOTH(I2S_STEPPER_STREAM, PRINTCOUNTER) && PRINTCOUNTER_SAVE_INTERVAL > 0 && DISABLED(PRINTCOUNTER_SYNC) +#if ALL(I2S_STEPPER_STREAM, PRINTCOUNTER) && PRINTCOUNTER_SAVE_INTERVAL > 0 && DISABLED(PRINTCOUNTER_SYNC) #error "PRINTCOUNTER_SAVE_INTERVAL may cause issues on ESP32 with an I2S expander. Define PRINTCOUNTER_SYNC in Configuration.h for an imperfect solution." #endif diff --git a/Marlin/src/HAL/ESP32/ota.cpp b/Marlin/src/HAL/ESP32/ota.cpp index 69a3e25e5631..01f5924871ff 100644 --- a/Marlin/src/HAL/ESP32/ota.cpp +++ b/Marlin/src/HAL/ESP32/ota.cpp @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 @@ -22,7 +24,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(WIFISUPPORT, OTASUPPORT) +#if ALL(WIFISUPPORT, OTASUPPORT) #include #include @@ -50,7 +52,7 @@ void OTA_init() { }) .onError([](ota_error_t error) { Serial.printf("Error[%u]: ", error); - char *str; + const char *str = "unknown"; switch (error) { case OTA_AUTH_ERROR: str = "Auth Failed"; break; case OTA_BEGIN_ERROR: str = "Begin Failed"; break; diff --git a/Marlin/src/HAL/ESP32/ota.h b/Marlin/src/HAL/ESP32/ota.h index 546ace82dbb8..a91d04dbb742 100644 --- a/Marlin/src/HAL/ESP32/ota.h +++ b/Marlin/src/HAL/ESP32/ota.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/ESP32/spiffs.cpp b/Marlin/src/HAL/ESP32/spiffs.cpp index a0e713bff0bb..043ad7849adb 100644 --- a/Marlin/src/HAL/ESP32/spiffs.cpp +++ b/Marlin/src/HAL/ESP32/spiffs.cpp @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(WIFISUPPORT, WEBSUPPORT) +#if ALL(WIFISUPPORT, WEBSUPPORT) #include "../../core/serial.h" diff --git a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp index bd7ecdc9f217..d26455572027 100644 --- a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp +++ b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp @@ -25,14 +25,14 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(MKS_MINI_12864, FYSETC_MINI_12864_2_1) +#if ANY(MKS_MINI_12864, FYSETC_MINI_12864_2_1) #include #include "../shared/HAL_SPI.h" #include "HAL.h" #include "SPI.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../../sd/cardreader.h" #if ENABLED(ESP3D_WIFISUPPORT) #include "sd_ESP32.h" @@ -41,7 +41,6 @@ static SPISettings spiConfig; - #ifndef LCD_SPI_SPEED #ifdef SD_SPI_SPEED #define LCD_SPI_SPEED SD_SPI_SPEED // Assume SPI speed shared with SD @@ -101,6 +100,6 @@ uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt return 1; } -#endif // EITHER(MKS_MINI_12864, FYSETC_MINI_12864_2_1) +#endif // MKS_MINI_12864 || FYSETC_MINI_12864_2_1 #endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/ESP32/web.cpp b/Marlin/src/HAL/ESP32/web.cpp index 7a27707a3e14..63a101595ff7 100644 --- a/Marlin/src/HAL/ESP32/web.cpp +++ b/Marlin/src/HAL/ESP32/web.cpp @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(WIFISUPPORT, WEBSUPPORT) +#if ALL(WIFISUPPORT, WEBSUPPORT) #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp index db43f42eaafd..9f5009d0a3cf 100644 --- a/Marlin/src/HAL/LINUX/HAL.cpp +++ b/Marlin/src/HAL/LINUX/HAL.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #ifdef __PLAT_LINUX__ #include "../../inc/MarlinConfig.h" @@ -52,8 +53,7 @@ uint8_t MarlinHAL::active_ch = 0; uint16_t MarlinHAL::adc_value() { const pin_t pin = analogInputToDigitalPin(active_ch); if (!VALID_PIN(pin)) return 0; - const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); - return data; // return 10bit value as Marlin expects + return uint16_t((Gpio::get(pin) >> 2) & 0x3FF); // return 10bit value as Marlin expects } void MarlinHAL::reboot() { /* Reset the application state and GPIO */ } diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 22c3e521f086..e84516d4dca9 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 @@ -80,8 +80,8 @@ extern MSerialT usb_serial; #define CRITICAL_SECTION_END() // ADC -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_VREF_MV 5000 +#define HAL_ADC_RESOLUTION 10 // ------------------------ // Class Utilities diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h index f05aaed88083..6e9c80ee07dc 100644 --- a/Marlin/src/HAL/LINUX/include/Arduino.h +++ b/Marlin/src/HAL/LINUX/include/Arduino.h @@ -28,6 +28,9 @@ #include +#define strlcpy(A, B, C) strncpy(A, B, (C) - 1) +#define strlcpy_P(A, B, C) strncpy_P(A, B, (C) - 1) + #define HIGH 0x01 #define LOW 0x00 diff --git a/Marlin/src/HAL/LINUX/pinsDebug.h b/Marlin/src/HAL/LINUX/pinsDebug.h index 7bfd97d024f7..e4ee27e8dd01 100644 --- a/Marlin/src/HAL/LINUX/pinsDebug.h +++ b/Marlin/src/HAL/LINUX/pinsDebug.h @@ -28,36 +28,33 @@ * Translation of routines & variables used by pinsDebug.h */ -#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS -#define pwm_details(pin) NOOP // (do nothing) -#define pwm_status(pin) false // Print a pin's PWM status. Return true if it's currently a PWM pin. +#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS #define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0) #define digitalRead_mod(p) digitalRead(p) -#define PRINT_PORT(p) #define GET_ARRAY_PIN(p) pin_array[p].pin #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%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) -#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin +#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin // active ADC function/mode/code values for PINSEL registers -constexpr int8_t ADC_pin_mode(pin_t pin) { - return (-1); -} +constexpr int8_t ADC_pin_mode(pin_t pin) { return -1; } -int8_t get_pin_mode(pin_t pin) { - if (!VALID_PIN(pin)) return -1; - return 0; -} +int8_t get_pin_mode(const pin_t pin) { return VALID_PIN(pin) ? 0 : -1; } -bool GET_PINMODE(pin_t pin) { - int8_t pin_mode = get_pin_mode(pin); - if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // found an invalid pin or active analog pin +bool GET_PINMODE(const pin_t pin) { + const int8_t pin_mode = get_pin_mode(pin); + if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // Invalid pin or active analog pin return false; - return (Gpio::getMode(pin) != 0); //input/output state + return (Gpio::getMode(pin) != 0); // Input/output state } -bool GET_ARRAY_IS_DIGITAL(pin_t pin) { +bool GET_ARRAY_IS_DIGITAL(const pin_t pin) { return (!IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin)); } + +void pwm_details(const pin_t pin) {} +bool pwm_status(const pin_t) { return false; } + +void print_port(const pin_t) {} diff --git a/Marlin/src/HAL/LINUX/servo_private.h b/Marlin/src/HAL/LINUX/servo_private.h index bcc8d2037f90..11e1c2b93c62 100644 --- a/Marlin/src/HAL/LINUX/servo_private.h +++ b/Marlin/src/HAL/LINUX/servo_private.h @@ -60,7 +60,6 @@ #define INVALID_SERVO 255 // flag indicating an invalid servo index - // Types typedef struct { diff --git a/Marlin/src/HAL/LINUX/spi_pins.h b/Marlin/src/HAL/LINUX/spi_pins.h index 9b406518738c..7bd2498be748 100644 --- a/Marlin/src/HAL/LINUX/spi_pins.h +++ b/Marlin/src/HAL/LINUX/spi_pins.h @@ -24,7 +24,7 @@ #include "../../core/macros.h" #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_U8GLIB, SDSUPPORT) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_ENABLE == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) +#if ALL(HAS_MARLINUI_U8GLIB, HAS_MEDIA) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) #define SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use diff --git a/Marlin/src/HAL/LINUX/timers.cpp b/Marlin/src/HAL/LINUX/timers.cpp index 66d80f25185a..a8ab40319773 100644 --- a/Marlin/src/HAL/LINUX/timers.cpp +++ b/Marlin/src/HAL/LINUX/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index 2d2a95774c1b..2b29edce0bb4 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index 9ff3a6ba598f..db9881cdd4ac 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -23,11 +23,22 @@ #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" -#include "../../../gcode/parser.h" +#include "../../core/millis_t.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include DefaultSerial1 USBSerial(false, UsbSerial); uint32_t MarlinHAL::adc_result = 0; +pin_t MarlinHAL::adc_pin = 0; // U8glib required functions extern "C" { @@ -48,6 +59,138 @@ int freeMemory() { return result; } +extern "C" { + #include + int isLPC1769(); + void disk_timerproc(); +} + +extern uint32_t MSC_SD_Init(uint8_t pdrv); + +void SysTick_Callback() { disk_timerproc(); } + +TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); + +void MarlinHAL::init() { + + // Init LEDs + #if PIN_EXISTS(LED) + SET_DIR_OUTPUT(LED_PIN); + WRITE_PIN_CLR(LED_PIN); + #if PIN_EXISTS(LED2) + SET_DIR_OUTPUT(LED2_PIN); + WRITE_PIN_CLR(LED2_PIN); + #if PIN_EXISTS(LED3) + SET_DIR_OUTPUT(LED3_PIN); + WRITE_PIN_CLR(LED3_PIN); + #if PIN_EXISTS(LED4) + SET_DIR_OUTPUT(LED4_PIN); + WRITE_PIN_CLR(LED4_PIN); + #endif + #endif + #endif + + // Flash status LED 3 times to indicate Marlin has started booting + for (uint8_t i = 0; i < 6; ++i) { + TOGGLE(LED_PIN); + delay(100); + } + #endif + + // Init Servo Pins + #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) + #if HAS_SERVO_0 + INIT_SERVO(0); + #endif + #if HAS_SERVO_1 + INIT_SERVO(1); + #endif + #if HAS_SERVO_2 + INIT_SERVO(2); + #endif + #if HAS_SERVO_3 + INIT_SERVO(3); + #endif + #if HAS_SERVO_4 + INIT_SERVO(4); + #endif + #if HAS_SERVO_5 + INIT_SERVO(5); + #endif + + //debug_frmwrk_init(); + //_DBG("\n\nDebug running\n"); + // Initialize the SD card chip select pins as soon as possible + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); + #endif + + #if PIN_EXISTS(ONBOARD_SD_CS) && ONBOARD_SD_CS_PIN != SD_SS_PIN + OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); + #endif + + #ifdef LPC1768_ENABLE_CLKOUT_12M + /** + * CLKOUTCFG register + * bit 8 (CLKOUT_EN) = enables CLKOUT signal. Disabled for now to prevent glitch when enabling GPIO. + * bits 7:4 (CLKOUTDIV) = set to 0 for divider setting of /1 + * bits 3:0 (CLKOUTSEL) = set to 1 to select main crystal oscillator as CLKOUT source + */ + LPC_SC->CLKOUTCFG = (0<<8)|(0<<4)|(1<<0); + // set P1.27 pin to function 01 (CLKOUT) + PINSEL_CFG_Type PinCfg; + PinCfg.Portnum = 1; + PinCfg.Pinnum = 27; + PinCfg.Funcnum = 1; // function 01 (CLKOUT) + PinCfg.OpenDrain = 0; // not open drain + PinCfg.Pinmode = 2; // no pull-up/pull-down + PINSEL_ConfigPin(&PinCfg); + // now set CLKOUT_EN bit + SBI(LPC_SC->CLKOUTCFG, 8); + #endif + + USB_Init(); // USB Initialization + USB_Connect(false); // USB clear connection + delay(1000); // Give OS time to notice + USB_Connect(true); + + TERN_(HAS_SD_HOST_DRIVE, MSC_SD_Init(0)); // Enable USB SD card access + + const millis_t usb_timeout = millis() + 2000; + while (!USB_Configuration && PENDING(millis(), usb_timeout)) { + delay(50); + idletask(); + #if PIN_EXISTS(LED) + TOGGLE(LED_PIN); // Flash quickly during USB initialization + #endif + } + + HAL_timer_init(); + + TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler +} + +#include "../../sd/cardreader.h" + +// HAL idle task +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. + // Other HALs use IS_SD_PRINTING() and IS_SD_FILE_OPEN() to check for access but + // this will not reliably detect delete operations. To be safe we will lock + // the disk if Marlin has it mounted. Unfortunately there is currently no way + // to unmount the disk from the LCD menu. + // if (IS_SD_PRINTING() || IS_SD_FILE_OPEN()) + if (card.isMounted()) + MSC_Aquire_Lock(); + else + MSC_Release_Lock(); + #endif + // Perform USB stack housekeeping + MSC_RunDeferredCommands(); +} + void MarlinHAL::reboot() { NVIC_SystemReset(); } uint8_t MarlinHAL::get_reset_source() { @@ -112,6 +255,8 @@ void flashFirmware(const int16_t) { #endif // USE_WATCHDOG +#include "../../../gcode/parser.h" + // 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. diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index b0eeb983b445..ab28e06eb89e 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 @@ -101,7 +101,7 @@ extern DefaultSerial1 USBSerial; #error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB." #endif #if HAS_DGUS_LCD - #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.available() + #define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.available() #endif #endif @@ -127,7 +127,7 @@ extern DefaultSerial1 USBSerial; // K = 6, 565 samples, 500Hz sample rate, 1.13s convergence on full range step // Memory usage per ADC channel (bytes): 4 (32 Bytes for 8 channels) -#define HAL_ADC_VREF 3.3 // ADC voltage reference +#define HAL_ADC_VREF_MV 3300 // ADC voltage reference #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 @@ -165,7 +165,9 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); // Defines // ------------------------ -#define PLATFORM_M997_SUPPORT +#ifndef PLATFORM_M997_SUPPORT + #define PLATFORM_M997_SUPPORT +#endif void flashFirmware(const int16_t); #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment @@ -241,15 +243,18 @@ class MarlinHAL { // Begin ADC sampling on the given pin. Called from Temperature::isr! static uint32_t adc_result; - static void adc_start(const pin_t pin) { - adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits - } + static pin_t adc_pin; + + static void adc_start(const pin_t pin) { adc_pin = pin; } // Is the ADC ready for reading? - static bool adc_ready() { return true; } + static bool adc_ready() { return LPC176x::adc_hardware.done(LPC176x::pin_get_adc_channel(adc_pin)); } // The current value of the ADC register - static uint16_t adc_value() { return uint16_t(adc_result); } + static uint16_t adc_value() { + adc_result = FilteredADC::read(adc_pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits + return uint16_t(adc_result); + } /** * Set the PWM duty cycle for the pin to the given value. diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index 4d6cb55cff58..6ce7f755527f 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -318,7 +318,7 @@ void SPIClass::dmaSend(void *buf, uint16_t length, bool minc) { // Enable DMA GPDMA_ChannelCmd(0, ENABLE); - /* + /** * Observed behaviour on normal data transfer completion (SKR 1.3 board / LPC1768 MCU) * GPDMA_STAT_INTTC flag is SET * GPDMA_STAT_INTERR flag is NOT SET diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.h b/Marlin/src/HAL/LPC1768/MarlinSerial.h index 3e6848a1e3d0..2fadd8209bdf 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.h +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.h @@ -30,16 +30,6 @@ #endif #include "../../core/serial_hook.h" -#ifndef SERIAL_PORT - #define SERIAL_PORT 0 -#endif -#ifndef RX_BUFFER_SIZE - #define RX_BUFFER_SIZE 128 -#endif -#ifndef TX_BUFFER_SIZE - #define TX_BUFFER_SIZE 32 -#endif - class MarlinSerial : public HardwareSerial { public: MarlinSerial(LPC_UART_TypeDef *UARTx) : HardwareSerial(UARTx) { } diff --git a/Marlin/src/HAL/LPC1768/MinSerial.cpp b/Marlin/src/HAL/LPC1768/MinSerial.cpp index 7a1c038c0b0b..368bcb5259cd 100644 --- a/Marlin/src/HAL/LPC1768/MinSerial.cpp +++ b/Marlin/src/HAL/LPC1768/MinSerial.cpp @@ -33,18 +33,18 @@ static void TX(char c) { _DBC(c); } void install_min_serial() { HAL_min_serial_out = &TX; } #if DISABLED(DYNAMIC_VECTORTABLE) -extern "C" { - __attribute__((naked)) void JumpHandler_ASM() { - __asm__ __volatile__ ( - "b CommonHandler_ASM\n" - ); + extern "C" { + __attribute__((naked)) void JumpHandler_ASM() { + __asm__ __volatile__ ( + "b CommonHandler_ASM\n" + ); + } + void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler(); } - void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler(); -} #endif #endif // POSTMORTEM_DEBUGGING diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h index f02f503a67da..221001c9483c 100644 --- a/Marlin/src/HAL/LPC1768/Servo.h +++ b/Marlin/src/HAL/LPC1768/Servo.h @@ -39,7 +39,6 @@ * License along with this library; if not, write to the Free Software * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA */ -#pragma once /** * Based on "servo.h - Interrupt driven Servo library for Arduino using 16 bit timers - diff --git a/Marlin/src/HAL/LPC1768/endstop_interrupts.h b/Marlin/src/HAL/LPC1768/endstop_interrupts.h index e4ac17f60815..924025a664a9 100644 --- a/Marlin/src/HAL/LPC1768/endstop_interrupts.h +++ b/Marlin/src/HAL/LPC1768/endstop_interrupts.h @@ -44,73 +44,97 @@ void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) #define LPC1768_PIN_INTERRUPT_M(pin) ((pin >> 0x5 & 0x7) == 0 || (pin >> 0x5 & 0x7) == 2) - #if HAS_X_MAX + #if USE_X_MAX #if !LPC1768_PIN_INTERRUPT_M(X_MAX_PIN) #error "X_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(X_MAX_PIN); #endif - #if HAS_X_MIN + #if USE_X_MIN #if !LPC1768_PIN_INTERRUPT_M(X_MIN_PIN) #error "X_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(X_MIN_PIN); #endif - #if HAS_Y_MAX + #if USE_Y_MAX #if !LPC1768_PIN_INTERRUPT_M(Y_MAX_PIN) #error "Y_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Y_MAX_PIN); #endif - #if HAS_Y_MIN + #if USE_Y_MIN #if !LPC1768_PIN_INTERRUPT_M(Y_MIN_PIN) #error "Y_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Y_MIN_PIN); #endif - #if HAS_Z_MAX + #if USE_Z_MAX #if !LPC1768_PIN_INTERRUPT_M(Z_MAX_PIN) #error "Z_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MAX_PIN); #endif - #if HAS_Z_MIN + #if USE_Z_MIN #if !LPC1768_PIN_INTERRUPT_M(Z_MIN_PIN) #error "Z_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MIN_PIN); #endif - #if HAS_Z2_MAX + #if USE_X2_MAX + #if !LPC1768_PIN_INTERRUPT_M(X2_MAX_PIN) + #error "X2_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(X2_MAX_PIN); + #endif + #if USE_X2_MIN + #if !LPC1768_PIN_INTERRUPT_M(X2_MIN_PIN) + #error "X2_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(X2_MIN_PIN); + #endif + #if USE_Y2_MAX + #if !LPC1768_PIN_INTERRUPT_M(Y2_MAX_PIN) + #error "Y2_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Y2_MAX_PIN); + #endif + #if USE_Y2_MIN + #if !LPC1768_PIN_INTERRUPT_M(Y2_MIN_PIN) + #error "Y2_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Y2_MIN_PIN); + #endif + #if USE_Z2_MAX #if !LPC1768_PIN_INTERRUPT_M(Z2_MAX_PIN) #error "Z2_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z2_MAX_PIN); #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN #if !LPC1768_PIN_INTERRUPT_M(Z2_MIN_PIN) #error "Z2_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z2_MIN_PIN); #endif - #if HAS_Z3_MAX + #if USE_Z3_MAX #if !LPC1768_PIN_INTERRUPT_M(Z3_MAX_PIN) #error "Z3_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z3_MAX_PIN); #endif - #if HAS_Z3_MIN + #if USE_Z3_MIN #if !LPC1768_PIN_INTERRUPT_M(Z3_MIN_PIN) #error "Z3_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z3_MIN_PIN); #endif - #if HAS_Z4_MAX + #if USE_Z4_MAX #if !LPC1768_PIN_INTERRUPT_M(Z4_MAX_PIN) #error "Z4_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z4_MAX_PIN); #endif - #if HAS_Z4_MIN + #if USE_Z4_MIN #if !LPC1768_PIN_INTERRUPT_M(Z4_MIN_PIN) #error "Z4_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif @@ -122,69 +146,69 @@ void setup_endstop_interrupts() { #endif _ATTACH(Z_MIN_PROBE_PIN); #endif - #if HAS_I_MAX + #if USE_I_MAX #if !LPC1768_PIN_INTERRUPT_M(I_MAX_PIN) - #error "I_MAX_PIN is not INTERRUPT-capable." + #error "I_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(I_MAX_PIN); - #elif HAS_I_MIN + #elif USE_I_MIN #if !LPC1768_PIN_INTERRUPT_M(I_MIN_PIN) - #error "I_MIN_PIN is not INTERRUPT-capable." + #error "I_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(I_MIN_PIN); #endif - #if HAS_J_MAX + #if USE_J_MAX #if !LPC1768_PIN_INTERRUPT_M(J_MAX_PIN) - #error "J_MAX_PIN is not INTERRUPT-capable." + #error "J_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(J_MAX_PIN); - #elif HAS_J_MIN + #elif USE_J_MIN #if !LPC1768_PIN_INTERRUPT_M(J_MIN_PIN) - #error "J_MIN_PIN is not INTERRUPT-capable." + #error "J_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(J_MIN_PIN); #endif - #if HAS_K_MAX + #if USE_K_MAX #if !LPC1768_PIN_INTERRUPT_M(K_MAX_PIN) - #error "K_MAX_PIN is not INTERRUPT-capable." + #error "K_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(K_MAX_PIN); - #elif HAS_K_MIN + #elif USE_K_MIN #if !LPC1768_PIN_INTERRUPT_M(K_MIN_PIN) - #error "K_MIN_PIN is not INTERRUPT-capable." + #error "K_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(K_MIN_PIN); #endif - #if HAS_U_MAX + #if USE_U_MAX #if !LPC1768_PIN_INTERRUPT_M(U_MAX_PIN) - #error "U_MAX_PIN is not INTERRUPT-capable." + #error "U_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(U_MAX_PIN); - #elif HAS_U_MIN + #elif USE_U_MIN #if !LPC1768_PIN_INTERRUPT_M(U_MIN_PIN) - #error "U_MIN_PIN is not INTERRUPT-capable." + #error "U_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(U_MIN_PIN); #endif - #if HAS_V_MAX + #if USE_V_MAX #if !LPC1768_PIN_INTERRUPT_M(V_MAX_PIN) - #error "V_MAX_PIN is not INTERRUPT-capable." + #error "V_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(V_MAX_PIN); - #elif HAS_V_MIN + #elif USE_V_MIN #if !LPC1768_PIN_INTERRUPT_M(V_MIN_PIN) - #error "V_MIN_PIN is not INTERRUPT-capable." + #error "V_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(V_MIN_PIN); #endif - #if HAS_W_MAX + #if USE_W_MAX #if !LPC1768_PIN_INTERRUPT_M(W_MAX_PIN) - #error "W_MAX_PIN is not INTERRUPT-capable." + #error "W_MAX_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(W_MAX_PIN); - #elif HAS_W_MIN + #elif USE_W_MIN #if !LPC1768_PIN_INTERRUPT_M(W_MIN_PIN) - #error "W_MIN_PIN is not INTERRUPT-capable." + #error "W_MIN_PIN is not INTERRUPT-capable. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(W_MIN_PIN); #endif diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h index 5f1c4b16019d..65b019b261a8 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h @@ -20,3 +20,7 @@ * */ #pragma once + +#ifndef SERIAL_PORT + #define SERIAL_PORT 0 +#endif diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h index 8e7cab185f2a..9d04c4f787c6 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h @@ -24,3 +24,10 @@ #if DISABLED(NO_SD_HOST_DRIVE) #define HAS_SD_HOST_DRIVE 1 #endif + +#ifndef RX_BUFFER_SIZE + #define RX_BUFFER_SIZE 128 +#endif +#ifndef TX_BUFFER_SIZE + #define TX_BUFFER_SIZE 32 +#endif diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h index a0bf4215383e..0b03cb2aea63 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h @@ -23,7 +23,7 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index 94923e21cf9a..f49bc34c9253 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -99,7 +99,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #if USING_HW_SERIAL0 #define IS_TX0(P) (P == P0_02) #define IS_RX0(P) (P == P0_03) - #if IS_TX0(TMC_SW_MISO) || IS_RX0(TMC_SW_MOSI) + #if IS_TX0(TMC_SPI_MISO) || IS_RX0(TMC_SPI_MOSI) #error "Serial port pins (0) conflict with Trinamic SPI pins!" #elif HAS_PRUSA_MMU1 && (IS_TX0(E_MUX1_PIN) || IS_RX0(E_MUX0_PIN)) #error "Serial port pins (0) conflict with Multi-Material-Unit multiplexer pins!" @@ -115,7 +115,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #define IS_RX1(P) (P == P0_16) #define _IS_TX1_1 IS_TX1 #define _IS_RX1_1 IS_RX1 - #if IS_TX1(TMC_SW_SCK) + #if IS_TX1(TMC_SPI_SCK) #error "Serial port pins (1) conflict with other pins!" #elif HAS_ROTARY_ENCODER #if IS_TX1(BTN_EN2) || IS_RX1(BTN_EN1) @@ -201,7 +201,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #if USEDI2CDEV_M == 0 // P0_27 [D57] (AUX-1) .......... P0_28 [D58] (AUX-1) #define PIN_IS_SDA0(P) (P##_PIN == P0_27) #define IS_SCL0(P) (P == P0_28) - #if ENABLED(SDSUPPORT) && PIN_IS_SDA0(SD_DETECT) + #if HAS_MEDIA && PIN_IS_SDA0(SD_DETECT) #error "SDA0 overlaps with SD_DETECT_PIN!" #elif PIN_IS_SDA0(E0_AUTO_FAN) #error "SDA0 overlaps with E0_AUTO_FAN_PIN!" diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp deleted file mode 100644 index 419c99793fb8..000000000000 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ /dev/null @@ -1,163 +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 . - * - */ -#ifdef TARGET_LPC1768 - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "../../inc/MarlinConfig.h" -#include "../../core/millis_t.h" - -#include "../../sd/cardreader.h" - -extern uint32_t MSC_SD_Init(uint8_t pdrv); - -extern "C" { - #include - extern "C" int isLPC1769(); - extern "C" void disk_timerproc(); -} - -void SysTick_Callback() { disk_timerproc(); } - -TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); - -void MarlinHAL::init() { - - // Init LEDs - #if PIN_EXISTS(LED) - SET_DIR_OUTPUT(LED_PIN); - WRITE_PIN_CLR(LED_PIN); - #if PIN_EXISTS(LED2) - SET_DIR_OUTPUT(LED2_PIN); - WRITE_PIN_CLR(LED2_PIN); - #if PIN_EXISTS(LED3) - SET_DIR_OUTPUT(LED3_PIN); - WRITE_PIN_CLR(LED3_PIN); - #if PIN_EXISTS(LED4) - SET_DIR_OUTPUT(LED4_PIN); - WRITE_PIN_CLR(LED4_PIN); - #endif - #endif - #endif - - // Flash status LED 3 times to indicate Marlin has started booting - LOOP_L_N(i, 6) { - TOGGLE(LED_PIN); - delay(100); - } - #endif - - // Init Servo Pins - #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) - #if HAS_SERVO_0 - INIT_SERVO(0); - #endif - #if HAS_SERVO_1 - INIT_SERVO(1); - #endif - #if HAS_SERVO_2 - INIT_SERVO(2); - #endif - #if HAS_SERVO_3 - INIT_SERVO(3); - #endif - - //debug_frmwrk_init(); - //_DBG("\n\nDebug running\n"); - // Initialize the SD card chip select pins as soon as possible - #if PIN_EXISTS(SD_SS) - OUT_WRITE(SD_SS_PIN, HIGH); - #endif - - #if PIN_EXISTS(ONBOARD_SD_CS) && ONBOARD_SD_CS_PIN != SD_SS_PIN - OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); - #endif - - #ifdef LPC1768_ENABLE_CLKOUT_12M - /** - * CLKOUTCFG register - * bit 8 (CLKOUT_EN) = enables CLKOUT signal. Disabled for now to prevent glitch when enabling GPIO. - * bits 7:4 (CLKOUTDIV) = set to 0 for divider setting of /1 - * bits 3:0 (CLKOUTSEL) = set to 1 to select main crystal oscillator as CLKOUT source - */ - LPC_SC->CLKOUTCFG = (0<<8)|(0<<4)|(1<<0); - // set P1.27 pin to function 01 (CLKOUT) - PINSEL_CFG_Type PinCfg; - PinCfg.Portnum = 1; - PinCfg.Pinnum = 27; - PinCfg.Funcnum = 1; // function 01 (CLKOUT) - PinCfg.OpenDrain = 0; // not open drain - PinCfg.Pinmode = 2; // no pull-up/pull-down - PINSEL_ConfigPin(&PinCfg); - // now set CLKOUT_EN bit - SBI(LPC_SC->CLKOUTCFG, 8); - #endif - - USB_Init(); // USB Initialization - USB_Connect(false); // USB clear connection - delay(1000); // Give OS time to notice - USB_Connect(true); - - TERN_(HAS_SD_HOST_DRIVE, MSC_SD_Init(0)); // Enable USB SD card access - - const millis_t usb_timeout = millis() + 2000; - while (!USB_Configuration && PENDING(millis(), usb_timeout)) { - delay(50); - idletask(); - #if PIN_EXISTS(LED) - TOGGLE(LED_PIN); // Flash quickly during USB initialization - #endif - } - - HAL_timer_init(); - - TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler -} - -// HAL idle task -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. - // Other HALs use IS_SD_PRINTING() and IS_SD_FILE_OPEN() to check for access but - // this will not reliably detect delete operations. To be safe we will lock - // the disk if Marlin has it mounted. Unfortunately there is currently no way - // to unmount the disk from the LCD menu. - // if (IS_SD_PRINTING() || IS_SD_FILE_OPEN()) - if (card.isMounted()) - MSC_Aquire_Lock(); - else - MSC_Release_Lock(); - #endif - // Perform USB stack housekeeping - MSC_RunDeferredCommands(); -} - -#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/pinsDebug.h b/Marlin/src/HAL/LPC1768/pinsDebug.h index ae8901b0137a..975511be9a94 100644 --- a/Marlin/src/HAL/LPC1768/pinsDebug.h +++ b/Marlin/src/HAL/LPC1768/pinsDebug.h @@ -29,11 +29,8 @@ */ #define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS -#define pwm_details(pin) NOOP // do nothing -#define pwm_status(pin) false // Print a pin's PWM status. Return true if it's currently a PWM pin. #define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0) #define digitalRead_mod(p) extDigitalRead(p) -#define PRINT_PORT(p) #define GET_ARRAY_PIN(p) pin_array[p].pin #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("P%d_%02d"), LPC176x::pin_port(p), LPC176x::pin_bit(p)); SERIAL_ECHO(buffer); }while(0) @@ -46,10 +43,14 @@ #endif bool GET_PINMODE(const pin_t pin) { - if (!LPC176x::pin_is_valid(pin) || LPC176x::pin_adc_enabled(pin)) // found an invalid pin or active analog pin + if (!LPC176x::pin_is_valid(pin) || LPC176x::pin_adc_enabled(pin)) // Invalid pin or active analog pin return false; return LPC176x::gpio_direction(pin); } #define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) + +void print_port(const pin_t) {} +void pwm_details(const pin_t) {} +bool pwm_status(const pin_t) { return false; } diff --git a/Marlin/src/HAL/LPC1768/spi_pins.h b/Marlin/src/HAL/LPC1768/spi_pins.h index a82b21dda91f..5551948286a5 100644 --- a/Marlin/src/HAL/LPC1768/spi_pins.h +++ b/Marlin/src/HAL/LPC1768/spi_pins.h @@ -23,7 +23,7 @@ #include "../../core/macros.h" -#if BOTH(SDSUPPORT, HAS_MARLINUI_U8GLIB) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_ENABLE == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) +#if ALL(HAS_MARLINUI_U8GLIB, HAS_MEDIA) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) #define SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use diff --git a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp index 804fc85e792f..c148617785cc 100644 --- a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp +++ b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp @@ -20,6 +20,8 @@ * */ +#ifdef TARGET_LPC1768 + #include "../../../inc/MarlinConfig.h" #if HAS_SPI_TFT @@ -72,7 +74,7 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { WRITE(TFT_CS_PIN, LOW); WriteReg(Reg); - LOOP_L_N(i, 4) { + for (uint8_t i = 0; i < 4; ++i) { SPIx.read((uint8_t*)&d, 1); data = (data << 8) | d; } @@ -139,7 +141,8 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun DataTransferBegin(DATASIZE_16BIT); SPIx.dmaSendAsync(Data, Count, MemoryIncrease); - TERN_(TFT_SHARED_SPI, while (isBusy())); + TERN_(TFT_SHARED_IO, while (isBusy())); } #endif // HAS_SPI_TFT +#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/tft/tft_spi.h b/Marlin/src/HAL/LPC1768/tft/tft_spi.h index dad393981ed1..54b72248b9d5 100644 --- a/Marlin/src/HAL/LPC1768/tft/tft_spi.h +++ b/Marlin/src/HAL/LPC1768/tft/tft_spi.h @@ -49,7 +49,7 @@ #define DATASIZE_8BIT SSP_DATABIT_8 #define DATASIZE_16BIT SSP_DATABIT_16 #define TFT_IO_DRIVER TFT_SPI -#define DMA_MAX_SIZE 0xFFF +#define DMA_MAX_WORDS 0xFFF #define DMA_MINC_ENABLE 1 #define DMA_MINC_DISABLE 0 @@ -82,8 +82,8 @@ class TFT_SPI { static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_MINC_ENABLE, Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { while (Count > 0) { - Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count); - Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0; + Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_WORDS ? DMA_MAX_WORDS : Count); + Count = Count > DMA_MAX_WORDS ? Count - DMA_MAX_WORDS : 0; } } }; diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp index 68a2176f5ed6..910511612b9b 100644 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp +++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp @@ -20,6 +20,8 @@ * */ +#ifdef TARGET_LPC1768 + #include "../../../inc/MarlinConfig.h" #if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS @@ -130,4 +132,5 @@ uint16_t XPT2046::SoftwareIO(uint16_t data) { return result; } -#endif // HAS_TFT_XPT2046 +#endif // HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS +#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/timers.cpp b/Marlin/src/HAL/LPC1768/timers.cpp index bbb13f81da05..b541ab6e6a25 100644 --- a/Marlin/src/HAL/LPC1768/timers.cpp +++ b/Marlin/src/HAL/LPC1768/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index c6d7bc632e2e..bae01703ed85 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h b/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h index d2260037b6a7..fb7fdcb8692b 100644 --- a/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h +++ b/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h @@ -34,7 +34,6 @@ uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t ar uint8_t u8g_com_HAL_LPC1768_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); - // connect U8g com generic com names to the desired driver #define U8G_COM_HW_SPI u8g_com_HAL_LPC1768_hw_spi_fn // use LPC1768 specific hardware SPI routine #define U8G_COM_SW_SPI u8g_com_HAL_LPC1768_sw_spi_fn // use LPC1768 specific software SPI routine diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp index 0118f92847de..406fc4840c21 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp @@ -125,5 +125,4 @@ uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, } #endif // HAS_MARLINUI_U8GLIB - #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp index bf76eaf0f491..3dea365ac7b8 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp @@ -194,5 +194,4 @@ uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_v } #endif // HAS_MARLINUI_U8GLIB - #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp index ce7b33801931..c029dc068013 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp @@ -134,5 +134,4 @@ uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t ar } #endif // HAS_MARLINUI_U8GLIB - #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp index f116a9b80aa6..f6ed7b0e7e8a 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp @@ -75,7 +75,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (spi_speed == 0) { LPC176x::gpio_set(mosi_pin, !!(b & 0x80)); LPC176x::gpio_set(sck_pin, HIGH); @@ -85,16 +85,16 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck } else { const uint8_t state = (b & 0x80) ? HIGH : LOW; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) LPC176x::gpio_set(mosi_pin, state); - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) LPC176x::gpio_set(sck_pin, HIGH); b <<= 1; if (miso_pin >= 0 && LPC176x::gpio_get(miso_pin)) b |= 1; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) LPC176x::gpio_set(sck_pin, LOW); } } @@ -104,7 +104,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { const uint8_t state = (b & 0x80) ? HIGH : LOW; if (spi_speed == 0) { LPC176x::gpio_set(sck_pin, LOW); @@ -113,13 +113,13 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck LPC176x::gpio_set(sck_pin, HIGH); } else { - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) LPC176x::gpio_set(sck_pin, LOW); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) LPC176x::gpio_set(mosi_pin, state); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) LPC176x::gpio_set(sck_pin, HIGH); } b <<= 1; @@ -132,7 +132,7 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck static uint8_t SPI_speed = 0; static void u8g_sw_spi_HAL_LPC1768_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val) { - #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) + #if ANY(FYSETC_MINI_12864, MKS_MINI_12864) swSpiTransfer_mode_3(val, SPI_speed, clockPin, -1, dataPin); #else swSpiTransfer_mode_0(val, SPI_speed, clockPin, -1, dataPin); @@ -160,10 +160,10 @@ uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, break; case U8G_COM_MSG_CHIP_SELECT: - #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 - if (arg_val) { // SCK idle state needs to be set to the proper idle state before - // the next chip select goes active - u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active + #if ANY(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active u8g_SetPILevel(u8g, U8G_PI_CS, LOW); } else { diff --git a/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf b/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf index 4732eb855242..37d9a617dbb5 100644 --- a/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf +++ b/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf @@ -8,14 +8,12 @@ DriverVer =04/14/2008, 5.1.2600.5512 [Manufacturer] %PROVIDER%=DeviceList,ntamd64 - [DeviceList] %DESCRIPTION%=LPC1768USB, USB\VID_1D50&PID_6029&MI_00 [DeviceList.ntamd64] %DESCRIPTION%=LPC1768USB, USB\VID_1D50&PID_6029&MI_00 - [LPC1768USB] include=mdmcpq.inf CopyFiles=FakeModemCopyFileSection @@ -28,9 +26,8 @@ AddService=usbser, 0x00000002, LowerFilter_Service_Inst [SerialPropPageAddReg] HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider" - [Strings] PROVIDER = "marlinfw.org" DRIVER.SVC = "Marlin USB Driver" DESCRIPTION= "Marlin USB Serial" -COMPOSITE = "Marlin USB VCOM" \ No newline at end of file +COMPOSITE = "Marlin USB VCOM" diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 52e5eb4f3997..8e88e5023026 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 @@ -114,8 +114,8 @@ extern MSerialT serial_stream_3; // ADC // ------------------------ -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_VREF_MV 5000 +#define HAL_ADC_RESOLUTION 10 /* ---------------- Delay in cycles */ diff --git a/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h index b5cc6f02a45a..0c447ba4cb3d 100644 --- a/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h +++ b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp new file mode 100644 index 000000000000..c4d56c6c218d --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.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 . + * + */ + +#ifdef __PLAT_NATIVE_SIM__ + +#include "../../inc/MarlinConfig.h" +#include "pinsDebug.h" + +int8_t ADC_pin_mode(pin_t pin) { return -1; } + +int8_t get_pin_mode(const pin_t pin) { return VALID_PIN(pin) ? 0 : -1; } + +bool GET_PINMODE(const pin_t pin) { + const int8_t pin_mode = get_pin_mode(pin); + if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // Invalid pin or active analog pin + return false; + + return (Gpio::getMode(pin) != 0); // Input/output state +} + +bool GET_ARRAY_IS_DIGITAL(const pin_t pin) { + return !IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin); +} + +void print_port(const pin_t) {} +void pwm_details(const pin_t) {} +bool pwm_status(const pin_t) { return false; } + +#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h index af9a651c79ae..3321d1484dbe 100644 --- a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h @@ -2,6 +2,9 @@ * 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 @@ -27,35 +30,19 @@ */ #define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS -#define pwm_details(pin) NOOP // do nothing -#define pwm_status(pin) false // Print a pin's PWM status. Return true if it's currently a PWM pin. #define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0) #define digitalRead_mod(p) digitalRead(p) -#define PRINT_PORT(p) #define GET_ARRAY_PIN(p) pin_array[p].pin #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%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) #define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin -// active ADC function/mode/code values for PINSEL registers -inline constexpr int8_t ADC_pin_mode(pin_t pin) { - return (-1); -} - -inline int8_t get_pin_mode(pin_t pin) { - if (!VALID_PIN(pin)) return -1; - return 0; -} - -inline bool GET_PINMODE(pin_t pin) { - int8_t pin_mode = get_pin_mode(pin); - if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // found an invalid pin or active analog pin - return false; - - return (Gpio::getMode(pin) != 0); //input/output state -} - -inline bool GET_ARRAY_IS_DIGITAL(pin_t pin) { - return (!IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin)); -} +// Active ADC function/mode/code values for PINSEL registers +int8_t ADC_pin_mode(pin_t pin); +int8_t get_pin_mode(const pin_t pin); +bool GET_PINMODE(const pin_t pin); +bool GET_ARRAY_IS_DIGITAL(const pin_t pin); +void print_port(const pin_t); +void pwm_details(const pin_t); +bool pwm_status(const pin_t); diff --git a/Marlin/src/HAL/NATIVE_SIM/servo_private.h b/Marlin/src/HAL/NATIVE_SIM/servo_private.h index 06be1893f6eb..e0eb30ab2846 100644 --- a/Marlin/src/HAL/NATIVE_SIM/servo_private.h +++ b/Marlin/src/HAL/NATIVE_SIM/servo_private.h @@ -61,7 +61,6 @@ #define INVALID_SERVO 255 // flag indicating an invalid servo index - // Types typedef struct { diff --git a/Marlin/src/HAL/NATIVE_SIM/spi_pins.h b/Marlin/src/HAL/NATIVE_SIM/spi_pins.h index fd3378b33759..9b1bae9a5836 100644 --- a/Marlin/src/HAL/NATIVE_SIM/spi_pins.h +++ b/Marlin/src/HAL/NATIVE_SIM/spi_pins.h @@ -24,7 +24,7 @@ #include "../../core/macros.h" #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_U8GLIB, SDSUPPORT) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_ENABLE == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) +#if ALL(HAS_MARLINUI_U8GLIB, HAS_MEDIA) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) #define SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h b/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h index b3e622f19ac4..1e0bc20984f8 100644 --- a/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h +++ b/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h @@ -31,10 +31,11 @@ #endif #define DATASIZE_8BIT 8 -#define DATASIZE_16BIT 16 -#define TFT_IO_DRIVER TFT_SPI +#define DATASIZE_16BIT 16 +#define TFT_IO_DRIVER TFT_SPI +#define DMA_MAX_WORDS 0xFFFF -#define DMA_MINC_ENABLE 1 +#define DMA_MINC_ENABLE 1 #define DMA_MINC_DISABLE 0 class TFT_SPI { diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h index 4e999f88ff98..8bf059f59c0f 100644 --- a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h +++ b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index be38d583b686..d46e8e7b9402 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h index 2a50eddcd407..05d5526b6312 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h @@ -21,6 +21,10 @@ */ #pragma once +/** + * Native/Simulator LCD-specific defines + */ + void usleep(uint64_t microsec); // The following are optional depending on the platform. diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h index c27c84e8c398..39af4d7e6844 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h @@ -31,7 +31,6 @@ * resulted in using about about 25% of the CPU's time. */ - #ifdef __cplusplus extern "C" { #endif diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp index a3254774bfdf..46f2798afaa6 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp @@ -100,6 +100,7 @@ static void u8g_com_st7920_write_byte_sw_spi(uint8_t rs, uint8_t val) { swSpiTransfer(val & 0x0F0, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); swSpiTransfer(val << 4, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); } + #ifdef __cplusplus extern "C" { #endif @@ -128,7 +129,7 @@ uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void break; case U8G_COM_MSG_RESET: - if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val); + if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val); break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ @@ -163,6 +164,7 @@ uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void } return 1; } + #ifdef __cplusplus } #endif diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp index 7be84580b133..9184e2f6188c 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp @@ -70,7 +70,7 @@ #endif uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (spi_speed == 0) { WRITE_PIN(mosi_pin, !!(b & 0x80)); WRITE_PIN(sck_pin, HIGH); @@ -80,16 +80,16 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck } else { const uint8_t state = (b & 0x80) ? HIGH : LOW; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE_PIN(mosi_pin, state); - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE_PIN(sck_pin, HIGH); b <<= 1; if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE_PIN(sck_pin, LOW); } } @@ -99,7 +99,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { const uint8_t state = (b & 0x80) ? HIGH : LOW; if (spi_speed == 0) { WRITE_PIN(sck_pin, LOW); @@ -108,13 +108,13 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck WRITE_PIN(sck_pin, HIGH); } else { - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE_PIN(sck_pin, LOW); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE_PIN(mosi_pin, state); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE_PIN(sck_pin, HIGH); } b <<= 1; @@ -131,7 +131,7 @@ static uint8_t swSpiInit(const uint8_t spi_speed, const uint8_t clk_pin, const u } static void u8g_sw_spi_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val) { - #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) + #if ANY(FYSETC_MINI_12864, MKS_MINI_12864) swSpiTransfer_mode_3(val, SPI_speed, clockPin, -1, dataPin); #else swSpiTransfer_mode_0(val, SPI_speed, clockPin, -1, dataPin); @@ -159,10 +159,10 @@ uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt break; case U8G_COM_MSG_CHIP_SELECT: - #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 - if (arg_val) { // SCK idle state needs to be set to the proper idle state before - // the next chip select goes active - u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active + #if ANY(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active u8g_SetPILevel(u8g, U8G_PI_CS, LOW); } else { diff --git a/Marlin/src/HAL/SAMD21/HAL.cpp b/Marlin/src/HAL/SAMD21/HAL.cpp index 14c439eeb911..3656d97190e6 100644 --- a/Marlin/src/HAL/SAMD21/HAL.cpp +++ b/Marlin/src/HAL/SAMD21/HAL.cpp @@ -40,8 +40,6 @@ DefaultSerial3 MSerial2(false, Serial2); #endif - - #define WDT_CONFIG_PER_7_Val 0x9u #define WDT_CONFIG_PER_Pos 0 #define WDT_CONFIG_PER_7 (WDT_CONFIG_PER_7_Val << WDT_CONFIG_PER_Pos) @@ -105,7 +103,7 @@ void MarlinHAL::dma_init() {} // HAL initialization task void MarlinHAL::init() { TERN_(DMA_IS_REQUIRED, dma_init()); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA #if HAS_SD_DETECT && SD_CONNECTION_IS(ONBOARD) SET_INPUT_PULLUP(SD_DETECT_PIN); #endif @@ -165,7 +163,6 @@ void MarlinHAL::adc_init() { ADC->REFCTRL.reg = ADC_REFCTRL_REFSEL_INTVCC1; ADC->AVGCTRL.reg = ADC_AVGCTRL_SAMPLENUM_32| ADC_AVGCTRL_ADJRES(4);; - ADC->CTRLB.reg = ADC_CTRLB_PRESCALER_DIV128 | ADC_CTRLB_RESSEL_16BIT | ADC_CTRLB_FREERUN; diff --git a/Marlin/src/HAL/SAMD21/HAL.h b/Marlin/src/HAL/SAMD21/HAL.h index 1854e523ed62..b9d428ae2e8e 100644 --- a/Marlin/src/HAL/SAMD21/HAL.h +++ b/Marlin/src/HAL/SAMD21/HAL.h @@ -47,7 +47,6 @@ typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; extern DefaultSerial2 MSerial0; extern DefaultSerial3 MSerial1; - #define __MSERIAL(X) MSerial##X #define _MSERIAL(X) __MSERIAL(X) #define MSERIAL(X) _MSERIAL(INCREMENT(X)) @@ -111,7 +110,7 @@ typedef Servo hal_servo_t; // #define HAL_ADC_FILTERED 1 // Disable Marlin's oversampling. The HAL filters ADC values. -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 12 #define HAL_ADC_AIN_START ADC_INPUTCTRL_MUXPOS_PIN3 #define HAL_ADC_AIN_NUM_SENSORS 3 diff --git a/Marlin/src/HAL/SAMD21/HAL_SPI.cpp b/Marlin/src/HAL/SAMD21/HAL_SPI.cpp index 69c6a43af835..e01f540cf8a1 100644 --- a/Marlin/src/HAL/SAMD21/HAL_SPI.cpp +++ b/Marlin/src/HAL/SAMD21/HAL_SPI.cpp @@ -45,7 +45,7 @@ // Public functions // -------------------------------------------------------------------------- -#if EITHER(SOFTWARE_SPI, FORCE_SOFT_SPI) +#if ANY(SOFTWARE_SPI, FORCE_SOFT_SPI) // ------------------------ // Software SPI diff --git a/Marlin/src/HAL/SAMD21/SAMD21.h b/Marlin/src/HAL/SAMD21/SAMD21.h index 8e9d17fc5026..b64c5ce72555 100644 --- a/Marlin/src/HAL/SAMD21/SAMD21.h +++ b/Marlin/src/HAL/SAMD21/SAMD21.h @@ -57,8 +57,6 @@ : (P == 3 && WITHIN(B, 20, 21)) ? 10 + (B) - 20 \ : -1) - - #define A2_AIN 3 #define A3_AIN 4 #define A4_AIN 5 diff --git a/Marlin/src/HAL/SAMD21/Servo.cpp b/Marlin/src/HAL/SAMD21/Servo.cpp index 38b995fc9a05..704d0a2904ce 100644 --- a/Marlin/src/HAL/SAMD21/Servo.cpp +++ b/Marlin/src/HAL/SAMD21/Servo.cpp @@ -55,7 +55,6 @@ #define TIMER_TCCHANNEL(t) ((t) & 1) #define TC_COUNTER_START_VAL 0xFFFF - 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() { diff --git a/Marlin/src/HAL/SAMD21/eeprom_flash.cpp b/Marlin/src/HAL/SAMD21/eeprom_flash.cpp index 4a4e328d1a00..5364cd671968 100644 --- a/Marlin/src/HAL/SAMD21/eeprom_flash.cpp +++ b/Marlin/src/HAL/SAMD21/eeprom_flash.cpp @@ -37,19 +37,23 @@ static const uint8_t flashdata[TOTAL_FLASH_SIZE] __attribute__((__aligned__(256 #include "../shared/eeprom_api.h" -size_t PersistentStore::capacity() { - return MARLIN_EEPROM_SIZE; - /* const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ, +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + +/* + const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ, sblk = NVMCTRL->SEESTAT.bit.SBLK; - return (!psz && !sblk) ? 0 - : (psz <= 2) ? (0x200 << psz) - : (sblk == 1 || psz == 3) ? 4096 - : (sblk == 2 || psz == 4) ? 8192 - : (sblk <= 4 || psz == 5) ? 16384 - : (sblk >= 9 && psz == 7) ? 65536 - : 32768;*/ + return ( + (!psz && !sblk) ? 0 + : (psz <= 2) ? (0x200 << psz) + : (sblk == 1 || psz == 3) ? 4096 + : (sblk == 2 || psz == 4) ? 8192 + : (sblk <= 4 || psz == 5) ? 16384 + : (sblk >= 9 && psz == 7) ? 65536 + : 32768 + ) - eeprom_exclude_size; } +*/ uint32_t PAGE_SIZE; uint32_t ROW_SIZE; @@ -99,8 +103,7 @@ bool PersistentStore::access_finish() { volatile uint32_t *dst_addr = (volatile uint32_t *) &flashdata; uint32_t *pointer = (uint32_t *) buffer; - for (uint32_t i = 0; i < TOTAL_FLASH_SIZE; i+=4) { - + for (uint32_t i = 0; i < TOTAL_FLASH_SIZE; i += 4) { *dst_addr = (uint32_t) *pointer; pointer++; dst_addr ++; @@ -120,7 +123,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui if (!hasWritten) { // init temp buffer buffer = (uint8_t *) malloc(MARLIN_EEPROM_SIZE); - hasWritten=true; + hasWritten = true; } memcpy(buffer+pos,value,size); @@ -132,7 +135,7 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t volatile uint8_t *dst_addr = (volatile uint8_t *) &flashdata; dst_addr += pos; - memcpy(value,(const void *) dst_addr,size); + memcpy(value, (const void *)dst_addr, size); pos += size; return false; } diff --git a/Marlin/src/HAL/SAMD21/endstop_interrupts.h b/Marlin/src/HAL/SAMD21/endstop_interrupts.h index d8711aa01870..1459ae9e40e3 100644 --- a/Marlin/src/HAL/SAMD21/endstop_interrupts.h +++ b/Marlin/src/HAL/SAMD21/endstop_interrupts.h @@ -54,30 +54,34 @@ #include "../../module/endstops.h" #define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2)) -#define MATCH_X_MAX_EILINE(P) TERN0(HAS_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN)) -#define MATCH_X_MIN_EILINE(P) TERN0(HAS_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN)) -#define MATCH_Y_MAX_EILINE(P) TERN0(HAS_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN)) -#define MATCH_Y_MIN_EILINE(P) TERN0(HAS_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN)) -#define MATCH_Z_MAX_EILINE(P) TERN0(HAS_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN)) -#define MATCH_Z_MIN_EILINE(P) TERN0(HAS_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN)) -#define MATCH_I_MAX_EILINE(P) TERN0(HAS_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN)) -#define MATCH_I_MIN_EILINE(P) TERN0(HAS_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN)) -#define MATCH_J_MAX_EILINE(P) TERN0(HAS_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN)) -#define MATCH_J_MIN_EILINE(P) TERN0(HAS_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN)) -#define MATCH_K_MAX_EILINE(P) TERN0(HAS_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN)) -#define MATCH_K_MIN_EILINE(P) TERN0(HAS_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN)) -#define MATCH_U_MAX_EILINE(P) TERN0(HAS_U_MAX, DEFER4(MATCH_EILINE)(P, U_MAX_PIN)) -#define MATCH_U_MIN_EILINE(P) TERN0(HAS_U_MIN, DEFER4(MATCH_EILINE)(P, U_MIN_PIN)) -#define MATCH_V_MAX_EILINE(P) TERN0(HAS_V_MAX, DEFER4(MATCH_EILINE)(P, V_MAX_PIN)) -#define MATCH_V_MIN_EILINE(P) TERN0(HAS_V_MIN, DEFER4(MATCH_EILINE)(P, V_MIN_PIN)) -#define MATCH_W_MAX_EILINE(P) TERN0(HAS_W_MAX, DEFER4(MATCH_EILINE)(P, W_MAX_PIN)) -#define MATCH_W_MIN_EILINE(P) TERN0(HAS_W_MIN, DEFER4(MATCH_EILINE)(P, W_MIN_PIN)) -#define MATCH_Z2_MAX_EILINE(P) TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN)) -#define MATCH_Z2_MIN_EILINE(P) TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN)) -#define MATCH_Z3_MAX_EILINE(P) TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN)) -#define MATCH_Z3_MIN_EILINE(P) TERN0(HAS_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN)) -#define MATCH_Z4_MAX_EILINE(P) TERN0(HAS_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN)) -#define MATCH_Z4_MIN_EILINE(P) TERN0(HAS_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN)) +#define MATCH_X_MAX_EILINE(P) TERN0(USE_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN)) +#define MATCH_X_MIN_EILINE(P) TERN0(USE_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN)) +#define MATCH_Y_MAX_EILINE(P) TERN0(USE_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN)) +#define MATCH_Y_MIN_EILINE(P) TERN0(USE_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN)) +#define MATCH_Z_MAX_EILINE(P) TERN0(USE_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN)) +#define MATCH_Z_MIN_EILINE(P) TERN0(USE_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN)) +#define MATCH_I_MAX_EILINE(P) TERN0(USE_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN)) +#define MATCH_I_MIN_EILINE(P) TERN0(USE_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN)) +#define MATCH_J_MAX_EILINE(P) TERN0(USE_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN)) +#define MATCH_J_MIN_EILINE(P) TERN0(USE_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN)) +#define MATCH_K_MAX_EILINE(P) TERN0(USE_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN)) +#define MATCH_K_MIN_EILINE(P) TERN0(USE_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN)) +#define MATCH_U_MAX_EILINE(P) TERN0(USE_U_MAX, DEFER4(MATCH_EILINE)(P, U_MAX_PIN)) +#define MATCH_U_MIN_EILINE(P) TERN0(USE_U_MIN, DEFER4(MATCH_EILINE)(P, U_MIN_PIN)) +#define MATCH_V_MAX_EILINE(P) TERN0(USE_V_MAX, DEFER4(MATCH_EILINE)(P, V_MAX_PIN)) +#define MATCH_V_MIN_EILINE(P) TERN0(USE_V_MIN, DEFER4(MATCH_EILINE)(P, V_MIN_PIN)) +#define MATCH_W_MAX_EILINE(P) TERN0(USE_W_MAX, DEFER4(MATCH_EILINE)(P, W_MAX_PIN)) +#define MATCH_W_MIN_EILINE(P) TERN0(USE_W_MIN, DEFER4(MATCH_EILINE)(P, W_MIN_PIN)) +#define MATCH_X2_MAX_EILINE(P) TERN0(USE_X2_MAX, DEFER4(MATCH_EILINE)(P, X2_MAX_PIN)) +#define MATCH_X2_MIN_EILINE(P) TERN0(USE_X2_MIN, DEFER4(MATCH_EILINE)(P, X2_MIN_PIN)) +#define MATCH_Y2_MAX_EILINE(P) TERN0(USE_Y2_MAX, DEFER4(MATCH_EILINE)(P, Y2_MAX_PIN)) +#define MATCH_Y2_MIN_EILINE(P) TERN0(USE_Y2_MIN, DEFER4(MATCH_EILINE)(P, Y2_MIN_PIN)) +#define MATCH_Z2_MAX_EILINE(P) TERN0(USE_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN)) +#define MATCH_Z2_MIN_EILINE(P) TERN0(USE_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN)) +#define MATCH_Z3_MAX_EILINE(P) TERN0(USE_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN)) +#define MATCH_Z3_MIN_EILINE(P) TERN0(USE_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN)) +#define MATCH_Z4_MAX_EILINE(P) TERN0(USE_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN)) +#define MATCH_Z4_MIN_EILINE(P) TERN0(USE_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN)) #define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE_PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN)) #define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1 \ @@ -90,6 +94,8 @@ && !MATCH_U_MAX_EILINE(P) && !MATCH_U_MIN_EILINE(P) \ && !MATCH_V_MAX_EILINE(P) && !MATCH_V_MIN_EILINE(P) \ && !MATCH_W_MAX_EILINE(P) && !MATCH_W_MIN_EILINE(P) \ + && !MATCH_X2_MAX_EILINE(P) && !MATCH_X2_MIN_EILINE(P) \ + && !MATCH_Y2_MAX_EILINE(P) && !MATCH_Y2_MIN_EILINE(P) \ && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \ && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \ && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \ @@ -100,153 +106,177 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) - #if HAS_X_MAX + #if USE_X_MAX #if !AVAILABLE_EILINE(X_MAX_PIN) - #error "X_MAX_PIN has no EXTINT line available." + #error "X_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(X_MAX_PIN); #endif - #if HAS_X_MIN + #if USE_X_MIN #if !AVAILABLE_EILINE(X_MIN_PIN) - #error "X_MIN_PIN has no EXTINT line available." + #error "X_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(X_MIN_PIN); #endif - #if HAS_Y_MAX + #if USE_Y_MAX #if !AVAILABLE_EILINE(Y_MAX_PIN) - #error "Y_MAX_PIN has no EXTINT line available." + #error "Y_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Y_MAX_PIN); #endif - #if HAS_Y_MIN + #if USE_Y_MIN #if !AVAILABLE_EILINE(Y_MIN_PIN) - #error "Y_MIN_PIN has no EXTINT line available." + #error "Y_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Y_MIN_PIN); #endif - #if HAS_Z_MAX + #if USE_Z_MAX #if !AVAILABLE_EILINE(Z_MAX_PIN) - #error "Z_MAX_PIN has no EXTINT line available." + #error "Z_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MAX_PIN); #endif - #if HAS_Z_MIN + #if USE_Z_MIN #if !AVAILABLE_EILINE(Z_MIN_PIN) - #error "Z_MIN_PIN has no EXTINT line available." + #error "Z_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MIN_PIN); #endif - #if HAS_Z2_MAX + #if USE_X2_MAX + #if !AVAILABLE_EILINE(X2_MAX_PIN) + #error "X2_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(X2_MAX_PIN); + #endif + #if USE_X2_MIN + #if !AVAILABLE_EILINE(X2_MIN_PIN) + #error "X2_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(X2_MIN_PIN); + #endif + #if USE_Y2_MAX + #if !AVAILABLE_EILINE(Y2_MAX_PIN) + #error "Y2_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Y2_MAX_PIN); + #endif + #if USE_Y2_MIN + #if !AVAILABLE_EILINE(Y2_MIN_PIN) + #error "Y2_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." + #endif + _ATTACH(Y2_MIN_PIN); + #endif + #if USE_Z2_MAX #if !AVAILABLE_EILINE(Z2_MAX_PIN) - #error "Z2_MAX_PIN has no EXTINT line available." + #error "Z2_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z2_MAX_PIN); #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN #if !AVAILABLE_EILINE(Z2_MIN_PIN) - #error "Z2_MIN_PIN has no EXTINT line available." + #error "Z2_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z2_MIN_PIN); #endif - #if HAS_Z3_MAX + #if USE_Z3_MAX #if !AVAILABLE_EILINE(Z3_MAX_PIN) - #error "Z3_MAX_PIN has no EXTINT line available." + #error "Z3_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z3_MAX_PIN); #endif - #if HAS_Z3_MIN + #if USE_Z3_MIN #if !AVAILABLE_EILINE(Z3_MIN_PIN) - #error "Z3_MIN_PIN has no EXTINT line available." + #error "Z3_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z3_MIN_PIN); #endif - #if HAS_Z4_MAX + #if USE_Z4_MAX #if !AVAILABLE_EILINE(Z4_MAX_PIN) - #error "Z4_MAX_PIN has no EXTINT line available." + #error "Z4_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z4_MAX_PIN); #endif - #if HAS_Z4_MIN + #if USE_Z4_MIN #if !AVAILABLE_EILINE(Z4_MIN_PIN) - #error "Z4_MIN_PIN has no EXTINT line available." + #error "Z4_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z4_MIN_PIN); #endif #if HAS_Z_MIN_PROBE_PIN #if !AVAILABLE_EILINE(Z_MIN_PROBE_PIN) - #error "Z_MIN_PROBE_PIN has no EXTINT line available." + #error "Z_MIN_PROBE_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MIN_PROBE_PIN); #endif - #if HAS_I_MAX + #if USE_I_MAX #if !AVAILABLE_EILINE(I_MAX_PIN) - #error "I_MAX_PIN has no EXTINT line available." + #error "I_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_I_MIN + #if USE_I_MIN #if !AVAILABLE_EILINE(I_MIN_PIN) - #error "I_MIN_PIN has no EXTINT line available." + #error "I_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_J_MAX + #if USE_J_MAX #if !AVAILABLE_EILINE(J_MAX_PIN) - #error "J_MAX_PIN has no EXTINT line available." + #error "J_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_J_MIN + #if USE_J_MIN #if !AVAILABLE_EILINE(J_MIN_PIN) - #error "J_MIN_PIN has no EXTINT line available." + #error "J_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_K_MAX + #if USE_K_MAX #if !AVAILABLE_EILINE(K_MAX_PIN) - #error "K_MAX_PIN has no EXTINT line available." + #error "K_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_K_MIN + #if USE_K_MIN #if !AVAILABLE_EILINE(K_MIN_PIN) - #error "K_MIN_PIN has no EXTINT line available." + #error "K_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_U_MAX + #if USE_U_MAX #if !AVAILABLE_EILINE(U_MAX_PIN) - #error "U_MAX_PIN has no EXTINT line available." + #error "U_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(U_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_U_MIN + #if USE_U_MIN #if !AVAILABLE_EILINE(U_MIN_PIN) - #error "U_MIN_PIN has no EXTINT line available." + #error "U_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(U_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_V_MAX + #if USE_V_MAX #if !AVAILABLE_EILINE(V_MAX_PIN) - #error "V_MAX_PIN has no EXTINT line available." + #error "V_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(V_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_V_MIN + #if USE_V_MIN #if !AVAILABLE_EILINE(V_MIN_PIN) - #error "V_MIN_PIN has no EXTINT line available." + #error "V_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(V_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_W_MAX + #if USE_W_MAX #if !AVAILABLE_EILINE(W_MAX_PIN) - #error "W_MAX_PIN has no EXTINT line available." + #error "W_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(W_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_W_MIN + #if USE_W_MIN #if !AVAILABLE_EILINE(W_MIN_PIN) - #error "W_MIN_PIN has no EXTINT line available." + #error "W_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(W_MIN_PIN, endstop_ISR, CHANGE); #endif diff --git a/Marlin/src/HAL/SAMD21/fastio.h b/Marlin/src/HAL/SAMD21/fastio.h index df907ff7ec6c..471e8b62abc7 100644 --- a/Marlin/src/HAL/SAMD21/fastio.h +++ b/Marlin/src/HAL/SAMD21/fastio.h @@ -129,7 +129,7 @@ * Added as necessary or if I feel like it- not a comprehensive list! */ -/* +/** * Some of these share the same source and so can't be used in the same time */ #define PWM_PIN(P) (WITHIN(P, 2, 13) || WITHIN(P, 22, 23) || WITHIN(P, 44, 45) || P == 48) diff --git a/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h b/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h index 9d58e454327f..570baf7e95e5 100644 --- a/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h @@ -19,5 +19,4 @@ * along with this program. If not, see . * */ - #pragma once diff --git a/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h index 7315dc12a779..87d3350c9450 100644 --- a/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h +++ b/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h @@ -28,6 +28,6 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/SAMD21/inc/SanityCheck.h b/Marlin/src/HAL/SAMD21/inc/SanityCheck.h index 8bf052e3bb15..83fafc968924 100644 --- a/Marlin/src/HAL/SAMD21/inc/SanityCheck.h +++ b/Marlin/src/HAL/SAMD21/inc/SanityCheck.h @@ -41,8 +41,8 @@ #error "EMERGENCY_PARSER is not yet implemented for SAMD21. Disable EMERGENCY_PARSER to continue." #endif -#if ENABLED(SDIO_SUPPORT) - #error "SDIO_SUPPORT is not supported on SAMD21." +#if ENABLED(ONBOARD_SDIO) + #error "ONBOARD_SDIO is not supported on SAMD21." #endif #if ENABLED(FAST_PWM_FAN) diff --git a/Marlin/src/HAL/SAMD21/timers.cpp b/Marlin/src/HAL/SAMD21/timers.cpp index 982eebc54951..b5f1d4f7bd80 100644 --- a/Marlin/src/HAL/SAMD21/timers.cpp +++ b/Marlin/src/HAL/SAMD21/timers.cpp @@ -135,7 +135,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { } else if (timer_config[timer_num].type==TimerType::tcc) { - + Tcc * const tc = timer_config[timer_num].pTcc; PM->APBCMASK.reg |= PM_APBCMASK_TCC0; diff --git a/Marlin/src/HAL/SAMD21/u8g/u8g_com_HAL_samd21_shared_hw_spi.cpp b/Marlin/src/HAL/SAMD21/u8g/u8g_com_HAL_samd21_shared_hw_spi.cpp index 02dc77229676..2e2b0d8f8d22 100644 --- a/Marlin/src/HAL/SAMD21/u8g/u8g_com_HAL_samd21_shared_hw_spi.cpp +++ b/Marlin/src/HAL/SAMD21/u8g/u8g_com_HAL_samd21_shared_hw_spi.cpp @@ -60,13 +60,17 @@ #ifdef __SAMD21__ +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_MARLINUI_U8GLIB + #include #include "SPI.h" #include "../../shared/HAL_SPI.h" #ifndef LCD_SPI_SPEED - #define LCD_SPI_SPEED SPI_QUARTER_SPEED + #define LCD_SPI_SPEED SPI_HALF_SPEED #endif void u8g_SetPIOutput(u8g_t *u8g, uint8_t pin_index) { @@ -81,8 +85,6 @@ void u8g_SetPILevel(u8g_t *u8g, uint8_t pin_index, uint8_t level) { uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { - static SPISettings lcdSPIConfig; - switch (msg) { case U8G_COM_MSG_STOP: break; @@ -95,7 +97,6 @@ uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val u8g_SetPILevel(u8g, U8G_PI_CS, LOW); spiBegin(); - lcdSPIConfig = SPISettings(900000, MSBFIRST, SPI_MODE0); u8g->pin_list[U8G_PI_A0_STATE] = 0; break; @@ -113,7 +114,7 @@ uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val break; case U8G_COM_MSG_WRITE_BYTE: - SPI.beginTransaction(lcdSPIConfig); + spiBeginTransaction(LCD_SPI_SPEED, MSBFIRST, SPI_MODE0); if (u8g->pin_list[U8G_PI_A0_STATE] == 0) { // command SPI.transfer(0x0f8); u8g->pin_list[U8G_PI_A0_STATE] = 2; @@ -128,7 +129,7 @@ uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val break; case U8G_COM_MSG_WRITE_SEQ: - SPI.beginTransaction(lcdSPIConfig); + spiBeginTransaction(LCD_SPI_SPEED, MSBFIRST, SPI_MODE0); if (u8g->pin_list[U8G_PI_A0_STATE] == 0 ) { // command SPI.transfer(0x0f8); u8g->pin_list[U8G_PI_A0_STATE] = 2; @@ -151,4 +152,6 @@ uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val return 1; } +#endif // HAS_MARLINUI_U8GLIB + #endif // __SAMD21__ diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index 8c102b643da8..308b45ebe76f 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -47,24 +47,27 @@ #endif #endif -#define GET_TEMP_0_ADC() TERN(HAS_TEMP_ADC_0, PIN_TO_ADC(TEMP_0_PIN), -1) -#define GET_TEMP_1_ADC() TERN(HAS_TEMP_ADC_1, PIN_TO_ADC(TEMP_1_PIN), -1) -#define GET_TEMP_2_ADC() TERN(HAS_TEMP_ADC_2, PIN_TO_ADC(TEMP_2_PIN), -1) -#define GET_TEMP_3_ADC() TERN(HAS_TEMP_ADC_3, PIN_TO_ADC(TEMP_3_PIN), -1) -#define GET_TEMP_4_ADC() TERN(HAS_TEMP_ADC_4, PIN_TO_ADC(TEMP_4_PIN), -1) -#define GET_TEMP_5_ADC() TERN(HAS_TEMP_ADC_5, PIN_TO_ADC(TEMP_5_PIN), -1) -#define GET_TEMP_6_ADC() TERN(HAS_TEMP_ADC_6, PIN_TO_ADC(TEMP_6_PIN), -1) -#define GET_TEMP_7_ADC() TERN(HAS_TEMP_ADC_7, PIN_TO_ADC(TEMP_7_PIN), -1) -#define GET_BED_ADC() TERN(HAS_TEMP_ADC_BED, PIN_TO_ADC(TEMP_BED_PIN), -1) -#define GET_CHAMBER_ADC() TERN(HAS_TEMP_ADC_CHAMBER, PIN_TO_ADC(TEMP_CHAMBER_PIN), -1) -#define GET_PROBE_ADC() TERN(HAS_TEMP_ADC_PROBE, PIN_TO_ADC(TEMP_PROBE_PIN), -1) -#define GET_COOLER_ADC() TERN(HAS_TEMP_ADC_COOLER, PIN_TO_ADC(TEMP_COOLER_PIN), -1) -#define GET_BOARD_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1) -#define GET_FILAMENT_WIDTH_ADC() TERN(FILAMENT_WIDTH_SENSOR, PIN_TO_ADC(FILWIDTH_PIN), -1) -#define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1) -#define GET_JOY_ADC_X() TERN(HAS_JOY_ADC_X, PIN_TO_ADC(JOY_X_PIN), -1) -#define GET_JOY_ADC_Y() TERN(HAS_JOY_ADC_Y, PIN_TO_ADC(JOY_Y_PIN), -1) -#define GET_JOY_ADC_Z() TERN(HAS_JOY_ADC_Z, PIN_TO_ADC(JOY_Z_PIN), -1) +#define GET_TEMP_0_ADC() TERN(HAS_TEMP_ADC_0, PIN_TO_ADC(TEMP_0_PIN), -1) +#define GET_TEMP_1_ADC() TERN(HAS_TEMP_ADC_1, PIN_TO_ADC(TEMP_1_PIN), -1) +#define GET_TEMP_2_ADC() TERN(HAS_TEMP_ADC_2, PIN_TO_ADC(TEMP_2_PIN), -1) +#define GET_TEMP_3_ADC() TERN(HAS_TEMP_ADC_3, PIN_TO_ADC(TEMP_3_PIN), -1) +#define GET_TEMP_4_ADC() TERN(HAS_TEMP_ADC_4, PIN_TO_ADC(TEMP_4_PIN), -1) +#define GET_TEMP_5_ADC() TERN(HAS_TEMP_ADC_5, PIN_TO_ADC(TEMP_5_PIN), -1) +#define GET_TEMP_6_ADC() TERN(HAS_TEMP_ADC_6, PIN_TO_ADC(TEMP_6_PIN), -1) +#define GET_TEMP_7_ADC() TERN(HAS_TEMP_ADC_7, PIN_TO_ADC(TEMP_7_PIN), -1) +#define GET_BED_ADC() TERN(HAS_TEMP_ADC_BED, PIN_TO_ADC(TEMP_BED_PIN), -1) +#define GET_CHAMBER_ADC() TERN(HAS_TEMP_ADC_CHAMBER, PIN_TO_ADC(TEMP_CHAMBER_PIN), -1) +#define GET_PROBE_ADC() TERN(HAS_TEMP_ADC_PROBE, PIN_TO_ADC(TEMP_PROBE_PIN), -1) +#define GET_COOLER_ADC() TERN(HAS_TEMP_ADC_COOLER, PIN_TO_ADC(TEMP_COOLER_PIN), -1) +#define GET_BOARD_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1) +#define GET_SOC_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1) +#define GET_FILAMENT_WIDTH_ADC() TERN(FILAMENT_WIDTH_SENSOR, PIN_TO_ADC(FILWIDTH_PIN), -1) +#define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1) +#define GET_JOY_ADC_X() TERN(HAS_JOY_ADC_X, PIN_TO_ADC(JOY_X_PIN), -1) +#define GET_JOY_ADC_Y() TERN(HAS_JOY_ADC_Y, PIN_TO_ADC(JOY_Y_PIN), -1) +#define GET_JOY_ADC_Z() TERN(HAS_JOY_ADC_Z, PIN_TO_ADC(JOY_Z_PIN), -1) +#define GET_POWERMON_ADC_CURRENT() TERN(POWER_MONITOR_CURRENT, PIN_TO_ADC(POWER_MONITOR_CURRENT_PIN), -1) +#define GET_POWERMON_ADC_VOLTS() TERN(POWER_MONITOR_VOLTAGE, PIN_TO_ADC(POWER_MONITOR_VOLTAGE_PIN), -1) #define IS_ADC_REQUIRED(n) ( \ GET_TEMP_0_ADC() == n || GET_TEMP_1_ADC() == n || GET_TEMP_2_ADC() == n || GET_TEMP_3_ADC() == n \ @@ -77,6 +80,7 @@ || GET_FILAMENT_WIDTH_ADC() == n \ || GET_BUTTONS_ADC() == n \ || GET_JOY_ADC_X() == n || GET_JOY_ADC_Y() == n || GET_JOY_ADC_Z() == n \ + || GET_POWERMON_ADC_CURRENT() == n || GET_POWERMON_ADC_VOLTS() == n \ ) #if IS_ADC_REQUIRED(0) @@ -151,6 +155,15 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 0 JOY_Z, #endif + #if GET_POWERMON_ADC_CURRENT() == 0 + POWERMON_CURRENT, + #endif + #if GET_POWERMON_ADC_VOLTS() == 0 + POWERMON_VOLTAGE, + #endif + + // Indexes for ADC1 after those for ADC0 + #if GET_TEMP_0_ADC() == 1 TEMP_0, #endif @@ -205,6 +218,12 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 1 JOY_Z, #endif + #if GET_POWERMON_ADC_CURRENT() == 1 + POWERMON_CURRENT, + #endif + #if GET_POWERMON_ADC_VOLTS() == 1 + POWERMON_VOLTAGE, + #endif ADC_COUNT }; @@ -318,7 +337,15 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 0 JOY_Z_PIN, #endif - // ADC1 pins + #if GET_POWERMON_ADC_CURRENT() == 0 + POWER_MONITOR_CURRENT_PIN, + #endif + #if GET_POWERMON_ADC_VOLTS() == 0 + POWER_MONITOR_VOLTAGE_PIN, + #endif + + // Pins for ADC1 after ADC0 + #if GET_TEMP_0_ADC() == 1 TEMP_0_PIN, #endif @@ -373,6 +400,12 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 1 JOY_Z_PIN, #endif + #if GET_POWERMON_ADC_CURRENT() == 1 + POWER_MONITOR_CURRENT_PIN, + #endif + #if GET_POWERMON_ADC_VOLTS() == 1 + POWER_MONITOR_VOLTAGE_PIN, + #endif }; static uint16_t adc_results[ADC_COUNT]; @@ -435,6 +468,12 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 0 { PIN_TO_INPUTCTRL(JOY_Z_PIN) }, #endif + #if GET_POWERMON_ADC_CURRENT() == 0 + { PIN_TO_INPUTCTRL(POWER_MONITOR_CURRENT_PIN) }, + #endif + #if GET_POWERMON_ADC_VOLTS() == 0 + { PIN_TO_INPUTCTRL(POWER_MONITOR_VOLTAGE_PIN) }, + #endif }; #define ADC0_AINCOUNT COUNT(adc0_dma_regs_list) @@ -498,6 +537,12 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 1 { PIN_TO_INPUTCTRL(JOY_Z_PIN) }, #endif + #if GET_POWERMON_ADC_CURRENT() == 1 + { PIN_TO_INPUTCTRL(POWER_MONITOR_CURRENT_PIN) }, + #endif + #if GET_POWERMON_ADC_VOLTS() == 1 + { PIN_TO_INPUTCTRL(POWER_MONITOR_VOLTAGE_PIN) }, + #endif }; #define ADC1_AINCOUNT COUNT(adc1_dma_regs_list) @@ -602,7 +647,7 @@ void MarlinHAL::dma_init() { // HAL initialization task void MarlinHAL::init() { TERN_(DMA_IS_REQUIRED, dma_init()); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA #if HAS_SD_DETECT && SD_CONNECTION_IS(ONBOARD) SET_INPUT_PULLUP(SD_DETECT_PIN); #endif @@ -650,10 +695,10 @@ void MarlinHAL::adc_init() { #if ADC_IS_REQUIRED memset(adc_results, 0xFF, sizeof(adc_results)); // Fill result with invalid values - LOOP_L_N(pi, COUNT(adc_pins)) + for (uint8_t pi = 0; pi < COUNT(adc_pins); ++pi) pinPeripheral(adc_pins[pi], PIO_ANALOG); - LOOP_S_LE_N(ai, FIRST_ADC, LAST_ADC) { + for (uint8_t ai = FIRST_ADC; ai <= LAST_ADC; ++ai) { Adc* adc = ((Adc*[])ADC_INSTS)[ai]; // ADC clock setup @@ -685,7 +730,7 @@ void MarlinHAL::adc_init() { void MarlinHAL::adc_start(const pin_t pin) { #if ADC_IS_REQUIRED - LOOP_L_N(pi, COUNT(adc_pins)) + for (uint8_t pi = 0; pi < COUNT(adc_pins); ++pi) if (pin == adc_pins[pi]) { adc_result = adc_results[pi]; return; } #endif diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index fe29d6c7f42d..c96401fd9750 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -112,7 +112,7 @@ typedef Servo hal_servo_t; // //#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values. -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 10 // ... 12 // diff --git a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp index 58fdfe9499a1..63d3971965c9 100644 --- a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp +++ b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp @@ -44,7 +44,7 @@ // Public functions // -------------------------------------------------------------------------- -#if EITHER(SOFTWARE_SPI, FORCE_SOFT_SPI) +#if ANY(SOFTWARE_SPI, FORCE_SOFT_SPI) // ------------------------ // Software SPI diff --git a/Marlin/src/HAL/SAMD51/Servo.cpp b/Marlin/src/HAL/SAMD51/Servo.cpp index e533eee30155..059955e11aac 100644 --- a/Marlin/src/HAL/SAMD51/Servo.cpp +++ b/Marlin/src/HAL/SAMD51/Servo.cpp @@ -54,7 +54,6 @@ #define TIMER_TCCHANNEL(t) ((t) & 1) #define TC_COUNTER_START_VAL 0xFFFF - 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() { diff --git a/Marlin/src/HAL/SAMD51/endstop_interrupts.h b/Marlin/src/HAL/SAMD51/endstop_interrupts.h index e0e811c3a018..62a49e5f206f 100644 --- a/Marlin/src/HAL/SAMD51/endstop_interrupts.h +++ b/Marlin/src/HAL/SAMD51/endstop_interrupts.h @@ -53,31 +53,35 @@ #include "../../module/endstops.h" #define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2)) -#define MATCH_X_MAX_EILINE(P) TERN0(HAS_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN)) -#define MATCH_X_MIN_EILINE(P) TERN0(HAS_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN)) -#define MATCH_Y_MAX_EILINE(P) TERN0(HAS_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN)) -#define MATCH_Y_MIN_EILINE(P) TERN0(HAS_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN)) -#define MATCH_Z_MAX_EILINE(P) TERN0(HAS_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN)) -#define MATCH_Z_MIN_EILINE(P) TERN0(HAS_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN)) -#define MATCH_I_MAX_EILINE(P) TERN0(HAS_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN)) -#define MATCH_I_MIN_EILINE(P) TERN0(HAS_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN)) -#define MATCH_J_MAX_EILINE(P) TERN0(HAS_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN)) -#define MATCH_J_MIN_EILINE(P) TERN0(HAS_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN)) -#define MATCH_K_MAX_EILINE(P) TERN0(HAS_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN)) -#define MATCH_K_MIN_EILINE(P) TERN0(HAS_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN)) -#define MATCH_U_MAX_EILINE(P) TERN0(HAS_U_MAX, DEFER4(MATCH_EILINE)(P, U_MAX_PIN)) -#define MATCH_U_MIN_EILINE(P) TERN0(HAS_U_MIN, DEFER4(MATCH_EILINE)(P, U_MIN_PIN)) -#define MATCH_V_MAX_EILINE(P) TERN0(HAS_V_MAX, DEFER4(MATCH_EILINE)(P, V_MAX_PIN)) -#define MATCH_V_MIN_EILINE(P) TERN0(HAS_V_MIN, DEFER4(MATCH_EILINE)(P, V_MIN_PIN)) -#define MATCH_W_MAX_EILINE(P) TERN0(HAS_W_MAX, DEFER4(MATCH_EILINE)(P, W_MAX_PIN)) -#define MATCH_W_MIN_EILINE(P) TERN0(HAS_W_MIN, DEFER4(MATCH_EILINE)(P, W_MIN_PIN)) -#define MATCH_Z2_MAX_EILINE(P) TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN)) -#define MATCH_Z2_MIN_EILINE(P) TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN)) -#define MATCH_Z3_MAX_EILINE(P) TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN)) -#define MATCH_Z3_MIN_EILINE(P) TERN0(HAS_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN)) -#define MATCH_Z4_MAX_EILINE(P) TERN0(HAS_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN)) -#define MATCH_Z4_MIN_EILINE(P) TERN0(HAS_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN)) -#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE_PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN)) +#define MATCH_X_MAX_EILINE(P) TERN0(USE_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN)) +#define MATCH_X_MIN_EILINE(P) TERN0(USE_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN)) +#define MATCH_Y_MAX_EILINE(P) TERN0(USE_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN)) +#define MATCH_Y_MIN_EILINE(P) TERN0(USE_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN)) +#define MATCH_Z_MAX_EILINE(P) TERN0(USE_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN)) +#define MATCH_Z_MIN_EILINE(P) TERN0(USE_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN)) +#define MATCH_I_MAX_EILINE(P) TERN0(USE_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN)) +#define MATCH_I_MIN_EILINE(P) TERN0(USE_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN)) +#define MATCH_J_MAX_EILINE(P) TERN0(USE_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN)) +#define MATCH_J_MIN_EILINE(P) TERN0(USE_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN)) +#define MATCH_K_MAX_EILINE(P) TERN0(USE_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN)) +#define MATCH_K_MIN_EILINE(P) TERN0(USE_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN)) +#define MATCH_U_MAX_EILINE(P) TERN0(USE_U_MAX, DEFER4(MATCH_EILINE)(P, U_MAX_PIN)) +#define MATCH_U_MIN_EILINE(P) TERN0(USE_U_MIN, DEFER4(MATCH_EILINE)(P, U_MIN_PIN)) +#define MATCH_V_MAX_EILINE(P) TERN0(USE_V_MAX, DEFER4(MATCH_EILINE)(P, V_MAX_PIN)) +#define MATCH_V_MIN_EILINE(P) TERN0(USE_V_MIN, DEFER4(MATCH_EILINE)(P, V_MIN_PIN)) +#define MATCH_W_MAX_EILINE(P) TERN0(USE_W_MAX, DEFER4(MATCH_EILINE)(P, W_MAX_PIN)) +#define MATCH_W_MIN_EILINE(P) TERN0(USE_W_MIN, DEFER4(MATCH_EILINE)(P, W_MIN_PIN)) +#define MATCH_X2_MAX_EILINE(P) TERN0(USE_X2_MAX, DEFER4(MATCH_EILINE)(P, X2_MAX_PIN)) +#define MATCH_X2_MIN_EILINE(P) TERN0(USE_X2_MIN, DEFER4(MATCH_EILINE)(P, X2_MIN_PIN)) +#define MATCH_Y2_MAX_EILINE(P) TERN0(USE_Y2_MAX, DEFER4(MATCH_EILINE)(P, Y2_MAX_PIN)) +#define MATCH_Y2_MIN_EILINE(P) TERN0(USE_Y2_MIN, DEFER4(MATCH_EILINE)(P, Y2_MIN_PIN)) +#define MATCH_Z2_MAX_EILINE(P) TERN0(USE_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN)) +#define MATCH_Z2_MIN_EILINE(P) TERN0(USE_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN)) +#define MATCH_Z3_MAX_EILINE(P) TERN0(USE_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN)) +#define MATCH_Z3_MIN_EILINE(P) TERN0(USE_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN)) +#define MATCH_Z4_MAX_EILINE(P) TERN0(USE_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN)) +#define MATCH_Z4_MIN_EILINE(P) TERN0(USE_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN)) +#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE+PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN)) #define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1 \ && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \ @@ -89,6 +93,8 @@ && !MATCH_U_MAX_EILINE(P) && !MATCH_U_MIN_EILINE(P) \ && !MATCH_V_MAX_EILINE(P) && !MATCH_V_MIN_EILINE(P) \ && !MATCH_W_MAX_EILINE(P) && !MATCH_W_MIN_EILINE(P) \ + && !MATCH_X2_MAX_EILINE(P) && !MATCH_X2_MIN_EILINE(P) \ + && !MATCH_Y2_MAX_EILINE(P) && !MATCH_Y2_MIN_EILINE(P) \ && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \ && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \ && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \ @@ -99,153 +105,153 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) - #if HAS_X_MAX + #if USE_X_MAX #if !AVAILABLE_EILINE(X_MAX_PIN) - #error "X_MAX_PIN has no EXTINT line available." + #error "X_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(X_MAX_PIN); #endif - #if HAS_X_MIN + #if USE_X_MIN #if !AVAILABLE_EILINE(X_MIN_PIN) - #error "X_MIN_PIN has no EXTINT line available." + #error "X_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(X_MIN_PIN); #endif - #if HAS_Y_MAX + #if USE_Y_MAX #if !AVAILABLE_EILINE(Y_MAX_PIN) - #error "Y_MAX_PIN has no EXTINT line available." + #error "Y_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Y_MAX_PIN); #endif - #if HAS_Y_MIN + #if USE_Y_MIN #if !AVAILABLE_EILINE(Y_MIN_PIN) - #error "Y_MIN_PIN has no EXTINT line available." + #error "Y_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Y_MIN_PIN); #endif - #if HAS_Z_MAX + #if USE_Z_MAX #if !AVAILABLE_EILINE(Z_MAX_PIN) - #error "Z_MAX_PIN has no EXTINT line available." + #error "Z_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MAX_PIN); #endif - #if HAS_Z_MIN + #if USE_Z_MIN #if !AVAILABLE_EILINE(Z_MIN_PIN) - #error "Z_MIN_PIN has no EXTINT line available." + #error "Z_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MIN_PIN); #endif - #if HAS_Z2_MAX + #if USE_Z2_MAX #if !AVAILABLE_EILINE(Z2_MAX_PIN) - #error "Z2_MAX_PIN has no EXTINT line available." + #error "Z2_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z2_MAX_PIN); #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN #if !AVAILABLE_EILINE(Z2_MIN_PIN) - #error "Z2_MIN_PIN has no EXTINT line available." + #error "Z2_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z2_MIN_PIN); #endif - #if HAS_Z3_MAX + #if USE_Z3_MAX #if !AVAILABLE_EILINE(Z3_MAX_PIN) - #error "Z3_MAX_PIN has no EXTINT line available." + #error "Z3_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z3_MAX_PIN); #endif - #if HAS_Z3_MIN + #if USE_Z3_MIN #if !AVAILABLE_EILINE(Z3_MIN_PIN) - #error "Z3_MIN_PIN has no EXTINT line available." + #error "Z3_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z3_MIN_PIN); #endif - #if HAS_Z4_MAX + #if USE_Z4_MAX #if !AVAILABLE_EILINE(Z4_MAX_PIN) - #error "Z4_MAX_PIN has no EXTINT line available." + #error "Z4_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z4_MAX_PIN); #endif - #if HAS_Z4_MIN + #if USE_Z4_MIN #if !AVAILABLE_EILINE(Z4_MIN_PIN) - #error "Z4_MIN_PIN has no EXTINT line available." + #error "Z4_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z4_MIN_PIN); #endif #if HAS_Z_MIN_PROBE_PIN #if !AVAILABLE_EILINE(Z_MIN_PROBE_PIN) - #error "Z_MIN_PROBE_PIN has no EXTINT line available." + #error "Z_MIN_PROBE_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif _ATTACH(Z_MIN_PROBE_PIN); #endif - #if HAS_I_MAX + #if USE_I_MAX #if !AVAILABLE_EILINE(I_MAX_PIN) - #error "I_MAX_PIN has no EXTINT line available." + #error "I_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_I_MIN + #if USE_I_MIN #if !AVAILABLE_EILINE(I_MIN_PIN) - #error "I_MIN_PIN has no EXTINT line available." + #error "I_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_J_MAX + #if USE_J_MAX #if !AVAILABLE_EILINE(J_MAX_PIN) - #error "J_MAX_PIN has no EXTINT line available." + #error "J_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_J_MIN + #if USE_J_MIN #if !AVAILABLE_EILINE(J_MIN_PIN) - #error "J_MIN_PIN has no EXTINT line available." + #error "J_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_K_MAX + #if USE_K_MAX #if !AVAILABLE_EILINE(K_MAX_PIN) - #error "K_MAX_PIN has no EXTINT line available." + #error "K_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_K_MIN + #if USE_K_MIN #if !AVAILABLE_EILINE(K_MIN_PIN) - #error "K_MIN_PIN has no EXTINT line available." + #error "K_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_U_MAX + #if USE_U_MAX #if !AVAILABLE_EILINE(U_MAX_PIN) - #error "U_MAX_PIN has no EXTINT line available." + #error "U_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(U_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_U_MIN + #if USE_U_MIN #if !AVAILABLE_EILINE(U_MIN_PIN) - #error "U_MIN_PIN has no EXTINT line available." + #error "U_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(U_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_V_MAX + #if USE_V_MAX #if !AVAILABLE_EILINE(V_MAX_PIN) - #error "V_MAX_PIN has no EXTINT line available." + #error "V_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(V_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_V_MIN + #if USE_V_MIN #if !AVAILABLE_EILINE(V_MIN_PIN) - #error "V_MIN_PIN has no EXTINT line available." + #error "V_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(V_MIN_PIN, endstop_ISR, CHANGE); #endif - #if HAS_W_MAX + #if USE_W_MAX #if !AVAILABLE_EILINE(W_MAX_PIN) - #error "W_MAX_PIN has no EXTINT line available." + #error "W_MAX_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(W_MAX_PIN, endstop_ISR, CHANGE); #endif - #if HAS_W_MIN + #if USE_W_MIN #if !AVAILABLE_EILINE(W_MIN_PIN) - #error "W_MIN_PIN has no EXTINT line available." + #error "W_MIN_PIN has no EXTINT line available. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif attachInterrupt(W_MIN_PIN, endstop_ISR, CHANGE); #endif diff --git a/Marlin/src/HAL/SAMD51/fastio.h b/Marlin/src/HAL/SAMD51/fastio.h index 0acf48131796..3d43bdb24d8b 100644 --- a/Marlin/src/HAL/SAMD51/fastio.h +++ b/Marlin/src/HAL/SAMD51/fastio.h @@ -130,7 +130,7 @@ #ifdef ADAFRUIT_GRAND_CENTRAL_M4 - /* + /** * Adafruit Grand Central M4 has a lot of PWMs the availables are listed here. * Some of these share the same source and so can't be used in the same time */ @@ -176,7 +176,7 @@ #define digitalPinToAnalogInput(P) (WITHIN(P, 67, 74) ? (P) - 67 : WITHIN(P, 54, 61) ? 8 + (P) - 54 : WITHIN(P, 12, 13) ? 16 + (P) - 12 : P == 9 ? 18 : -1) - /* + /** * pins */ diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h index ce6d3fdde27f..295596b78b19 100644 --- a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h +++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h @@ -23,6 +23,6 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h index f9ff090f75ae..4719ac6eb8c2 100644 --- a/Marlin/src/HAL/SAMD51/inc/SanityCheck.h +++ b/Marlin/src/HAL/SAMD51/inc/SanityCheck.h @@ -54,8 +54,8 @@ #error "EMERGENCY_PARSER is not yet implemented for SAMD51. Disable EMERGENCY_PARSER to continue." #endif -#if ENABLED(SDIO_SUPPORT) - #error "SDIO_SUPPORT is not supported on SAMD51." +#if ENABLED(ONBOARD_SDIO) + #error "ONBOARD_SDIO is not supported on SAMD51." #endif #if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY diff --git a/Marlin/src/HAL/SAMD51/spi_pins.h b/Marlin/src/HAL/SAMD51/spi_pins.h index f1e4fd430246..2c7cbeb99432 100644 --- a/Marlin/src/HAL/SAMD51/spi_pins.h +++ b/Marlin/src/HAL/SAMD51/spi_pins.h @@ -27,7 +27,7 @@ #ifdef ADAFRUIT_GRAND_CENTRAL_M4 - /* + /** * AGCM4 Default SPI Pins * * SS SCK MISO MOSI diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index aff52f597f4d..610bd0b243bd 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2017 Victor Perez + * + * 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 @@ -70,7 +69,7 @@ void MarlinHAL::init() { constexpr int cpuFreq = F_CPU; UNUSED(cpuFreq); - #if ENABLED(SDSUPPORT) && DISABLED(SDIO_SUPPORT) && (defined(SDSS) && SDSS != -1) + #if HAS_MEDIA && DISABLED(ONBOARD_SDIO) && (defined(SDSS) && SDSS != -1) OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up #endif diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 61569c793738..88cbaa536a5c 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2017 Victor Perez + * + * 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 @@ -56,64 +55,64 @@ #define _MSERIAL(X) MSerial##X #define MSERIAL(X) _MSERIAL(X) -#if WITHIN(SERIAL_PORT, 1, 6) +#if WITHIN(SERIAL_PORT, 1, 9) #define MYSERIAL1 MSERIAL(SERIAL_PORT) #elif !defined(USBCON) - #error "SERIAL_PORT must be from 1 to 6." + #error "SERIAL_PORT must be from 1 to 9." #elif SERIAL_PORT == -1 #define MYSERIAL1 MSerialUSB #else - #error "SERIAL_PORT must be from 1 to 6, or -1 for Native USB." + #error "SERIAL_PORT must be from 1 to 9, or -1 for Native USB." #endif #ifdef SERIAL_PORT_2 - #if WITHIN(SERIAL_PORT_2, 1, 6) + #if WITHIN(SERIAL_PORT_2, 1, 9) #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) #elif !defined(USBCON) - #error "SERIAL_PORT must be from 1 to 6." + #error "SERIAL_PORT_2 must be from 1 to 9." #elif SERIAL_PORT_2 == -1 #define MYSERIAL2 MSerialUSB #else - #error "SERIAL_PORT_2 must be from 1 to 6, or -1 for Native USB." + #error "SERIAL_PORT_2 must be from 1 to 9, or -1 for Native USB." #endif #endif #ifdef SERIAL_PORT_3 - #if WITHIN(SERIAL_PORT_3, 1, 6) + #if WITHIN(SERIAL_PORT_3, 1, 9) #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) #elif !defined(USBCON) - #error "SERIAL_PORT must be from 1 to 6." + #error "SERIAL_PORT_3 must be from 1 to 9." #elif SERIAL_PORT_3 == -1 #define MYSERIAL3 MSerialUSB #else - #error "SERIAL_PORT_3 must be from 1 to 6, or -1 for Native USB." + #error "SERIAL_PORT_3 must be from 1 to 9, or -1 for Native USB." #endif #endif #ifdef MMU2_SERIAL_PORT - #if WITHIN(MMU2_SERIAL_PORT, 1, 6) + #if WITHIN(MMU2_SERIAL_PORT, 1, 9) #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT) #elif !defined(USBCON) - #error "SERIAL_PORT must be from 1 to 6." + #error "MMU2_SERIAL_PORT must be from 1 to 9." #elif MMU2_SERIAL_PORT == -1 #define MMU2_SERIAL MSerialUSB #else - #error "MMU2_SERIAL_PORT must be from 1 to 6, or -1 for Native USB." + #error "MMU2_SERIAL_PORT must be from 1 to 9, or -1 for Native USB." #endif #endif #ifdef LCD_SERIAL_PORT - #if WITHIN(LCD_SERIAL_PORT, 1, 6) + #if WITHIN(LCD_SERIAL_PORT, 1, 9) #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) #elif !defined(USBCON) - #error "SERIAL_PORT must be from 1 to 6." + #error "LCD_SERIAL_PORT must be from 1 to 9." #elif LCD_SERIAL_PORT == -1 #define LCD_SERIAL MSerialUSB #else - #error "LCD_SERIAL_PORT must be from 1 to 6, or -1 for Native USB." + #error "LCD_SERIAL_PORT must be from 1 to 9, or -1 for Native USB." #endif #if HAS_DGUS_LCD - #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() + #define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() #endif #endif @@ -138,11 +137,7 @@ typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs. -#if defined(STM32G0B1xx) || defined(STM32H7xx) - typedef int32_t pin_t; -#else - typedef int16_t pin_t; -#endif +typedef int32_t pin_t; // Parity with platform/ststm32 class libServo; typedef libServo hal_servo_t; @@ -159,7 +154,7 @@ typedef libServo hal_servo_t; #define HAL_ADC_RESOLUTION 12 #endif -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 // // Pin Mapping for M42, M43, M226 @@ -174,7 +169,9 @@ typedef libServo hal_servo_t; #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG #endif -#define PLATFORM_M997_SUPPORT +#ifndef PLATFORM_M997_SUPPORT + #define PLATFORM_M997_SUPPORT +#endif void flashFirmware(const int16_t); // Maple Compatibility diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 278d209c47cb..cc035ecffabc 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp index 37a8f40fd0b1..9f0b003a316b 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp @@ -37,6 +37,15 @@ #ifndef USART5 #define USART5 UART5 #endif +#ifndef USART7 + #define USART7 UART7 +#endif +#ifndef USART8 + #define USART8 UART8 +#endif +#ifndef USART9 + #define USART9 UART9 +#endif #define DECLARE_SERIAL_PORT(ser_num) \ void _rx_complete_irq_ ## ser_num (serial_t * obj); \ diff --git a/Marlin/src/HAL/STM32/MinSerial.cpp b/Marlin/src/HAL/STM32/MinSerial.cpp index b0fcff20c172..a27bc35a146b 100644 --- a/Marlin/src/HAL/STM32/MinSerial.cpp +++ b/Marlin/src/HAL/STM32/MinSerial.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -45,7 +44,7 @@ struct USARTMin { volatile uint32_t CR2; }; -#if WITHIN(SERIAL_PORT, 1, 6) +#if WITHIN(SERIAL_PORT, 1, 9) // Depending on the CPU, the serial port is different for USART1 static const uintptr_t regsAddr[] = { TERN(STM32F1xx, 0x40013800, 0x40011000), // USART1 @@ -53,7 +52,10 @@ struct USARTMin { 0x40004800, // USART3 0x40004C00, // UART4_BASE 0x40005000, // UART5_BASE - 0x40011400 // USART6 + 0x40011400, // USART6 + 0x40007800, // UART7_BASE + 0x40007C00, // UART8_BASE + 0x40011800 // UART9_BASE }; static USARTMin * regs = (USARTMin*)regsAddr[SERIAL_PORT - 1]; #endif @@ -116,7 +118,7 @@ static void TXBegin() { // A SW memory barrier, to ensure GCC does not overoptimize loops #define sw_barrier() __asm__ volatile("": : :"memory"); static void TX(char c) { - #if WITHIN(SERIAL_PORT, 1, 6) + #if WITHIN(SERIAL_PORT, 1, 9) constexpr uint32_t usart_sr_txe = _BV(7); while (!(regs->SR & usart_sr_txe)) { hal.watchdog_refresh(); @@ -135,18 +137,18 @@ void install_min_serial() { } #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__ ( - "b CommonHandler_ASM\n" - ); + extern "C" { + __attribute__((naked)) void JumpHandler_ASM() { + __asm__ __volatile__ ( + "b CommonHandler_ASM\n" + ); + } + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler(); } - void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler(); -} #endif #endif // POSTMORTEM_DEBUGGING diff --git a/Marlin/src/HAL/STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp index a00186e0e79e..4f026ffc6df4 100644 --- a/Marlin/src/HAL/STM32/Servo.cpp +++ b/Marlin/src/HAL/STM32/Servo.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/STM32/Servo.h b/Marlin/src/HAL/STM32/Servo.h index 1527e753b661..95ecb5d97762 100644 --- a/Marlin/src/HAL/STM32/Servo.h +++ b/Marlin/src/HAL/STM32/Servo.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 6bd519877d53..69511c6de40c 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/STM32/eeprom_sram.cpp b/Marlin/src/HAL/STM32/eeprom_sram.cpp index 687e7f55c226..9bd84ff4fe27 100644 --- a/Marlin/src/HAL/STM32/eeprom_sram.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sram.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp index cf0468151e5e..6fb9d9b51b7b 100644 --- a/Marlin/src/HAL/STM32/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/STM32/endstop_interrupts.h b/Marlin/src/HAL/STM32/endstop_interrupts.h index d2f20ba1c711..c7414f959f0a 100644 --- a/Marlin/src/HAL/STM32/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32/endstop_interrupts.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -29,33 +28,33 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); - TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN)); - TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN)); - TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN)); - TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN)); - TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN)); - TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/STM32/fastio.cpp b/Marlin/src/HAL/STM32/fastio.cpp index b34555b8c841..f8501545a078 100644 --- a/Marlin/src/HAL/STM32/fastio.cpp +++ b/Marlin/src/HAL/STM32/fastio.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -29,7 +28,7 @@ GPIO_TypeDef* FastIOPortMap[LastPort + 1] = { 0 }; void FastIO_init() { - LOOP_L_N(i, NUM_DIGITAL_PINS) + for (uint8_t i = 0; i < NUM_DIGITAL_PINS; ++i) FastIOPortMap[STM_PORT(digitalPin[i])] = get_GPIO_Port(STM_PORT(digitalPin[i])); } diff --git a/Marlin/src/HAL/STM32/fastio.h b/Marlin/src/HAL/STM32/fastio.h index 4a489544716f..af2941c49c1a 100644 --- a/Marlin/src/HAL/STM32/fastio.h +++ b/Marlin/src/HAL/STM32/fastio.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h index 451c94f25d1f..032716a294ce 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h @@ -21,7 +21,7 @@ */ #pragma once -#if BOTH(SDSUPPORT, USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE) +#if ALL(HAS_MEDIA, USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE) #define HAS_SD_HOST_DRIVE 1 #endif diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_post.h b/Marlin/src/HAL/STM32/inc/Conditionals_post.h index 83ce077c754d..6c97a635b3cc 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_post.h @@ -24,7 +24,7 @@ // If no real or emulated EEPROM selected, fall back to SD emulation #if USE_FALLBACK_EEPROM #define SDCARD_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h index e8ddfa172005..deb16ef71e21 100644 --- a/Marlin/src/HAL/STM32/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h @@ -28,8 +28,7 @@ // #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector" //#endif - -#if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT) +#if ENABLED(SDCARD_EEPROM_EMULATION) && !HAS_MEDIA #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise #if USE_FALLBACK_EEPROM #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION." @@ -55,7 +54,7 @@ * Check for common serial pin conflicts */ #define _CHECK_SERIAL_PIN(N) (( \ - BTN_EN1 == N || DOGLCD_CS == N || HEATER_BED_PIN == N || FAN_PIN == N || \ + BTN_EN1 == N || DOGLCD_CS == N || HEATER_BED_PIN == N || FAN0_PIN == N || \ SDIO_D2_PIN == N || SDIO_D3_PIN == N || SDIO_CK_PIN == N || SDIO_CMD_PIN == N \ )) #define CHECK_SERIAL_PIN(T,N) defined(UART##N##_##T##_PIN) && _CHECK_SERIAL_PIN(UART##N##_##T##_PIN) diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index a40bec9d644d..5c8bee9c62bc 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * 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 . * @@ -33,6 +40,12 @@ #define BLOCK_SIZE 512 #define PRODUCT_ID 0x29 +#ifndef SD_MULTIBLOCK_RETRY_CNT + #define SD_MULTIBLOCK_RETRY_CNT 1 +#elif SD_MULTIBLOCK_RETRY_CNT < 1 + #error "SD_MULTIBLOCK_RETRY_CNT must be greater than or equal to 1." +#endif + class Sd2CardUSBMscHandler : public USBMscHandler { public: DiskIODriver* diskIODriver() { @@ -58,19 +71,29 @@ class Sd2CardUSBMscHandler : public USBMscHandler { // single block if (blkLen == 1) { hal.watchdog_refresh(); - sd2card->writeBlock(blkAddr, pBuf); - return true; + return sd2card->writeBlock(blkAddr, pBuf); } // multi block optimization - sd2card->writeStart(blkAddr, blkLen); - while (blkLen--) { - hal.watchdog_refresh(); - sd2card->writeData(pBuf); - pBuf += BLOCK_SIZE; + bool done = false; + for (uint16_t rcount = SD_MULTIBLOCK_RETRY_CNT; !done && rcount--;) { + uint8_t *cBuf = pBuf; + sd2card->writeStart(blkAddr, blkLen); + bool okay = true; // Assume success + for (uint32_t i = blkLen; i--;) { + hal.watchdog_refresh(); + if (!sd2card->writeData(cBuf)) { // Write. Did it fail? + sd2card->writeStop(); // writeStop for new writeStart + okay = false; // Failed, so retry + break; // Go to while... below + } + cBuf += BLOCK_SIZE; + } + done = okay; // Done if no error occurred } - sd2card->writeStop(); - return true; + + if (done) sd2card->writeStop(); + return done; } bool Read(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) { @@ -78,24 +101,32 @@ class Sd2CardUSBMscHandler : public USBMscHandler { // single block if (blkLen == 1) { hal.watchdog_refresh(); - sd2card->readBlock(blkAddr, pBuf); - return true; + return sd2card->readBlock(blkAddr, pBuf); } // multi block optimization - sd2card->readStart(blkAddr); - while (blkLen--) { - hal.watchdog_refresh(); - sd2card->readData(pBuf); - pBuf += BLOCK_SIZE; + bool done = false; + for (uint16_t rcount = SD_MULTIBLOCK_RETRY_CNT; !done && rcount--;) { + uint8_t *cBuf = pBuf; + sd2card->readStart(blkAddr); + bool okay = true; // Assume success + for (uint32_t i = blkLen; i--;) { + hal.watchdog_refresh(); + if (!sd2card->readData(cBuf)) { // Read. Did it fail? + sd2card->readStop(); // readStop for new readStart + okay = false; // Failed, so retry + break; // Go to while... below + } + cBuf += BLOCK_SIZE; + } + done = okay; // Done if no error occurred } - sd2card->readStop(); - return true; - } - bool IsReady() { - return diskIODriver()->isReady(); + if (done) sd2card->readStop(); + return done; } + + bool IsReady() { return diskIODriver()->isReady(); } }; Sd2CardUSBMscHandler usbMscHandler; diff --git a/Marlin/src/HAL/STM32/msc_sd.h b/Marlin/src/HAL/STM32/msc_sd.h index a8e5349f7cd3..20e738223cd2 100644 --- a/Marlin/src/HAL/STM32/msc_sd.h +++ b/Marlin/src/HAL/STM32/msc_sd.h @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * 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 . * diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index 29a4e003f98a..13990a69f5ef 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -111,13 +111,14 @@ const XrefInfo pin_xref[] PROGMEM = { #if NUM_ANALOG_FIRST >= NUM_DIGITAL_PINS #define HAS_HIGH_ANALOG_PINS 1 #endif -#define NUM_ANALOG_LAST ((NUM_ANALOG_FIRST) + (NUM_ANALOG_INPUTS) - 1) +#ifndef NUM_ANALOG_LAST + #define NUM_ANALOG_LAST ((NUM_ANALOG_FIRST) + (NUM_ANALOG_INPUTS) - 1) +#endif #define NUMBER_PINS_TOTAL ((NUM_DIGITAL_PINS) + TERN0(HAS_HIGH_ANALOG_PINS, NUM_ANALOG_INPUTS)) #define VALID_PIN(P) (WITHIN(P, 0, (NUM_DIGITAL_PINS) - 1) || TERN0(HAS_HIGH_ANALOG_PINS, WITHIN(P, NUM_ANALOG_FIRST, NUM_ANALOG_LAST))) #define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads #define PRINT_PIN(Q) #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 // x is a variable used to search pin_array @@ -185,7 +186,7 @@ bool is_digital(const pin_t Ard_num) { return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT; } -void port_print(const pin_t Ard_num) { +void print_port(const pin_t Ard_num) { char buffer[16]; pin_t Index; for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++) diff --git a/Marlin/src/HAL/STM32/sdio.cpp b/Marlin/src/HAL/STM32/sdio.cpp index 72518ef1cc87..de388b8e146a 100644 --- a/Marlin/src/HAL/STM32/sdio.cpp +++ b/Marlin/src/HAL/STM32/sdio.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDIO_SUPPORT) +#if ENABLED(ONBOARD_SDIO) #include "sdio.h" @@ -453,5 +453,5 @@ uint32_t SDIO_GetCardSize() { return (uint32_t)(hsd.SdCard.BlockNbr) * (hsd.SdCard.BlockSize); } -#endif // SDIO_SUPPORT +#endif // ONBOARD_SDIO #endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/gt911.cpp b/Marlin/src/HAL/STM32/tft/gt911.cpp index 82b7c5b10391..6809f6620093 100644 --- a/Marlin/src/HAL/STM32/tft/gt911.cpp +++ b/Marlin/src/HAL/STM32/tft/gt911.cpp @@ -90,7 +90,7 @@ bool SW_IIC::read_ack() { } void SW_IIC::send_byte(uint8_t txd) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { write_sda(txd & 0x80); // write data bit txd <<= 1; iic_delay(1); @@ -107,7 +107,7 @@ uint8_t SW_IIC::read_byte(bool ack) { uint8_t data = 0; set_sda_in(); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { write_scl(HIGH); // SCL = 1 iic_delay(1); data <<= 1; @@ -128,12 +128,12 @@ SW_IIC GT911::sw_iic = SW_IIC(GT911_SW_I2C_SDA_PIN, GT911_SW_I2C_SCL_PIN); void GT911::write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len) { sw_iic.start(); sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address - LOOP_L_N(i, reg_len) { // Set reg address + for (uint8_t i = 0; i < reg_len; ++i) { // Set reg address uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF; sw_iic.send_byte(r); } - LOOP_L_N(i, w_len) { // Write data to reg + for (uint8_t i = 0; i < w_len; ++i) { // Write data to reg sw_iic.send_byte(w_data[i]); } sw_iic.stop(); @@ -142,7 +142,7 @@ void GT911::write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_ void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len) { sw_iic.start(); sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address - LOOP_L_N(i, reg_len) { // Set reg address + for (uint8_t i = 0; i < reg_len; ++i) { // Set reg address uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF; sw_iic.send_byte(r); } @@ -150,7 +150,7 @@ void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_l sw_iic.start(); sw_iic.send_byte(gt911_slave_address + 1); // Set read mode - LOOP_L_N(i, r_len) + for (uint8_t i = 0; i < r_len; ++i) r_data[i] = sw_iic.read_byte(1); // Read data from reg sw_iic.stop(); diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.h b/Marlin/src/HAL/STM32/tft/tft_fsmc.h index 41ff8c9a83c8..6189fed28f20 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.h +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.h @@ -41,7 +41,7 @@ #define DATASIZE_8BIT SPI_DATASIZE_8BIT #define DATASIZE_16BIT SPI_DATASIZE_16BIT #define TFT_IO_DRIVER TFT_FSMC -#define DMA_MAX_SIZE 0xFFFF +#define DMA_MAX_WORDS 0xFFFF #define TFT_DATASIZE TERN(TFT_INTERFACE_FSMC_8BIT, DATASIZE_8BIT, DATASIZE_16BIT) typedef TERN(TFT_INTERFACE_FSMC_8BIT, uint8_t, uint16_t) tft_data_t; @@ -81,8 +81,8 @@ class TFT_FSMC { static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_PINC_ENABLE, Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { while (Count > 0) { - Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count); - Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0; + Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_WORDS ? DMA_MAX_WORDS : Count); + Count = Count > DMA_MAX_WORDS ? Count - DMA_MAX_WORDS : 0; } } }; diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.h b/Marlin/src/HAL/STM32/tft/tft_ltdc.h index 8d83839bb3fa..c60b33febcbc 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.h +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.h @@ -32,7 +32,7 @@ #define DATASIZE_8BIT SPI_DATASIZE_8BIT #define DATASIZE_16BIT SPI_DATASIZE_16BIT #define TFT_IO_DRIVER TFT_LTDC -#define DMA_MAX_SIZE 0xFFFF +#define DMA_MAX_WORDS 0xFFFF #define TFT_DATASIZE DATASIZE_16BIT typedef uint16_t tft_data_t; @@ -71,8 +71,8 @@ class TFT_LTDC { static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_PINC_ENABLE, Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { while (Count > 0) { - Transmit(DMA_PINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count); - Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0; + Transmit(DMA_PINC_DISABLE, &Color, Count > DMA_MAX_WORDS ? DMA_MAX_WORDS : Count); + Count = Count > DMA_MAX_WORDS ? Count - DMA_MAX_WORDS : 0; } } }; diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index 5e79f156d27c..26472875268c 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -242,10 +242,9 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request - TERN_(TFT_SHARED_SPI, while (isBusy())); + TERN_(TFT_SHARED_IO, while (isBusy())); } - void TFT_SPI::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { DMAtx.Init.MemInc = MemoryIncrease; HAL_DMA_Init(&DMAtx); diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.h b/Marlin/src/HAL/STM32/tft/tft_spi.h index 6b8613e3f87f..9ec3b88f476a 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.h +++ b/Marlin/src/HAL/STM32/tft/tft_spi.h @@ -38,8 +38,9 @@ #define DATASIZE_8BIT SPI_DATASIZE_8BIT #define DATASIZE_16BIT SPI_DATASIZE_16BIT +#define DATASIZE_32BIT SPI_DATASIZE_32BIT #define TFT_IO_DRIVER TFT_SPI -#define DMA_MAX_SIZE 0xFFFF +#define DMA_MAX_WORDS 0xFFFF class TFT_SPI { private: @@ -78,8 +79,8 @@ class TFT_SPI { static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_MINC_ENABLE, Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { while (Count > 0) { - Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count); - Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0; + Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_WORDS ? DMA_MAX_WORDS : Count); + Count = Count > DMA_MAX_WORDS ? Count - DMA_MAX_WORDS : 0; } } }; diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index e68b59c46fee..10e0dc43a436 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 @@ -292,9 +292,9 @@ static constexpr int get_timer_num_from_base_address(uintptr_t base_address) { // constexpr doesn't like using the base address pointers that timers evaluate to. // We can get away with casting them to uintptr_t, if we do so inside an array. // GCC will not currently do it directly to a uintptr_t. -IF_ENABLED(HAS_TMC_SW_SERIAL, static constexpr uintptr_t timer_serial[] = {uintptr_t(TIMER_SERIAL)}); -IF_ENABLED(SPEAKER, static constexpr uintptr_t timer_tone[] = {uintptr_t(TIMER_TONE)}); -IF_ENABLED(HAS_SERVOS, static constexpr uintptr_t timer_servo[] = {uintptr_t(TIMER_SERVO)}); +TERN_(HAS_TMC_SW_SERIAL, static constexpr uintptr_t timer_serial[] = {uintptr_t(TIMER_SERIAL)}); +TERN_(SPEAKER, static constexpr uintptr_t timer_tone[] = {uintptr_t(TIMER_TONE)}); +TERN_(HAS_SERVOS, static constexpr uintptr_t timer_servo[] = {uintptr_t(TIMER_SERVO)}); enum TimerPurpose { TP_SERIAL, TP_TONE, TP_SERVO, TP_STEP, TP_TEMP }; @@ -316,8 +316,8 @@ static constexpr struct { TimerPurpose p; int t; } timers_in_use[] = { }; static constexpr bool verify_no_timer_conflicts() { - LOOP_L_N(i, COUNT(timers_in_use)) - LOOP_S_L_N(j, i + 1, COUNT(timers_in_use)) + for (uint8_t i = 0; i < COUNT(timers_in_use); ++i) + for (uint8_t j = i + 1; j < COUNT(timers_in_use); ++j) if (timers_in_use[i].t == timers_in_use[j].t) return false; return true; } diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 6828998198af..180e24031471 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/STM32/usb_host.cpp b/Marlin/src/HAL/STM32/usb_host.cpp index f3784670049c..afafe1d4f3d1 100644 --- a/Marlin/src/HAL/STM32/usb_host.cpp +++ b/Marlin/src/HAL/STM32/usb_host.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfig.h" -#if BOTH(USE_OTG_USB_HOST, USBHOST) +#if ALL(USE_OTG_USB_HOST, USBHOST) #include "usb_host.h" #include "../shared/Marduino.h" diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index 4d3140001e82..be2c933413fc 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2017 Victor Perez + * + * 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 @@ -224,7 +223,7 @@ void MarlinHAL::init() { #endif #if HAS_SD_HOST_DRIVE MSC_SD_init(); - #elif BOTH(SERIAL_USB, EMERGENCY_PARSER) + #elif ALL(SERIAL_USB, EMERGENCY_PARSER) usb_cdcacm_set_hooks(USB_CDCACM_HOOK_RX, my_rx_callback); #endif #if PIN_EXISTS(USB_CONNECT) diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index b14b5f7e7926..52d3b805e611 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2017 Victor Perez + * + * 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 @@ -82,7 +81,7 @@ #define _MSERIAL(X) MSerial##X #define MSERIAL(X) _MSERIAL(X) -#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) +#if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) #define NUM_UARTS 5 #else #define NUM_UARTS 3 @@ -140,7 +139,7 @@ static_assert(false, "LCD_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.") #endif #if HAS_DGUS_LCD - #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() + #define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() #endif #endif @@ -190,7 +189,7 @@ typedef int8_t pin_t; #define HAL_ADC_RESOLUTION 12 #endif -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 uint16_t analogRead(const pin_t pin); // need hal.adc_enable() first void analogWrite(const pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? @@ -205,7 +204,9 @@ void analogWrite(const pin_t pin, int pwm_val8); // PWM only! mul by 257 in mapl #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 +#ifndef PLATFORM_M997_SUPPORT + #define PLATFORM_M997_SUPPORT +#endif void flashFirmware(const int16_t); #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment @@ -220,8 +221,6 @@ void flashFirmware(const int16_t); // Memory related #define __bss_end __bss_end__ -void _delay_ms(const int ms); - extern "C" char* _sbrk(int incr); #pragma GCC diagnostic push diff --git a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp index abb348d743c5..b5b57536f3f8 100644 --- a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp index 6dabcde51ead..3b26b630df22 100644 --- a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp @@ -28,7 +28,7 @@ // Copied from ~/.platformio/packages/framework-arduinoststm32-maple/STM32F1/system/libmaple/usart_private.h // Changed to handle Emergency Parser -static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MSerialT &serial) { +FORCE_INLINE void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MSerialT &serial) { /* Handle RXNEIE and TXEIE interrupts. * RXNE signifies availability of a byte in DR. * @@ -75,9 +75,9 @@ static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb } // Not every MarlinSerial port should handle emergency parsing. -// It would not make sense to parse GCode from TMC responses, for example. +// It would not make sense to parse G-Code from TMC responses, for example. constexpr bool serial_handles_emergency(int port) { - return false + return (false #ifdef SERIAL_PORT || (SERIAL_PORT) == port #endif @@ -87,7 +87,7 @@ constexpr bool serial_handles_emergency(int port) { #ifdef LCD_SERIAL_PORT || (LCD_SERIAL_PORT) == port #endif - ; + ); } #define DEFINE_HWSERIAL_MARLIN(name, n) \ @@ -116,7 +116,7 @@ constexpr bool serial_handles_emergency(int port) { #endif DEFINE_HWSERIAL_MARLIN(MSerial2, 2); DEFINE_HWSERIAL_MARLIN(MSerial3, 3); -#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) +#if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) DEFINE_HWSERIAL_UART_MARLIN(MSerial4, 4); DEFINE_HWSERIAL_UART_MARLIN(MSerial5, 5); #endif diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.h b/Marlin/src/HAL/STM32F1/MarlinSerial.h index dda32fe7a2ef..53bcd4847638 100644 --- a/Marlin/src/HAL/STM32F1/MarlinSerial.h +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.h @@ -52,7 +52,7 @@ typedef Serial1Class MSerialT; extern MSerialT MSerial1; extern MSerialT MSerial2; extern MSerialT MSerial3; -#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) +#if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) extern MSerialT MSerial4; extern MSerialT MSerial5; #endif diff --git a/Marlin/src/HAL/STM32F1/MinSerial.cpp b/Marlin/src/HAL/STM32F1/MinSerial.cpp index 6cf68d8d8f45..8fb913325496 100644 --- a/Marlin/src/HAL/STM32F1/MinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/MinSerial.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/STM32F1/SPI.cpp b/Marlin/src/HAL/STM32F1/SPI.cpp index a180684757ee..ab111ddbf01b 100644 --- a/Marlin/src/HAL/STM32F1/SPI.cpp +++ b/Marlin/src/HAL/STM32F1/SPI.cpp @@ -517,7 +517,6 @@ uint8_t SPIClass::dmaSendAsync(const void * transmitBuf, uint16_t length, bool m return b; } - /** * New functions added to manage callbacks. * Victor Perez 2017 diff --git a/Marlin/src/HAL/STM32F1/SPI.h b/Marlin/src/HAL/STM32F1/SPI.h index 0941fa55b781..27bf684388ea 100644 --- a/Marlin/src/HAL/STM32F1/SPI.h +++ b/Marlin/src/HAL/STM32F1/SPI.h @@ -58,7 +58,7 @@ #define SPI_CLOCK_DIV128 SPI_BAUD_PCLK_DIV_128 #define SPI_CLOCK_DIV256 SPI_BAUD_PCLK_DIV_256 -/* +/** * Roger Clark. 20150106 * Commented out redundant AVR defined * @@ -153,7 +153,7 @@ class SPISettings { friend class SPIClass; }; -/* +/** * Kept for compat. */ static const uint8_t ff = 0xFF; @@ -233,7 +233,7 @@ class SPIClass { void onReceive(void(*)()); void onTransmit(void(*)()); - /* + /** * I/O */ @@ -314,7 +314,7 @@ class SPIClass { uint8_t dmaSendRepeat(uint16_t length); uint8_t dmaSendAsync(const void * transmitBuf, uint16_t length, bool minc = 1); - /* + /** * Pin accessors */ @@ -398,7 +398,7 @@ class SPIClass { void updateSettings(); - /* + /** * Functions added for DMA transfers with Callback. * Experimental. */ diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp index 47ffb631cf8f..7aa8fe3d00df 100644 --- a/Marlin/src/HAL/STM32F1/Servo.cpp +++ b/Marlin/src/HAL/STM32F1/Servo.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/STM32F1/Servo.h b/Marlin/src/HAL/STM32F1/Servo.h index 745a1c93f07d..ffafc23833e3 100644 --- a/Marlin/src/HAL/STM32F1/Servo.h +++ b/Marlin/src/HAL/STM32F1/Servo.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp index 26ea1ea19af9..c57350aa2efd 100644 --- a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp +++ b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp @@ -24,7 +24,7 @@ #include "../../../inc/MarlinConfig.h" -#if BOTH(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) +#if ALL(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) #include #include "../../shared/HAL_SPI.h" @@ -37,7 +37,7 @@ static uint8_t SPI_speed = LCD_SPI_SPEED; static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (spi_speed == 0) { WRITE(DOGLCD_MOSI, !!(b & 0x80)); WRITE(DOGLCD_SCK, HIGH); @@ -47,16 +47,16 @@ static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, c } else { const uint8_t state = (b & 0x80) ? HIGH : LOW; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE(DOGLCD_MOSI, state); - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE(DOGLCD_SCK, HIGH); b <<= 1; if (miso_pin >= 0 && READ(miso_pin)) b |= 1; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE(DOGLCD_SCK, LOW); } } @@ -64,7 +64,7 @@ static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, c } static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { const uint8_t state = (b & 0x80) ? HIGH : LOW; if (spi_speed == 0) { WRITE(DOGLCD_SCK, LOW); @@ -73,13 +73,13 @@ static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, c WRITE(DOGLCD_SCK, HIGH); } else { - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE(DOGLCD_SCK, LOW); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE(DOGLCD_MOSI, state); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE(DOGLCD_SCK, HIGH); } b <<= 1; diff --git a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp index e7d9dd29e2c5..48fb2d286cc6 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/STM32F1/endstop_interrupts.h b/Marlin/src/HAL/STM32F1/endstop_interrupts.h index a1ef8a8c3a36..56600bcd0ef8 100644 --- a/Marlin/src/HAL/STM32F1/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32F1/endstop_interrupts.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -54,33 +53,33 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); - TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN)); - TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN)); - TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN)); - TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN)); - TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN)); - TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/STM32F1/fastio.h b/Marlin/src/HAL/STM32F1/fastio.h index e75254d6929e..5b3ebaa52c49 100644 --- a/Marlin/src/HAL/STM32F1/fastio.h +++ b/Marlin/src/HAL/STM32F1/fastio.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h index 656fbe1ce259..f130f5cad8e1 100644 --- a/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h @@ -24,11 +24,11 @@ // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation #if USE_FALLBACK_EEPROM #define SDCARD_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif -// Allow SDSUPPORT to be disabled -#if DISABLED(SDSUPPORT) - #undef SDIO_SUPPORT +// Allow for no media drives +#if !HAS_MEDIA + #undef ONBOARD_SDIO #endif diff --git a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h index fe8f6e0ec24b..1da42dcc8fd0 100644 --- a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h @@ -25,7 +25,7 @@ * Test STM32F1-specific configuration values for errors at compile-time. */ -#if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT) +#if ENABLED(SDCARD_EEPROM_EMULATION) && !HAS_MEDIA #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise #if USE_FALLBACK_EEPROM #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION." diff --git a/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf b/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf index c39f4ce0ed5d..0df30d2c42a4 100644 --- a/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf +++ b/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf @@ -48,7 +48,6 @@ ServiceBinary=%12%\usbser.sys ; String Definitions ;------------------------------------------------------------------------------ - [Strings] STM = "LeafLabs" MFGNAME = "LeafLabs" diff --git a/Marlin/src/HAL/STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/msc_sd.cpp index f490c83ed829..067b46eb8bad 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.cpp +++ b/Marlin/src/HAL/STM32F1/msc_sd.cpp @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * 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 . * diff --git a/Marlin/src/HAL/STM32F1/msc_sd.h b/Marlin/src/HAL/STM32F1/msc_sd.h index f4636bdff702..371211efc68a 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.h +++ b/Marlin/src/HAL/STM32F1/msc_sd.h @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * 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 . * diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.h b/Marlin/src/HAL/STM32F1/onboard_sd.h index f8846e95bcaa..be1d1d0a6bdc 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.h +++ b/Marlin/src/HAL/STM32F1/onboard_sd.h @@ -47,7 +47,6 @@ typedef enum { RES_PARERR /* 4: Invalid Parameter */ } DRESULT; - #if _DISKIO_ISDIO /* Command structure for iSDIO ioctl command */ typedef struct { diff --git a/Marlin/src/HAL/STM32F1/pinsDebug.h b/Marlin/src/HAL/STM32F1/pinsDebug.h index 7828479658a9..6f8e48f455bd 100644 --- a/Marlin/src/HAL/STM32F1/pinsDebug.h +++ b/Marlin/src/HAL/STM32F1/pinsDebug.h @@ -41,11 +41,9 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]; #define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS #define VALID_PIN(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS) #define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin) -#define pwm_status(pin) PWM_PIN(pin) #define digitalRead_mod(p) extDigitalRead(p) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(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) -#define PRINT_PORT(p) print_port(p) #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin @@ -54,20 +52,18 @@ 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 int8_t get_pin_mode(pin_t pin) { - return VALID_PIN(pin) ? _GET_MODE(pin) : -1; -} +int8_t get_pin_mode(const pin_t pin) { return VALID_PIN(pin) ? _GET_MODE(pin) : -1; } -static pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) { +pin_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t pin) { if (!VALID_PIN(pin)) return -1; - int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel); + pin_t adc_channel = pin_t(PIN_MAP[pin].adc_channel); #ifdef NUM_ANALOG_INPUTS - if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = ADCx; + if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = (pin_t)ADCx; #endif - return pin_t(adc_channel); + return adc_channel; } -static bool IS_ANALOG(pin_t pin) { +bool IS_ANALOG(const pin_t pin) { if (!VALID_PIN(pin)) return false; if (PIN_MAP[pin].adc_channel != ADCx) { #ifdef NUM_ANALOG_INPUTS @@ -78,11 +74,11 @@ static bool IS_ANALOG(pin_t pin) { return false; } -static bool GET_PINMODE(const pin_t pin) { +bool GET_PINMODE(const pin_t pin) { return VALID_PIN(pin) && !IS_INPUT(pin); } -static bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) { +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,12 +89,12 @@ static bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) { #include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density -static void pwm_details(const pin_t pin) { +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; const char num = ( - #if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) + #if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) tdev == &timer8 ? '8' : tdev == &timer5 ? '5' : #endif @@ -113,7 +109,9 @@ static void pwm_details(const pin_t pin) { } } -static void print_port(pin_t pin) { +bool pwm_status(const pin_t pin) { return PWM_PIN(pin); } + +void print_port(const 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/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp index 6e41d2cbf1b4..23f984eff329 100644 --- a/Marlin/src/HAL/STM32F1/sdio.cpp +++ b/Marlin/src/HAL/STM32F1/sdio.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -26,7 +25,7 @@ #include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density -#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) +#if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) #include "sdio.h" @@ -136,8 +135,13 @@ bool SDIO_ReadBlock_DMA(uint32_t blockAddress, uint8_t *data) { } bool SDIO_ReadBlock(uint32_t blockAddress, uint8_t *data) { - uint32_t retries = SDIO_READ_RETRIES; - while (retries--) if (SDIO_ReadBlock_DMA(blockAddress, data)) return true; + uint8_t retries = SDIO_READ_RETRIES; + while (retries--) { + if (SDIO_ReadBlock_DMA(blockAddress, data)) return true; + #if SD_RETRY_DELAY_MS + delay(SD_RETRY_DELAY_MS); + #endif + } return false; } diff --git a/Marlin/src/HAL/STM32F1/sdio.h b/Marlin/src/HAL/STM32F1/sdio.h index 8777299f01bc..08c884666d8c 100644 --- a/Marlin/src/HAL/STM32F1/sdio.h +++ b/Marlin/src/HAL/STM32F1/sdio.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2017 Victor Perez + * + * 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 @@ -60,7 +60,6 @@ #define ACMD41_SD_APP_OP_COND (uint16_t)(SDMMC_ACMD_SD_APP_OP_COND | SDIO_CMD_WAIT_SHORT_RESP) #define ACMD42_SD_APP_SET_CLR_CARD_DETECT (uint16_t)(SDMMC_ACMD_SD_APP_SET_CLR_CARD_DETECT | SDIO_CMD_WAIT_SHORT_RESP) - #define SDMMC_ALLZERO 0x00000000U #define SDMMC_OCR_ERRORBITS 0xFDFFE008U diff --git a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp index 512e70cf3f70..175576c24835 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp @@ -20,6 +20,8 @@ * */ +#ifdef __STM32F1__ + #include "../../../inc/MarlinConfig.h" #if HAS_FSMC_TFT @@ -260,3 +262,5 @@ void TFT_FSMC::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) } #endif // HAS_FSMC_TFT + +#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h index 8d26f6eac0b7..720af8db16b1 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h +++ b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h @@ -33,7 +33,7 @@ #define DATASIZE_8BIT DMA_SIZE_8BITS #define DATASIZE_16BIT DMA_SIZE_16BITS #define TFT_IO_DRIVER TFT_FSMC -#define DMA_MAX_SIZE 0xFFFF +#define DMA_MAX_WORDS 0xFFFF #define DMA_PINC_ENABLE DMA_PINC_MODE #define DMA_PINC_DISABLE 0 @@ -70,8 +70,8 @@ class TFT_FSMC { static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_PINC_ENABLE, Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { while (Count > 0) { - Transmit(DMA_PINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count); - Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0; + Transmit(DMA_PINC_DISABLE, &Color, Count > DMA_MAX_WORDS ? DMA_MAX_WORDS : Count); + Count = Count > DMA_MAX_WORDS ? Count - DMA_MAX_WORDS : 0; } } }; diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp index bb495d5f58b5..d0772e27a521 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp @@ -20,6 +20,8 @@ * */ +#ifdef __STM32F1__ + #include "../../../inc/MarlinConfig.h" #if HAS_SPI_TFT @@ -101,7 +103,7 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { DataTransferBegin(DATASIZE_8BIT); WriteReg(Reg); - LOOP_L_N(i, 4) { + for (uint8_t i = 0; i < 4; ++i) { SPIx.read((uint8_t*)&d, 1); data = (data << 8) | d; } @@ -154,7 +156,7 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun DataTransferBegin(); SPIx.dmaSendAsync(Data, Count, MemoryIncrease == DMA_MINC_ENABLE); - TERN_(TFT_SHARED_SPI, while (isBusy())); + TERN_(TFT_SHARED_IO, while (isBusy())); } void TFT_SPI::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { @@ -165,3 +167,5 @@ void TFT_SPI::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) } #endif // HAS_SPI_TFT + +#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.h b/Marlin/src/HAL/STM32F1/tft/tft_spi.h index 2bda8c21f724..3416f88f5968 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.h +++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.h @@ -56,7 +56,7 @@ #define DATASIZE_8BIT DATA_SIZE_8BIT #define DATASIZE_16BIT DATA_SIZE_16BIT #define TFT_IO_DRIVER TFT_SPI -#define DMA_MAX_SIZE 0xFFFF +#define DMA_MAX_WORDS 0xFFFF #define DMA_MINC_ENABLE DMA_MINC_MODE #define DMA_MINC_DISABLE 0 @@ -89,8 +89,8 @@ class TFT_SPI { static void WriteSequence(uint16_t *Data, uint16_t Count) { Transmit(DMA_MINC_ENABLE, Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { while (Count > 0) { - Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_SIZE ? DMA_MAX_SIZE : Count); - Count = Count > DMA_MAX_SIZE ? Count - DMA_MAX_SIZE : 0; + Transmit(DMA_MINC_DISABLE, &Color, Count > DMA_MAX_WORDS ? DMA_MAX_WORDS : Count); + Count = Count > DMA_MAX_WORDS ? Count - DMA_MAX_WORDS : 0; } } }; diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp index ac9ad072aa05..bf57ba0034b1 100644 --- a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp @@ -20,6 +20,8 @@ * */ +#ifdef __STM32F1__ + #include "../../../inc/MarlinConfig.h" #if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS @@ -141,4 +143,6 @@ uint16_t XPT2046::SoftwareIO(uint16_t data) { return result; } -#endif // HAS_TFT_XPT2046 +#endif // HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS + +#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/timers.cpp b/Marlin/src/HAL/STM32F1/timers.cpp index 112c730b9acc..12477a458314 100644 --- a/Marlin/src/HAL/STM32F1/timers.cpp +++ b/Marlin/src/HAL/STM32F1/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 0cd807fc8479..f92c32c2a3ef 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2017 Victor Perez + * + * 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 @@ -81,7 +81,7 @@ typedef uint16_t hal_timer_t; #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. + // SKR Mini E3 boards use PA8 as FAN0_PIN, so TIMER 1 is used for Fan PWM. #ifdef STM32_HIGH_DENSITY #define MF_TIMER_SERVO0 8 // tone.cpp uses Timer 4 #else diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index a7aa9f0da211..16594c16a821 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 @@ -101,7 +101,7 @@ uint32_t __get_PRIMASK(void); // CMSIS #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 10 // diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index 415c69222986..cda7e7d16cdf 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -120,7 +120,6 @@ void spiSendBlock(uint8_t token, const uint8_t *buf) { SPI.endTransaction(); } - // Begin SPI transaction, set clock, bit order, data mode void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { spiConfig = SPISettings(spiClock, bitOrder, dataMode); diff --git a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h index c1bbcb121bdc..08ffc256b9b5 100644 --- a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h @@ -47,33 +47,33 @@ void endstop_ISR() { endstops.update(); } void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); - TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN)); - TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN)); - TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN)); - TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN)); - TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN)); - TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 2a192e47189d..692133400390 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 @@ -106,7 +106,7 @@ typedef int8_t pin_t; #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 10 // diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp index b80e93b536a5..a2afa4534345 100644 --- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h index 48d3bbbfa17d..6ba7d7fc6cab 100644 --- a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h @@ -46,33 +46,33 @@ void endstop_ISR() { endstops.update(); } */ void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); - TERN_(HAS_U_MAX, _ATTACH(U_MAX_PIN)); - TERN_(HAS_U_MIN, _ATTACH(U_MIN_PIN)); - TERN_(HAS_V_MAX, _ATTACH(V_MAX_PIN)); - TERN_(HAS_V_MIN, _ATTACH(V_MIN_PIN)); - TERN_(HAS_W_MAX, _ATTACH(W_MAX_PIN)); - TERN_(HAS_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); } diff --git a/Marlin/src/HAL/TEENSY35_36/pinsDebug.h b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h index 7a2e1d6e592e..8526febf10e3 100644 --- a/Marlin/src/HAL/TEENSY35_36/pinsDebug.h +++ b/Marlin/src/HAL/TEENSY35_36/pinsDebug.h @@ -55,12 +55,12 @@ #define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(9)) || ((P) >= analogInputToDigitalPin(12) && (P) <= analogInputToDigitalPin(20)) -void HAL_print_analog_pin(char buffer[], int8_t pin) { +void print_analog_pin(char buffer[], int8_t pin) { if (pin <= 23) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 14)); else if (pin <= 39) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 19)); } -void HAL_analog_pin_state(char buffer[], int8_t pin) { +void analog_pin_state(char buffer[], int8_t pin) { if (pin <= 23) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 14)); else if (pin <= 39) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 19)); } @@ -77,7 +77,7 @@ void HAL_analog_pin_state(char buffer[], int8_t pin) { * Print a pin's PWM status. * Return true if it's currently a PWM pin. */ -bool HAL_pwm_status(int8_t pin) { +bool pwm_status(int8_t pin) { char buffer[20]; // for the sprintf statements switch (pin) { FTM_CASE(0,0); @@ -108,4 +108,4 @@ bool HAL_pwm_status(int8_t pin) { SERIAL_ECHOPGM(" "); } -static void HAL_pwm_details(uint8_t pin) { /* TODO */ } +void pwm_details(uint8_t pin) { /* TODO */ } diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 8af79d73928e..3536b62265f2 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index 1d02ab8575c3..4dd5c3678d78 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -39,9 +39,19 @@ #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) -#if WITHIN(SERIAL_PORT, 0, 3) +#if WITHIN(SERIAL_PORT, 0, 8) IMPLEMENT_SERIAL(SERIAL_PORT); #endif +#ifdef SERIAL_PORT_2 + #if WITHIN(SERIAL_PORT_2, 0, 8) + IMPLEMENT_SERIAL(SERIAL_PORT_2); + #endif +#endif +#ifdef SERIAL_PORT_3 + #if WITHIN(SERIAL_PORT_3, 0, 8) + IMPLEMENT_SERIAL(SERIAL_PORT_3); + #endif +#endif USBSerialType USBSerial(false, SerialUSB); // ------------------------ diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index c54a2e8a0b64..fa5971a68102 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 @@ -80,7 +80,7 @@ extern USBSerialType USBSerial; #define MSERIAL(X) _MSERIAL(X) #if SERIAL_PORT == -1 - #define MYSERIAL1 SerialUSB + #define MYSERIAL1 USBSerial #elif WITHIN(SERIAL_PORT, 0, 8) DECLARE_SERIAL(SERIAL_PORT); #define MYSERIAL1 MSERIAL(SERIAL_PORT) @@ -90,16 +90,28 @@ extern USBSerialType USBSerial; #ifdef SERIAL_PORT_2 #if SERIAL_PORT_2 == -1 - #define MYSERIAL2 usbSerial + #define MYSERIAL2 USBSerial #elif SERIAL_PORT_2 == -2 #define MYSERIAL2 ethernet.telnetClient #elif WITHIN(SERIAL_PORT_2, 0, 8) + DECLARE_SERIAL(SERIAL_PORT_2); #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) #else #error "SERIAL_PORT_2 must be from 0 to 8, or -1 for Native USB, or -2 for Ethernet." #endif #endif +#ifdef SERIAL_PORT_3 + #if SERIAL_PORT_3 == -1 + #define MYSERIAL3 USBSerial + #elif WITHIN(SERIAL_PORT_3, 0, 8) + DECLARE_SERIAL(SERIAL_PORT_3); + #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) + #else + #error "SERIAL_PORT_3 must be from 0 to 8, or -1 for Native USB." + #endif +#endif + // ------------------------ // Types // ------------------------ @@ -124,7 +136,7 @@ typedef int8_t pin_t; #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ADC_VREF 3.3 +#define HAL_ADC_VREF_MV 3300 #define HAL_ADC_RESOLUTION 10 #define HAL_ADC_FILTERED // turn off ADC oversampling diff --git a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp index 3cd376edce62..87f7dd3cfce5 100644 --- a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h index 4c3ddec9f1f1..c646b6be6231 100644 --- a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h @@ -46,27 +46,33 @@ void endstop_ISR() { endstops.update(); } */ void setup_endstop_interrupts() { #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) - TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); - TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); - TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); - TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); - TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); - TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); - TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); - TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); - TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); - TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); - TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); - TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); - TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); - TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); - TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); - TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(USE_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); - TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); - TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); - TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); - TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); - TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); - TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN)); + TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN)); + TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN)); + TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN)); + TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN)); + TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN)); + TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN)); + TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN)); } diff --git a/Marlin/src/HAL/TEENSY40_41/fastio.h b/Marlin/src/HAL/TEENSY40_41/fastio.h index 52f991dfb85f..179f044c9b85 100644 --- a/Marlin/src/HAL/TEENSY40_41/fastio.h +++ b/Marlin/src/HAL/TEENSY40_41/fastio.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/Marlin/src/HAL/TEENSY40_41/pinsDebug.h b/Marlin/src/HAL/TEENSY40_41/pinsDebug.h index fc90f671cffe..54f3cb5885a3 100644 --- a/Marlin/src/HAL/TEENSY40_41/pinsDebug.h +++ b/Marlin/src/HAL/TEENSY40_41/pinsDebug.h @@ -30,7 +30,6 @@ #define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS #define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin -#define PRINT_PORT(p) #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0) #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) @@ -39,7 +38,6 @@ #define VALID_PIN(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL)) #define DIGITAL_PIN_TO_ANALOG_PIN(p) int(p - analogInputToDigitalPin(0)) #define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(13)) || ((P) >= analogInputToDigitalPin(14) && (P) <= analogInputToDigitalPin(17)) -#define pwm_status(pin) HAL_pwm_status(pin) #define GET_PINMODE(PIN) (VALID_PIN(pin) && IS_OUTPUT(pin)) #define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin @@ -120,12 +118,12 @@ const struct pwm_pin_info_struct pwm_pin_info[] = { #endif }; -void HAL_print_analog_pin(char buffer[], int8_t pin) { +void print_analog_pin(char buffer[], const pin_t pin) { if (pin <= 23) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 14)); else if (pin <= 41) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 24)); } -void HAL_analog_pin_state(char buffer[], int8_t pin) { +void analog_pin_state(char buffer[], const pin_t pin) { if (pin <= 23) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 14)); else if (pin <= 41) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 24)); } @@ -136,14 +134,14 @@ void HAL_analog_pin_state(char buffer[], int8_t pin) { * Print a pin's PWM status. * Return true if it's currently a PWM pin. */ -bool HAL_pwm_status(int8_t pin) { +bool pwm_status(const pin_t pin) { char buffer[20]; // for the sprintf statements const struct pwm_pin_info_struct *info; - if (pin >= CORE_NUM_DIGITAL) return 0; - info = pwm_pin_info + pin; + if (pin >= CORE_NUM_DIGITAL) return false; - if (info->type == 0) return 0; + info = pwm_pin_info + pin; + if (info->type == 0) return false; /* TODO decode pwm value from timers */ // for now just indicate if output is set as pwm @@ -151,4 +149,6 @@ bool HAL_pwm_status(int8_t pin) { return (*(portConfigRegister(pin)) == info->muxval); } -static void pwm_details(uint8_t pin) { /* TODO */ } +void pwm_details(const pin_t) { /* TODO */ } + +void print_port(const pin_t) {} diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 77fe0953d3bd..3c7cda0b4e66 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/shared/Delay.cpp b/Marlin/src/HAL/shared/Delay.cpp index c64376d25d9a..8856fe134d8c 100644 --- a/Marlin/src/HAL/shared/Delay.cpp +++ b/Marlin/src/HAL/shared/Delay.cpp @@ -167,7 +167,6 @@ } #endif // MARLIN_DEV_MODE - #else void calibrate_delay_loop() {} diff --git a/Marlin/src/HAL/shared/HAL_ST7920.h b/Marlin/src/HAL/shared/HAL_ST7920.h index 4e362f96ba55..305736c3a514 100644 --- a/Marlin/src/HAL/shared/HAL_ST7920.h +++ b/Marlin/src/HAL/shared/HAL_ST7920.h @@ -27,7 +27,7 @@ * (bypassing U8G), it will allow the LIGHTWEIGHT_UI to operate. */ -#if BOTH(HAS_MARLINUI_U8GLIB, LIGHTWEIGHT_UI) +#if ALL(HAS_MARLINUI_U8GLIB, LIGHTWEIGHT_UI) void ST7920_cs(); void ST7920_ncs(); void ST7920_set_cmd(); diff --git a/Marlin/src/HAL/shared/backtrace/unwarm.cpp b/Marlin/src/HAL/shared/backtrace/unwarm.cpp index e72a02e487cd..823f54c157b4 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarm.cpp @@ -50,7 +50,6 @@ void UnwInvalidateRegisterFile(RegData *regFile) { } while (t < 13); } - /** * Initialize the data used for unwinding. */ @@ -129,7 +128,6 @@ bool UnwReportRetAddr(UnwState * const state, uint32_t addr) { return state->cb->report((void *)state->reportData, &entry); } - /** * Write some register to memory. * This will store some register and meta data onto the virtual stack. diff --git a/Marlin/src/HAL/shared/backtrace/unwarm.h b/Marlin/src/HAL/shared/backtrace/unwarm.h index edae90650e29..72ea0b062767 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm.h +++ b/Marlin/src/HAL/shared/backtrace/unwarm.h @@ -41,7 +41,6 @@ typedef enum { REG_VAL_ARITHMETIC = 0x80 } RegValOrigin; - /** Type for tracking information about a register. * This stores the register value, as well as other data that helps unwinding. */ @@ -56,7 +55,6 @@ typedef struct { int o; /* (RegValOrigin) */ } RegData; - /** Structure used to track reads and writes to memory. * This structure is used as a hash to store a small number of writes * to memory. @@ -81,7 +79,6 @@ typedef struct { uint8_t tracked[(MEM_HASH_SIZE + 7) / 8]; } MemData; - /** Structure that is used to keep track of unwinding meta-data. * This data is passed between all the unwinding functions. */ diff --git a/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp b/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp index 148927a19f52..bd87b6731cdf 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp @@ -55,7 +55,12 @@ static const char *UnwTabGetFunctionName(const UnwindCallbacks *cb, uint32_t add return nullptr; if ((flag_word & 0xFF000000) == 0xFF000000) { - return (const char *)(address - 4 - (flag_word & 0x00FFFFFF)); + const uint32_t fn_name_addr = address - 4 - (flag_word & 0x00FFFFFF); + + // Ensure the address is readable to avoid returning a bogus pointer + uint8_t dummy = 0; + if (cb->readB(fn_name_addr, &dummy)) + return (const char *)fn_name_addr; } return nullptr; } diff --git a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp index a4151b38c20e..da1cff4fcc88 100644 --- a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp @@ -135,7 +135,7 @@ // Generic ARM code, that's testing if an access to the given address would cause a fault or not // It can't guarantee an address is in RAM or Flash only, but we usually don't care - #define NVIC_FAULT_STAT 0xE000ED28 // Configurable Fault Status Reg. + #define NVIC_FAULT_STAT 0xE000ED28 // Configurable Fault Status reg. #define NVIC_CFG_CTRL 0xE000ED14 // Configuration Control Register #define NVIC_FAULT_STAT_BFARV 0x00008000 // BFAR is valid #define NVIC_CFG_CTRL_BFHFNMIGN 0x00000100 // Ignore bus fault in NMI/fault diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp index e54661c77071..f4435c733e06 100644 --- a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp +++ b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2020 Cyril Russo * * 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 @@ -27,7 +26,6 @@ #if defined(__arm__) || defined(__thumb__) - /* On ARM CPUs exception handling is quite powerful. @@ -279,8 +277,6 @@ void CommonHandler_C(ContextStateFrame * frame, unsigned long lr, unsigned long if (!faulted_from_exception) { // Not sure about the non_usage_fault, we want to try anyway, don't we ? && !non_usage_fault_occurred) // Try to resume to our handler here CFSR |= CFSR; // The ARM programmer manual says you must write to 1 all fault bits to clear them so this instruction is correct - // The frame will not be valid when returning anymore, let's clean it - savedFrame.CFSR = 0; frame->pc = (uint32_t)resume_from_fault; // Patch where to return to frame->lr = 0xDEADBEEF; // If our handler returns (it shouldn't), let's make it trigger an exception immediately diff --git a/Marlin/src/HAL/shared/eeprom_api.cpp b/Marlin/src/HAL/shared/eeprom_api.cpp index 47cfa5a2dbe0..62a8f2afbc75 100644 --- a/Marlin/src/HAL/shared/eeprom_api.cpp +++ b/Marlin/src/HAL/shared/eeprom_api.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 @@ -22,7 +21,7 @@ */ #include "../../inc/MarlinConfigPre.h" -#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) +#if ANY(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) #include "eeprom_api.h" PersistentStore persistentStore; diff --git a/Marlin/src/HAL/shared/eeprom_api.h b/Marlin/src/HAL/shared/eeprom_api.h index cd744f82dc79..7be1e72f7ab5 100644 --- a/Marlin/src/HAL/shared/eeprom_api.h +++ b/Marlin/src/HAL/shared/eeprom_api.h @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/shared/eeprom_if.h b/Marlin/src/HAL/shared/eeprom_if.h index e496de2a03c6..8b9791e1f804 100644 --- a/Marlin/src/HAL/shared/eeprom_if.h +++ b/Marlin/src/HAL/shared/eeprom_if.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/shared/fauxpins.h b/Marlin/src/HAL/shared/fauxpins.h new file mode 100644 index 000000000000..924bfba02ae0 --- /dev/null +++ b/Marlin/src/HAL/shared/fauxpins.h @@ -0,0 +1,367 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 + +// +// Faux pins for Dependency Check +// + +// +// STM32 Pin Names +// +#define PA0 0x10 +#define PA1 0x11 +#define PA2 0x12 +#define PA3 0x13 +#define PA4 0x14 +#define PA5 0x15 +#define PA6 0x16 +#define PA7 0x17 +#define PA8 0x18 +#define PA9 0x19 +#define PA10 0x1A +#define PA11 0x1B +#define PA12 0x1C +#define PA13 0x1D +#define PA14 0x1E +#define PA15 0x1F + +#define PB0 0x20 +#define PB1 0x21 +#define PB2 0x22 +#define PB3 0x23 +#define PB4 0x24 +#define PB5 0x25 +#define PB6 0x26 +#define PB7 0x27 +#define PB8 0x28 +#define PB9 0x29 +#define PB10 0x2A +#define PB11 0x2B +#define PB12 0x2C +#define PB13 0x2D +#define PB14 0x2E +#define PB15 0x2F + +#define PC0 0x30 +#define PC1 0x31 +#define PC2 0x32 +#define PC3 0x33 +#define PC4 0x34 +#define PC5 0x35 +#define PC6 0x36 +#define PC7 0x37 +#define PC8 0x38 +#define PC9 0x39 +#define PC10 0x3A +#define PC11 0x3B +#define PC12 0x3C +#define PC13 0x3D +#define PC14 0x3E +#define PC15 0x3F + +#define PD0 0x40 +#define PD1 0x41 +#define PD2 0x42 +#define PD3 0x43 +#define PD4 0x44 +#define PD5 0x45 +#define PD6 0x46 +#define PD7 0x47 +#define PD8 0x48 +#define PD9 0x49 +#define PD10 0x4A +#define PD11 0x4B +#define PD12 0x4C +#define PD13 0x4D +#define PD14 0x4E +#define PD15 0x4F + +#define PE0 0x50 +#define PE1 0x51 +#define PE2 0x52 +#define PE3 0x53 +#define PE4 0x54 +#define PE5 0x55 +#define PE6 0x56 +#define PE7 0x57 +#define PE8 0x58 +#define PE9 0x59 +#define PE10 0x5A +#define PE11 0x5B +#define PE12 0x5C +#define PE13 0x5D +#define PE14 0x5E +#define PE15 0x5F + +#define PF0 0x60 +#define PF1 0x61 +#define PF2 0x62 +#define PF3 0x63 +#define PF4 0x64 +#define PF5 0x65 +#define PF6 0x66 +#define PF7 0x67 +#define PF8 0x68 +#define PF9 0x69 +#define PF10 0x6A +#define PF11 0x6B +#define PF12 0x6C +#define PF13 0x6D +#define PF14 0x6E +#define PF15 0x6F + +#define PG0 0x70 +#define PG1 0x71 +#define PG2 0x72 +#define PG3 0x73 +#define PG4 0x74 +#define PG5 0x75 +#define PG6 0x76 +#define PG7 0x77 +#define PG8 0x78 +#define PG9 0x79 +#define PG10 0x7A +#define PG11 0x7B +#define PG12 0x7C +#define PG13 0x7D +#define PG14 0x7E +#define PG15 0x7F + +#define PH0 0x80 +#define PH1 0x81 +#define PH2 0x82 +#define PH3 0x83 +#define PH4 0x84 +#define PH5 0x85 +#define PH6 0x86 +#define PH7 0x87 +#define PH8 0x88 +#define PH9 0x89 +#define PH10 0x8A +#define PH11 0x8B +#define PH12 0x8C +#define PH13 0x8D +#define PH14 0x8E +#define PH15 0x8F + +#define PI0 0x90 +#define PI1 0x91 +#define PI2 0x92 +#define PI3 0x93 +#define PI4 0x94 +#define PI5 0x95 +#define PI6 0x96 +#define PI7 0x97 +#define PI8 0x98 +#define PI9 0x99 +#define PI10 0x9A +#define PI11 0x9B +#define PI12 0x9C +#define PI13 0x9D +#define PI14 0x9E +#define PI15 0x9F + +#define PJ0 0xA0 +#define PJ1 0xA1 +#define PJ2 0xA2 +#define PJ3 0xA3 +#define PJ4 0xA4 +#define PJ5 0xA5 +#define PJ6 0xA6 +#define PJ7 0xA7 +#define PJ8 0xA8 +#define PJ9 0xA9 +#define PJ10 0xAA +#define PJ11 0xAB +#define PJ12 0xAC +#define PJ13 0xAD +#define PJ14 0xAE +#define PJ15 0xAF + +// +// LPC Pin Names +// +#define P0_00 100 +#define P0_01 101 +#define P0_02 102 +#define P0_03 103 +#define P0_04 104 +#define P0_05 105 +#define P0_06 106 +#define P0_07 107 +#define P0_08 108 +#define P0_09 109 +#define P0_10 110 +#define P0_11 111 +#define P0_12 112 +#define P0_13 113 +#define P0_14 114 +#define P0_15 115 +#define P0_16 116 +#define P0_17 117 +#define P0_18 118 +#define P0_19 119 +#define P0_20 120 +#define P0_21 121 +#define P0_22 122 +#define P0_23 123 +#define P0_24 124 +#define P0_25 125 +#define P0_26 126 +#define P0_27 127 +#define P0_28 128 +#define P0_29 129 +#define P0_30 130 +#define P0_31 131 + +#define P1_00 200 +#define P1_01 201 +#define P1_02 202 +#define P1_03 203 +#define P1_04 204 +#define P1_05 205 +#define P1_06 206 +#define P1_07 207 +#define P1_08 208 +#define P1_09 209 +#define P1_10 210 +#define P1_11 211 +#define P1_12 212 +#define P1_13 213 +#define P1_14 214 +#define P1_15 215 +#define P1_16 216 +#define P1_17 217 +#define P1_18 218 +#define P1_19 219 +#define P1_20 220 +#define P1_21 221 +#define P1_22 222 +#define P1_23 223 +#define P1_24 224 +#define P1_25 225 +#define P1_26 226 +#define P1_27 227 +#define P1_28 228 +#define P1_29 229 +#define P1_30 230 +#define P1_31 231 + +#define P2_00 300 +#define P2_01 301 +#define P2_02 302 +#define P2_03 303 +#define P2_04 304 +#define P2_05 305 +#define P2_06 306 +#define P2_07 307 +#define P2_08 308 +#define P2_09 309 +#define P2_10 310 +#define P2_11 311 +#define P2_12 312 +#define P2_13 313 +#define P2_14 314 +#define P2_15 315 +#define P2_16 316 +#define P2_17 317 +#define P2_18 318 +#define P2_19 319 +#define P2_20 320 +#define P2_21 321 +#define P2_22 322 +#define P2_23 323 +#define P2_24 324 +#define P2_25 325 +#define P2_26 326 +#define P2_27 327 +#define P2_28 328 +#define P2_29 329 +#define P2_30 330 +#define P2_31 331 + +#define P3_00 400 +#define P3_01 401 +#define P3_02 402 +#define P3_03 403 +#define P3_04 404 +#define P3_05 405 +#define P3_06 406 +#define P3_07 407 +#define P3_08 408 +#define P3_09 409 +#define P3_10 410 +#define P3_11 411 +#define P3_12 412 +#define P3_13 413 +#define P3_14 414 +#define P3_15 415 +#define P3_16 416 +#define P3_17 417 +#define P3_18 418 +#define P3_19 419 +#define P3_20 420 +#define P3_21 421 +#define P3_22 422 +#define P3_23 423 +#define P3_24 424 +#define P3_25 425 +#define P3_26 426 +#define P3_27 427 +#define P3_28 428 +#define P3_29 429 +#define P3_30 430 +#define P3_31 431 + +#define P4_00 500 +#define P4_01 501 +#define P4_02 502 +#define P4_03 503 +#define P4_04 504 +#define P4_05 505 +#define P4_06 506 +#define P4_07 507 +#define P4_08 508 +#define P4_09 509 +#define P4_10 510 +#define P4_11 511 +#define P4_12 512 +#define P4_13 513 +#define P4_14 514 +#define P4_15 515 +#define P4_16 516 +#define P4_17 517 +#define P4_18 518 +#define P4_19 519 +#define P4_20 520 +#define P4_21 521 +#define P4_22 522 +#define P4_23 523 +#define P4_24 524 +#define P4_25 525 +#define P4_26 526 +#define P4_27 527 +#define P4_28 528 +#define P4_29 529 +#define P4_30 530 +#define P4_31 531 diff --git a/Marlin/src/HAL/shared/servo.cpp b/Marlin/src/HAL/shared/servo.cpp index b838800de654..543bc8e873ae 100644 --- a/Marlin/src/HAL/shared/servo.cpp +++ b/Marlin/src/HAL/shared/servo.cpp @@ -60,14 +60,14 @@ ServoInfo_t servo_info[MAX_SERVOS]; // static array of servo info structures uint8_t ServoCount = 0; // the total number of attached servos -#define SERVO_MIN(v) (MIN_PULSE_WIDTH - (v) * 4) // minimum value in uS for this servo -#define SERVO_MAX(v) (MAX_PULSE_WIDTH - (v) * 4) // maximum value in uS for this servo +#define SERVO_MIN_US(v) (MIN_PULSE_WIDTH - (v) * 4) // minimum value in uS for this servo +#define SERVO_MAX_US(v) (MAX_PULSE_WIDTH - (v) * 4) // maximum value in uS for this servo /************ static functions common to all instances ***********************/ static bool anyTimerChannelActive(const timer16_Sequence_t timer) { // returns true if any servo is active on this timer - LOOP_L_N(channel, SERVOS_PER_TIMER) { + for (uint8_t channel = 0; channel < SERVOS_PER_TIMER; ++channel) { if (SERVO(timer, channel).Pin.isActive) return true; } @@ -117,7 +117,7 @@ void Servo::detach() { void Servo::write(int value) { if (value < MIN_PULSE_WIDTH) // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds) - value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(min), SERVO_MAX(max)); + value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN_US(min), SERVO_MAX_US(max)); writeMicroseconds(value); } @@ -126,8 +126,8 @@ void Servo::writeMicroseconds(int value) { byte channel = servoIndex; if (channel < MAX_SERVOS) { // ensure channel is valid // ensure pulse width is valid - value = constrain(value, SERVO_MIN(min), SERVO_MAX(max)) - (TRIM_DURATION); - value = usToTicks(value); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009 + LIMIT(value, SERVO_MIN_US(min), SERVO_MAX_US(max)); + value = usToTicks(value - (TRIM_DURATION)); // convert to ticks after compensating for interrupt overhead - 12 Aug 2009 CRITICAL_SECTION_START(); servo_info[channel].ticks = value; @@ -136,7 +136,7 @@ void Servo::writeMicroseconds(int value) { } // return the value as degrees -int Servo::read() { return map(readMicroseconds() + 1, SERVO_MIN(min), SERVO_MAX(max), 0, 180); } +int Servo::read() { return map(readMicroseconds() + 1, SERVO_MIN_US(min), SERVO_MAX_US(max), 0, 180); } int Servo::readMicroseconds() { return (servoIndex == INVALID_SERVO) ? 0 : ticksToUs(servo_info[servoIndex].ticks) + (TRIM_DURATION); diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 0ca4199fcd6d..e21c89be2111 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -157,7 +157,7 @@ #include "feature/spindle_laser.h" #endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA CardReader card; #endif @@ -194,7 +194,7 @@ #include "feature/runout.h" #endif -#if EITHER(PROBE_TARE, HAS_Z_SERVO_PROBE) +#if ANY(PROBE_TARE, HAS_Z_SERVO_PROBE) #include "module/probe.h" #endif @@ -316,7 +316,7 @@ bool pin_is_protected(const pin_t pin) { static constexpr size_t pincount = OnlyPins::size; static const pin_t (&sensitive_pins)[pincount] PROGMEM = OnlyPins::table; #endif - LOOP_L_N(i, pincount) { + for (uint8_t i = 0; i < pincount; ++i) { const pin_t * const pptr = &sensitive_pins[i]; if (pin == (sizeof(pin_t) == 2 ? (pin_t)pgm_read_word(pptr) : (pin_t)pgm_read_byte(pptr))) return true; } @@ -351,14 +351,12 @@ void startOrResumeJob() { TERN_(GCODE_REPEAT_MARKERS, repeat.reset()); TERN_(CANCEL_OBJECTS, cancelable.reset()); TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator = 0); - #if ENABLED(SET_REMAINING_TIME) - ui.reset_remaining_time(); - #endif + TERN_(SET_REMAINING_TIME, ui.reset_remaining_time()); } print_job_timer.start(); } -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA inline void abortSDPrinting() { IF_DISABLED(NO_SD_AUTOSTART, card.autofile_cancel()); @@ -392,7 +390,7 @@ void startOrResumeJob() { } } -#endif // SDSUPPORT +#endif // HAS_MEDIA /** * Minimal management of Marlin's core activities: @@ -431,7 +429,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { if (has_blocks) gcode.reset_stepper_timeout(ms); // Reset timeout for M18/M84, M85 max 'kill', and laser. // M18 / M84 : Handle steppers inactive time timeout - #if HAS_DISABLE_INACTIVE_AXIS + #if HAS_DISABLE_IDLE_AXES if (gcode.stepper_inactive_time) { static bool already_shutdown_steppers; // = false @@ -441,16 +439,16 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { already_shutdown_steppers = true; // Individual axes will be disabled if configured - TERN_(DISABLE_INACTIVE_X, stepper.disable_axis(X_AXIS)); - TERN_(DISABLE_INACTIVE_Y, stepper.disable_axis(Y_AXIS)); - TERN_(DISABLE_INACTIVE_Z, stepper.disable_axis(Z_AXIS)); - TERN_(DISABLE_INACTIVE_I, stepper.disable_axis(I_AXIS)); - TERN_(DISABLE_INACTIVE_J, stepper.disable_axis(J_AXIS)); - TERN_(DISABLE_INACTIVE_K, stepper.disable_axis(K_AXIS)); - TERN_(DISABLE_INACTIVE_U, stepper.disable_axis(U_AXIS)); - TERN_(DISABLE_INACTIVE_V, stepper.disable_axis(V_AXIS)); - TERN_(DISABLE_INACTIVE_W, stepper.disable_axis(W_AXIS)); - TERN_(DISABLE_INACTIVE_E, stepper.disable_e_steppers()); + TERN_(DISABLE_IDLE_X, stepper.disable_axis(X_AXIS)); + TERN_(DISABLE_IDLE_Y, stepper.disable_axis(Y_AXIS)); + TERN_(DISABLE_IDLE_Z, stepper.disable_axis(Z_AXIS)); + TERN_(DISABLE_IDLE_I, stepper.disable_axis(I_AXIS)); + TERN_(DISABLE_IDLE_J, stepper.disable_axis(J_AXIS)); + TERN_(DISABLE_IDLE_K, stepper.disable_axis(K_AXIS)); + TERN_(DISABLE_IDLE_U, stepper.disable_axis(U_AXIS)); + TERN_(DISABLE_IDLE_V, stepper.disable_axis(V_AXIS)); + TERN_(DISABLE_IDLE_W, stepper.disable_axis(W_AXIS)); + TERN_(DISABLE_IDLE_E, stepper.disable_e_steppers()); TERN_(AUTO_BED_LEVELING_UBL, bedlevel.steppers_were_disabled()); } @@ -825,11 +823,11 @@ void idle(const bool no_stepper_sleep/*=false*/) { // Run StallGuard endstop checks #if ENABLED(SPI_ENDSTOPS) if (endstops.tmc_spi_homing.any && TERN1(IMPROVE_HOMING_RELIABILITY, ELAPSED(millis(), sg_guard_period))) - LOOP_L_N(i, 4) if (endstops.tmc_spi_homing_check()) break; // Read SGT 4 times per idle loop + for (uint8_t i = 0; i < 4; ++i) if (endstops.tmc_spi_homing_check()) break; // Read SGT 4 times per idle loop #endif // Handle SD Card insert / remove - TERN_(SDSUPPORT, card.manage_media()); + TERN_(HAS_MEDIA, card.manage_media()); // Handle USB Flash Drive insert / remove TERN_(USB_FLASH_DRIVE_SUPPORT, card.diskIODriver()->idle()); @@ -940,7 +938,7 @@ void minkill(const bool steppers_off/*=false*/) { TERN_(HAS_SUICIDE, suicide()); - #if EITHER(HAS_KILL, SOFT_RESET_ON_KILL) + #if ANY(HAS_KILL, SOFT_RESET_ON_KILL) // Wait for both KILL and ENC to be released while (TERN0(HAS_KILL, kill_state()) || TERN0(SOFT_RESET_ON_KILL, ui.button_pressed())) @@ -969,7 +967,7 @@ void stop() { print_job_timer.stop(); - #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) + #if ANY(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) thermalManager.set_fans_paused(false); // Un-pause fans for safety #endif @@ -1079,7 +1077,7 @@ inline void tmc_standby_setup() { * - Init the buzzer, possibly a custom timer * - Init more optional hardware: * • Color LED illumination - * • Neopixel illumination + * • NeoPixel illumination * • Controller Fan * • Creality DWIN LCD (show boot image) * • Tare the Probe if possible @@ -1331,14 +1329,14 @@ void setup() { #endif #endif - #if BOTH(SDSUPPORT, SDCARD_EEPROM_EMULATION) + #if ALL(HAS_MEDIA, SDCARD_EEPROM_EMULATION) SETUP_RUN(card.mount()); // Mount media with settings before first_load #endif SETUP_RUN(settings.first_load()); // Load data from EEPROM if available (or use defaults) // This also updates variables in the planner, elsewhere - #if BOTH(HAS_WIRED_LCD, SHOW_BOOTSCREEN) + #if ALL(HAS_WIRED_LCD, SHOW_BOOTSCREEN) SETUP_RUN(ui.show_bootscreen()); const millis_t bootscreen_ms = millis(); #endif @@ -1413,7 +1411,7 @@ void setup() { SETUP_RUN(stepper_dac.init()); #endif - #if EITHER(Z_PROBE_SLED, SOLENOID_PROBE) && HAS_SOLENOID_1 + #if ANY(Z_PROBE_SLED, SOLENOID_PROBE) && HAS_SOLENOID_1 OUT_WRITE(SOL1_PIN, LOW); // OFF #endif @@ -1615,13 +1613,13 @@ void setup() { #endif #if HAS_TFT_LVGL_UI - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (!card.isMounted()) SETUP_RUN(card.mount()); // Mount SD to load graphics and fonts #endif SETUP_RUN(tft_lvgl_init()); #endif - #if BOTH(HAS_WIRED_LCD, SHOW_BOOTSCREEN) + #if ALL(HAS_WIRED_LCD, SHOW_BOOTSCREEN) const millis_t elapsed = millis() - bootscreen_ms; #if ENABLED(MARLIN_DEV_MODE) SERIAL_ECHOLNPGM("elapsed=", elapsed); @@ -1633,7 +1631,7 @@ void setup() { SETUP_RUN(password.lock_machine()); // Will not proceed until correct password provided #endif - #if BOTH(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) && EITHER(TFT_CLASSIC_UI, TFT_COLOR_UI) + #if ALL(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) && ANY(TFT_CLASSIC_UI, TFT_COLOR_UI) SETUP_RUN(ui.check_touch_calibration()); #endif @@ -1673,14 +1671,14 @@ void loop() { do { idle(); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (card.flag.abort_sd_printing) abortSDPrinting(); if (marlin_state == MF_SD_COMPLETE) finishSDPrinting(); #endif queue.advance(); - #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) powerManager.checkAutoPowerOff(); #endif diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 4963945fc120..ed5b649f240d 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -308,9 +308,9 @@ // #define BOARD_BTT_EBB42_V1_1 4000 // BigTreeTech EBB42 V1.1 (STM32G0B1CB) -#define BOARD_BTT_SKR_MINI_E3_V3_0 4001 // BigTreeTech SKR Mini E3 V3.0 (STM32G0B1RE) +#define BOARD_BTT_SKR_MINI_E3_V3_0 4001 // BigTreeTech SKR Mini E3 V3.0 (STM32G0B0RE / STM32G0B1RE) #define BOARD_BTT_MANTA_E3_EZ_V1_0 4002 // BigTreeTech Manta E3 EZ V1.0 (STM32G0B1RE) -#define BOARD_BTT_MANTA_M4P_V1_0 4003 // BigTreeTech Manta M4P V1.0 (STM32G0B1RE) +#define BOARD_BTT_MANTA_M4P_V2_1 4003 // BigTreeTech Manta M4P V2.1 (STM32G0B0RE) #define BOARD_BTT_MANTA_M5P_V1_0 4004 // BigTreeTech Manta M5P V1.0 (STM32G0B1RE) #define BOARD_BTT_MANTA_M8P_V1_0 4005 // BigTreeTech Manta M8P V1.0 (STM32G0B1VE) #define BOARD_BTT_MANTA_M8P_V1_1 4006 // BigTreeTech Manta M8P V1.1 (STM32G0B1VE) @@ -386,7 +386,7 @@ #define BOARD_ZONESTAR_ZM3E4V2 5064 // Zonestar ZM3E4 V2 (STM32F103VC) #define BOARD_ERYONE_ERY32_MINI 5065 // Eryone Ery32 mini (STM32F103VE) #define BOARD_PANDA_PI_V29 5066 // Panda Pi V2.9 - Standalone (STM32F103RC) -#define BOARD_SOVOL_V131 5067 // Sovol V1.3.1 (GD32F103RET6) +#define BOARD_SOVOL_V131 5067 // Sovol V1.3.1 (GD32F103RE) // // ARM Cortex-M4F @@ -420,31 +420,30 @@ #define BOARD_LERDGE_K 5218 // Lerdge K (STM32F407ZG) #define BOARD_LERDGE_S 5219 // Lerdge S (STM32F407VE) #define BOARD_LERDGE_X 5220 // Lerdge X (STM32F407VE) -#define BOARD_VAKE403D 5221 // VAkE 403D (STM32F446VE) -#define BOARD_FYSETC_S6 5222 // FYSETC S6 (STM32F446VE) -#define BOARD_FYSETC_S6_V2_0 5223 // FYSETC S6 v2.0 (STM32F446VE) -#define BOARD_FYSETC_SPIDER 5224 // FYSETC Spider (STM32F446VE) -#define BOARD_FLYF407ZG 5225 // FLYmaker FLYF407ZG (STM32F407ZG) -#define BOARD_MKS_ROBIN2 5226 // MKS Robin2 V1.0 (STM32F407ZE) -#define BOARD_MKS_ROBIN_PRO_V2 5227 // MKS Robin Pro V2 (STM32F407VE) -#define BOARD_MKS_ROBIN_NANO_V3 5228 // MKS Robin Nano V3 (STM32F407VG) -#define BOARD_MKS_ROBIN_NANO_V3_1 5229 // MKS Robin Nano V3.1 (STM32F407VE) -#define BOARD_MKS_MONSTER8_V1 5230 // MKS Monster8 V1 (STM32F407VE) -#define BOARD_MKS_MONSTER8_V2 5231 // MKS Monster8 V2 (STM32F407VE) -#define BOARD_ANET_ET4 5232 // ANET ET4 V1.x (STM32F407VG) -#define BOARD_ANET_ET4P 5233 // ANET ET4P V1.x (STM32F407VG) -#define BOARD_FYSETC_CHEETAH_V20 5234 // FYSETC Cheetah V2.0 (STM32F401RC) -#define BOARD_TH3D_EZBOARD_V2 5235 // TH3D EZBoard v2.0 (STM32F405RG) -#define BOARD_OPULO_LUMEN_REV3 5236 // Opulo Lumen PnP Controller REV3 (STM32F407VE / STM32F407VG) -#define BOARD_MKS_ROBIN_NANO_V1_3_F4 5237 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VE) -#define BOARD_MKS_EAGLE 5238 // MKS Eagle (STM32F407VE) -#define BOARD_ARTILLERY_RUBY 5239 // Artillery Ruby (STM32F401RC) -#define BOARD_FYSETC_SPIDER_V2_2 5240 // FYSETC Spider V2.2 (STM32F446VE) -#define BOARD_CREALITY_V24S1_301F4 5241 // Creality v2.4.S1_301F4 (STM32F401RC) as found in the Ender-3 S1 F4 -#define BOARD_OPULO_LUMEN_REV4 5242 // Opulo Lumen PnP Controller REV4 (STM32F407VE / STM32F407VG) -#define BOARD_FYSETC_SPIDER_KING407 5243 // FYSETC Spider King407 (STM32F407ZG) -#define BOARD_MKS_SKIPR_V1 5244 // MKS SKIPR v1.0 all-in-one board (STM32F407VE) -#define BOARD_TRONXY_V10 5245 // TRONXY V10 (STM32F446ZE) +#define BOARD_FYSETC_S6 5221 // FYSETC S6 (STM32F446VE) +#define BOARD_FYSETC_S6_V2_0 5222 // FYSETC S6 v2.0 (STM32F446VE) +#define BOARD_FYSETC_SPIDER 5223 // FYSETC Spider (STM32F446VE) +#define BOARD_FLYF407ZG 5224 // FLYmaker FLYF407ZG (STM32F407ZG) +#define BOARD_MKS_ROBIN2 5225 // MKS Robin2 V1.0 (STM32F407ZE) +#define BOARD_MKS_ROBIN_PRO_V2 5226 // MKS Robin Pro V2 (STM32F407VE) +#define BOARD_MKS_ROBIN_NANO_V3 5227 // MKS Robin Nano V3 (STM32F407VG) +#define BOARD_MKS_ROBIN_NANO_V3_1 5228 // MKS Robin Nano V3.1 (STM32F407VE) +#define BOARD_MKS_MONSTER8_V1 5229 // MKS Monster8 V1 (STM32F407VE) +#define BOARD_MKS_MONSTER8_V2 5230 // MKS Monster8 V2 (STM32F407VE) +#define BOARD_ANET_ET4 5231 // ANET ET4 V1.x (STM32F407VG) +#define BOARD_ANET_ET4P 5232 // ANET ET4P V1.x (STM32F407VG) +#define BOARD_FYSETC_CHEETAH_V20 5233 // FYSETC Cheetah V2.0 (STM32F401RC) +#define BOARD_TH3D_EZBOARD_V2 5234 // TH3D EZBoard v2.0 (STM32F405RG) +#define BOARD_OPULO_LUMEN_REV3 5235 // Opulo Lumen PnP Controller REV3 (STM32F407VE / STM32F407VG) +#define BOARD_MKS_ROBIN_NANO_V1_3_F4 5236 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VE) +#define BOARD_MKS_EAGLE 5237 // MKS Eagle (STM32F407VE) +#define BOARD_ARTILLERY_RUBY 5238 // Artillery Ruby (STM32F401RC) +#define BOARD_FYSETC_SPIDER_V2_2 5239 // FYSETC Spider V2.2 (STM32F446VE) +#define BOARD_CREALITY_V24S1_301F4 5240 // Creality v2.4.S1_301F4 (STM32F401RC) as found in the Ender-3 S1 F4 +#define BOARD_OPULO_LUMEN_REV4 5241 // Opulo Lumen PnP Controller REV4 (STM32F407VE / STM32F407VG) +#define BOARD_FYSETC_SPIDER_KING407 5242 // FYSETC Spider King407 (STM32F407ZG) +#define BOARD_MKS_SKIPR_V1 5243 // MKS SKIPR v1.0 all-in-one board (STM32F407VE) +#define BOARD_TRONXY_V10 5244 // TRONXY V10 (STM32F446ZE) // // ARM Cortex-M7 @@ -456,9 +455,9 @@ #define BOARD_NUCLEO_F767ZI 6003 // ST NUCLEO-F767ZI Dev Board #define BOARD_BTT_SKR_SE_BX_V2 6004 // BigTreeTech SKR SE BX V2.0 (STM32H743II) #define BOARD_BTT_SKR_SE_BX_V3 6005 // BigTreeTech SKR SE BX V3.0 (STM32H743II) -#define BOARD_BTT_SKR_V3_0 6006 // BigTreeTech SKR V3.0 (STM32H743VG) -#define BOARD_BTT_SKR_V3_0_EZ 6007 // BigTreeTech SKR V3.0 EZ (STM32H743VG) -#define BOARD_BTT_OCTOPUS_MAX_EZ_V1_0 6008 // BigTreeTech Octopus Max EZ V1.0 (STM32H723VE / STM32H723ZE) +#define BOARD_BTT_SKR_V3_0 6006 // BigTreeTech SKR V3.0 (STM32H743VI / STM32H723VG) +#define BOARD_BTT_SKR_V3_0_EZ 6007 // BigTreeTech SKR V3.0 EZ (STM32H743VI / STM32H723VG) +#define BOARD_BTT_OCTOPUS_MAX_EZ_V1_0 6008 // BigTreeTech Octopus Max EZ V1.0 (STM32H723ZE) // // Espressif ESP32 WiFi diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 72a7d1f4b7eb..2f589b3e1d42 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -120,6 +120,10 @@ #define HAS_TMC220x 1 #endif +#if HAS_DRIVER(TMC26X) + #define HAS_TMC26X 1 +#endif + #define AXIS_IS_TMC(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ || AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) \ || AXIS_DRIVER_TYPE(A,TMC2660) \ @@ -184,10 +188,3 @@ #if ANY_AXIS_HAS(SPI) #define HAS_TMC_SPI 1 #endif - -// -// TMC26XX Stepper Drivers -// -#if HAS_DRIVER(TMC26X) - #define HAS_TMC26X 1 -#endif diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 58d9eb5848a5..443d73bfcf38 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -153,7 +153,7 @@ #define STR_ERR_ARC_ARGS "G2/G3 bad parameters" #define STR_ERR_PROTECTED_PIN "Protected Pin" #define STR_ERR_M420_FAILED "Failed to enable Bed Leveling" -#define STR_ERR_M428_TOO_FAR "Too far from reference point" +#define STR_ERR_M428_TOO_FAR "Too far from MIN/MAX" #define STR_ERR_M303_DISABLED "PIDTEMP disabled" #define STR_M119_REPORT "Reporting endstop status" #define STR_ON "ON" @@ -323,10 +323,12 @@ // // Endstop Names used by Endstops::report_states // -#define STR_X_MIN "x_min" -#define STR_X_MAX "x_max" -#define STR_X2_MIN "x2_min" -#define STR_X2_MAX "x2_max" +#if HAS_X_AXIS + #define STR_X_MIN "x_min" + #define STR_X_MAX "x_max" + #define STR_X2_MIN "x2_min" + #define STR_X2_MAX "x2_max" +#endif #if HAS_Y_AXIS #define STR_Y_MIN "y_min" @@ -503,7 +505,7 @@ #define STR_W "" #endif -#if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) +#if ANY(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) // Custom characters defined in the first 8 characters of the LCD #define LCD_STR_BEDTEMP "\x00" // Print only as a char. This will have 'unexpected' results when used in a string! diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index fce7d4eb763f..47ba840d2b2c 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -82,11 +82,12 @@ #define FORCE_INLINE __attribute__((always_inline)) inline #define NO_INLINE __attribute__((noinline)) #define _UNUSED __attribute__((unused)) -#define __O0 __attribute__((optimize("O0"))) -#define __Os __attribute__((optimize("Os"))) -#define __O1 __attribute__((optimize("O1"))) -#define __O2 __attribute__((optimize("O2"))) -#define __O3 __attribute__((optimize("O3"))) +#define __O0 __attribute__((optimize("O0"))) // No optimization and less debug info +#define __Og __attribute__((optimize("Og"))) // Optimize the debugging experience +#define __Os __attribute__((optimize("Os"))) // Optimize for size +#define __O1 __attribute__((optimize("O1"))) // Try to reduce size and cycles; nothing that takes a lot of time to compile +#define __O2 __attribute__((optimize("O2"))) // Optimize even more +#define __O3 __attribute__((optimize("O3"))) // Optimize yet more #define IS_CONSTEXPR(...) __builtin_constant_p(__VA_ARGS__) // Only valid solution with C++14. Should use std::is_constant_evaluated() in C++20 instead @@ -223,22 +224,25 @@ #define _DO_N(W,C,N,V...) __DO_N(W,C,N,V) #define DO(W,C,V...) (_DO_N(W,C,NUM_ARGS(V),V)) -// Macros to support option testing +// Concatenate symbol names, without or with pre-expansion #define _CAT(a,V...) a##V #define CAT(a,V...) _CAT(a,V) +// Recognize "true" values: blank, 1, 0x1, true #define _ISENA_ ~,1 #define _ISENA_1 ~,1 #define _ISENA_0x1 ~,1 #define _ISENA_true ~,1 #define _ISENA(V...) IS_PROBE(V) +// Macros to evaluate simple option switches #define _ENA_1(O) _ISENA(CAT(_IS,CAT(ENA_, O))) #define _DIS_1(O) NOT(_ENA_1(O)) #define ENABLED(V...) DO(ENA,&&,V) #define DISABLED(V...) DO(DIS,&&,V) #define COUNT_ENABLED(V...) DO(ENA,+,V) +// Ternary pre-compiler macros conceal non-emitted content from the compiler #define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION ? 'A' : 'B' #define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION ? 'A' : '0' #define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION ? 'A' : '1' @@ -247,6 +251,7 @@ #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. +// Macros to conditionally emit array items and function arguments #define _OPTITEM(A...) A, #define OPTITEM(O,A...) TERN_(O,DEFER4(_OPTITEM)(A)) #define _OPTARG(A...) , A @@ -254,12 +259,16 @@ #define _OPTCODE(A) A; #define OPTCODE(O,A) TERN_(O,DEFER4(_OPTCODE)(A)) -// Macros to avoid 'f + 0.0' which is not always optimized away. Minus included for symmetry. +// Macros to avoid operations that aren't always optimized away (e.g., 'f + 0.0' and 'f * 1.0'). // Compiler flags -fno-signed-zeros -ffinite-math-only also cover 'f * 1.0', 'f - f', etc. #define PLUS_TERN0(O,A) _TERN(_ENA_1(O),,+ (A)) // OPTION ? '+ (A)' : '' #define MINUS_TERN0(O,A) _TERN(_ENA_1(O),,- (A)) // OPTION ? '- (A)' : '' +#define MUL_TERN1(O,A) _TERN(_ENA_1(O),,* (A)) // OPTION ? '* (A)' : '' +#define DIV_TERN1(O,A) _TERN(_ENA_1(O),,/ (A)) // OPTION ? '/ (A)' : '' #define SUM_TERN(O,B,A) ((B) PLUS_TERN0(O,A)) // ((B) (OPTION ? '+ (A)' : '')) #define DIFF_TERN(O,B,A) ((B) MINUS_TERN0(O,A)) // ((B) (OPTION ? '- (A)' : '')) +#define MUL_TERN(O,B,A) ((B) MUL_TERN1(O,A)) // ((B) (OPTION ? '* (A)' : '')) +#define DIV_TERN(O,B,A) ((B) DIV_TERN1(O,A)) // ((B) (OPTION ? '/ (A)' : '')) #define IF_ENABLED TERN_ #define IF_DISABLED(O,A) TERN(O,,A) @@ -282,6 +291,7 @@ #define BUTTONS_EXIST(V...) DO(BTNEX,&&,V) #define ANY_BUTTON(V...) DO(BTNEX,||,V) +// Value helper macros #define WITHIN(N,L,H) ((N) >= (L) && (N) <= (H)) #define ISEOL(C) ((C) == '\n' || (C) == '\r') #define NUMERIC(a) WITHIN(a, '0', '9') @@ -289,6 +299,8 @@ #define HEXCHR(a) (NUMERIC(a) ? (a) - '0' : WITHIN(a, 'a', 'f') ? ((a) - 'a' + 10) : WITHIN(a, 'A', 'F') ? ((a) - 'A' + 10) : -1) #define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-' || (a) == '+') #define DECIMAL_SIGNED(a) (DECIMAL(a) || (a) == '-' || (a) == '+') + +// Array shorthand #define COUNT(a) (sizeof(a)/sizeof(*a)) #define ZERO(a) memset((void*)a,0,sizeof(a)) #define COPY(a,b) do{ \ @@ -296,6 +308,7 @@ memcpy(&a[0],&b[0],_MIN(sizeof(a),sizeof(b))); \ }while(0) +// Expansion of some code #define CODE_16( A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,...) A; B; C; D; E; F; G; H; I; J; K; L; M; N; O; P #define CODE_15( A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,...) A; B; C; D; E; F; G; H; I; J; K; L; M; N; O #define CODE_14( A,B,C,D,E,F,G,H,I,J,K,L,M,N,...) A; B; C; D; E; F; G; H; I; J; K; L; M; N @@ -316,6 +329,7 @@ #define _CODE_N(N,V...) CODE_##N(V) #define CODE_N(N,V...) _CODE_N(N,V) +// Expansion of some non-delimited content #define GANG_16(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,...) A B C D E F G H I J K L M N O P #define GANG_15(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,...) A B C D E F G H I J K L M N O #define GANG_14(A,B,C,D,E,F,G,H,I,J,K,L,M,N,...) A B C D E F G H I J K L M N @@ -337,7 +351,7 @@ #define GANG_N(N,V...) _GANG_N(N,V) #define GANG_N_1(N,K) _GANG_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K) -// Macros for initializing arrays +// Expansion of some list items #define LIST_26(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z #define LIST_25(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y #define LIST_24(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X @@ -375,11 +389,6 @@ #define _JOIN_1(O) (O) #define JOIN_N(N,C,V...) (DO(JOIN,C,LIST_N(N,V))) -#define LOOP_S_LE_N(VAR, S, N) for (uint8_t VAR=(S); VAR<=(N); VAR++) -#define LOOP_S_L_N(VAR, S, N) for (uint8_t VAR=(S); VAR<(N); VAR++) -#define LOOP_LE_N(VAR, N) LOOP_S_LE_N(VAR, 0, N) -#define LOOP_L_N(VAR, N) LOOP_S_L_N(VAR, 0, N) - #define NOOP (void(0)) #define CEILING(x,y) (((x) + (y) - 1) / (y)) @@ -429,6 +438,8 @@ extern "C++" { // C++11 solution that is standards compliant. Return type is deduced automatically + template static constexpr N _MIN(const N val) { return val; } + template static constexpr N _MAX(const N val) { return val; } template static constexpr auto _MIN(const L lhs, const R rhs) -> decltype(lhs + rhs) { return lhs < rhs ? lhs : rhs; } @@ -448,9 +459,9 @@ FORCE_INLINE constexpr T operator|(T x, T y) { return static_cast(static_cast(x) | static_cast(y)); } \ FORCE_INLINE constexpr T operator^(T x, T y) { return static_cast(static_cast(x) ^ static_cast(y)); } \ FORCE_INLINE constexpr T operator~(T x) { return static_cast(~static_cast(x)); } \ - FORCE_INLINE T & operator&=(T &x, T y) { return x &= y; } \ - FORCE_INLINE T & operator|=(T &x, T y) { return x |= y; } \ - FORCE_INLINE T & operator^=(T &x, T y) { return x ^= y; } + FORCE_INLINE T & operator&=(T &x, T y) { x = x & y; return x; } \ + FORCE_INLINE T & operator|=(T &x, T y) { x = x | y; return x; } \ + FORCE_INLINE T & operator^=(T &x, T y) { x = x ^ y; return x; } // C++11 solution that is standard compliant. is not available on all platform namespace Private { @@ -462,7 +473,41 @@ template struct first_type_of { typedef T type; }; template struct first_type_of { typedef T type; }; + + // remove const/volatile type qualifiers + template struct remove_const { typedef T type; }; + template struct remove_const { typedef T type; }; + + template struct remove_volatile { typedef T type; }; + template struct remove_volatile { typedef T type; }; + + template struct remove_cv { typedef typename remove_const::type>::type type; }; + + // test if type is integral + template struct _is_integral { enum { value = false }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template<> struct _is_integral { enum { value = true }; }; + template struct is_integral : public _is_integral::type> {}; } + + // enum type check and regression to its underlying integral. + namespace Private { + template struct is_enum { enum { value = __is_enum(T) }; }; + + template::value> struct _underlying_type { using type = __underlying_type(T); }; + template struct _underlying_type { }; + + template struct underlying_type : public _underlying_type { }; + } + // C++11 solution using SFINAE to detect the existence of a member in a class at compile time. // It creates a HasMember structure containing 'value' set to true if the member exists #define HAS_MEMBER_IMPL(Member) \ @@ -720,6 +765,19 @@ #define RREPEAT2_S(S,N,OP,V...) EVAL1024(_RREPEAT2(S,SUB##S(N),OP,V)) #define RREPEAT2(N,OP,V...) RREPEAT2_S(0,N,OP,V) +// Emit a list of N OP(I) items with ascending counter. +#define _REPLIST(_RPT_I,_RPT_N,_RPT_OP) \ + _RPT_OP(_RPT_I) \ + IF_ELSE(SUB1(_RPT_N)) \ + ( , DEFER2(__REPLIST)()(ADD1(_RPT_I),SUB1(_RPT_N),_RPT_OP) ) \ + ( /* Do nothing */ ) +#define __REPLIST() _REPLIST + +// Repeat a macro, comma-separated, passing S...N-1. +#define REPLIST_S(S,N,OP) EVAL(_REPLIST(S,SUB##S(N),OP)) +#define REPLIST(N,OP) REPLIST_S(0,N,OP) +#define REPLIST_1(N,OP) REPLIST_S(1,INCREMENT(N),OP) + // Call OP(A) with each item as an argument #define _MAP(_MAP_OP,A,V...) \ _MAP_OP(A) \ diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h index 05a713e435de..2c0eb7aa7297 100644 --- a/Marlin/src/core/multi_language.h +++ b/Marlin/src/core/multi_language.h @@ -64,6 +64,9 @@ typedef const char Language_Str[]; #if NUM_LANGUAGES > 1 #define HAS_MULTI_LANGUAGE 1 + #if HAS_MARLINUI_MENU + #define HAS_MENU_MULTI_LANGUAGE 1 + #endif #define GET_TEXT(MSG) ( \ ui.language == 4 ? GET_LANG(LCD_LANGUAGE_5)::MSG : \ ui.language == 3 ? GET_LANG(LCD_LANGUAGE_4)::MSG : \ diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 64704c1e6cb4..96a333d49b1f 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -27,7 +27,8 @@ #include "../feature/ethernet.h" #endif -uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE; +// Echo commands to the terminal by default in dev mode +uint8_t marlin_debug_flags = TERN(MARLIN_DEV_MODE, MARLIN_DEBUG_ECHO, MARLIN_DEBUG_NONE); // Commonly-used strings in serial output PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C"); diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index a741d4b1e4d0..43777f5f0d29 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -125,8 +125,6 @@ extern uint8_t marlin_debug_flags; #define SERIAL_IMPL SERIAL_LEAF_1 #endif -#define SERIAL_OUT(WHAT, V...) (void)SERIAL_IMPL.WHAT(V) - #define PORT_REDIRECT(p) _PORT_REDIRECT(1,p) #define PORT_RESTORE() _PORT_RESTORE(1) #define SERIAL_PORTMASK(P) SerialMask::from(P) @@ -149,10 +147,8 @@ template void SERIAL_ECHO(T x) { SERIAL_IMPL.print(x); } // Wrapper for ECHO commands to interpret a char -typedef struct SerialChar { char c; SerialChar(char n) : c(n) { } } serial_char_t; inline void SERIAL_ECHO(serial_char_t x) { SERIAL_IMPL.write(x.c); } -#define AS_CHAR(C) serial_char_t(C) -#define AS_DIGIT(C) AS_CHAR('0' + (C)) +#define AS_DIGIT(n) C('0' + (n)) template void SERIAL_ECHOLN(T x) { SERIAL_IMPL.println(x); } diff --git a/Marlin/src/core/serial_base.h b/Marlin/src/core/serial_base.h index a5abd67d8727..a2f49417b7dc 100644 --- a/Marlin/src/core/serial_base.h +++ b/Marlin/src/core/serial_base.h @@ -23,6 +23,8 @@ #include "../inc/MarlinConfigPre.h" +#include // for size_t + #if ENABLED(EMERGENCY_PARSER) #include "../feature/e_parser.h" #endif @@ -77,7 +79,7 @@ struct EnsureDouble { operator double() { return a; } // If the compiler breaks on ambiguity here, it's likely because print(X, base) is called with X not a double/float, and // a base that's not a PrintBase value. This code is made to detect the error. You MUST set a base explicitly like this: - // SERIAL_PRINT(v, PrintBase::Hex) + //SERIAL_PRINT(v, PrintBase::Hex) EnsureDouble(double a) : a(a) {} EnsureDouble(float a) : a(a) {} }; @@ -167,7 +169,6 @@ struct SerialBase { FORCE_INLINE void print(unsigned int c, PrintBase base) { printNumber_unsigned(c, base); } FORCE_INLINE void print(unsigned long c, PrintBase base) { printNumber_unsigned(c, base); } - void print(EnsureDouble c, int digits) { printFloat(c, digits); } // Forward the call to the former's method @@ -178,7 +179,7 @@ struct SerialBase { void print(T c) { print(c, PrintBase::Dec); } void print(float c) { print(c, 2); } - void print(double c) { print(c, 2); } + void print(double c) { print(c, 2); } void println(char *s) { print(s); println(); } void println(const char *s) { print(s); println(); } @@ -232,7 +233,7 @@ struct SerialBase { // Round correctly so that print(1.999, 2) prints as "2.00" double rounding = 0.5; - LOOP_L_N(i, digits) rounding *= 0.1; + for (uint8_t i = 0; i < digits; ++i) rounding *= 0.1; number += rounding; // Extract the integer part of the number and print it diff --git a/Marlin/src/core/serial_hook.h b/Marlin/src/core/serial_hook.h index 65c553c70259..06efce1dc5fe 100644 --- a/Marlin/src/core/serial_hook.h +++ b/Marlin/src/core/serial_hook.h @@ -179,7 +179,7 @@ struct RuntimeSerial : public SerialBase< RuntimeSerial >, public Seria // Append Hookable for this class SerialFeature features(serial_index_t index) const { return SerialFeature::Hookable | CALL_IF_EXISTS(SerialFeature, static_cast(this), features, index); } - void setHook(WriteHook writeHook = 0, EndOfMessageHook eofHook = 0, void * userPointer = 0) { + void setHook(WriteHook writeHook=0, EndOfMessageHook eofHook=0, void * userPointer=0) { // Order is important here as serial code can be called inside interrupts // When setting a hook, the user pointer must be set first so if writeHook is called as soon as it's set, it'll be valid if (userPointer) this->userPointer = userPointer; @@ -292,7 +292,7 @@ struct MultiSerial : public SerialBase< MultiSerial< REPEAT(NUM_SERIAL, _S_NAME) #define _S_REFS(N) Serial##N##T & serial##N, #define _S_INIT(N) ,serial##N (serial##N) - MultiSerial(REPEAT(NUM_SERIAL, _S_REFS) const SerialMask mask = ALL, const bool e = false) + MultiSerial(REPEAT(NUM_SERIAL, _S_REFS) const SerialMask mask=ALL, const bool e=false) : BaseClassT(e), portMask(mask) REPEAT(NUM_SERIAL, _S_INIT) {} }; diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index f1fae85b5ca4..6ec0771d8484 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -31,52 +31,108 @@ // // typename IF<(MYOPT==12), int, float>::type myvar; // -template -struct IF { typedef R type; }; -template -struct IF { typedef L type; }; +template struct IF { typedef R type; }; +template struct IF { typedef L type; }; #define ALL_AXIS_NAMES X, X2, Y, Y2, Z, Z2, Z3, Z4, I, J, K, U, V, W, E0, E1, E2, E3, E4, E5, E6, E7 -#define NUM_AXIS_GANG(V...) GANG_N(NUM_AXES, V) -#define NUM_AXIS_CODE(V...) CODE_N(NUM_AXES, V) -#define NUM_AXIS_LIST(V...) LIST_N(NUM_AXES, V) -#define NUM_AXIS_LIST_1(V) LIST_N_1(NUM_AXES, V) -#define NUM_AXIS_ARRAY(V...) { NUM_AXIS_LIST(V) } -#define NUM_AXIS_ARRAY_1(V) { NUM_AXIS_LIST_1(V) } -#define NUM_AXIS_ARGS(T...) NUM_AXIS_LIST(T x, T y, T z, T i, T j, T k, T u, T v, T w) -#define NUM_AXIS_ELEM(O) NUM_AXIS_LIST(O.x, O.y, O.z, O.i, O.j, O.k, O.u, O.v, O.w) -#define NUM_AXIS_DEFS(T,V) NUM_AXIS_LIST(T x=V, T y=V, T z=V, T i=V, T j=V, T k=V, T u=V, T v=V, T w=V) -#define MAIN_AXIS_NAMES NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W) -#define MAIN_AXIS_MAP(F) MAP(F, MAIN_AXIS_NAMES) -#define STR_AXES_MAIN NUM_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W) - -#define LOGICAL_AXIS_GANG(E,V...) NUM_AXIS_GANG(V) GANG_ITEM_E(E) -#define LOGICAL_AXIS_CODE(E,V...) NUM_AXIS_CODE(V) CODE_ITEM_E(E) -#define LOGICAL_AXIS_LIST(E,V...) NUM_AXIS_LIST(V) LIST_ITEM_E(E) -#define LOGICAL_AXIS_LIST_1(V) NUM_AXIS_LIST_1(V) LIST_ITEM_E(V) +#define NUM_AXIS_GANG(V...) GANG_N(NUM_AXES, V) +#define NUM_AXIS_CODE(V...) CODE_N(NUM_AXES, V) +#define NUM_AXIS_LIST(V...) LIST_N(NUM_AXES, V) +#define NUM_AXIS_LIST_1(V) LIST_N_1(NUM_AXES, V) +#define NUM_AXIS_ARRAY(V...) { NUM_AXIS_LIST(V) } +#define NUM_AXIS_ARRAY_1(V) { NUM_AXIS_LIST_1(V) } +#define NUM_AXIS_ARGS(T) NUM_AXIS_LIST(T x, T y, T z, T i, T j, T k, T u, T v, T w) +#define NUM_AXIS_ELEM(O) NUM_AXIS_LIST(O.x, O.y, O.z, O.i, O.j, O.k, O.u, O.v, O.w) +#define NUM_AXIS_DECL(T,V) NUM_AXIS_LIST(T x=V, T y=V, T z=V, T i=V, T j=V, T k=V, T u=V, T v=V, T w=V) +#define MAIN_AXIS_NAMES NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W) +#define STR_AXES_MAIN NUM_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W) + +#define LOGICAL_AXIS_GANG(E,V...) NUM_AXIS_GANG(V) GANG_ITEM_E(E) +#define LOGICAL_AXIS_CODE(E,V...) NUM_AXIS_CODE(V) CODE_ITEM_E(E) +#define LOGICAL_AXIS_LIST(E,V...) NUM_AXIS_LIST(V) LIST_ITEM_E(E) +#define LOGICAL_AXIS_LIST_1(V) NUM_AXIS_LIST_1(V) LIST_ITEM_E(V) #define LOGICAL_AXIS_ARRAY(E,V...) { LOGICAL_AXIS_LIST(E,V) } #define LOGICAL_AXIS_ARRAY_1(V) { LOGICAL_AXIS_LIST_1(V) } -#define LOGICAL_AXIS_ARGS(T...) LOGICAL_AXIS_LIST(T e, T x, T y, T z, T i, T j, T k, T u, T v, T w) -#define LOGICAL_AXIS_ELEM(O) LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k, O.u, O.v, O.w) -#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, T u=V, T v=V, T w=V) -#define LOGICAL_AXIS_NAMES LOGICAL_AXIS_LIST(E, X, Y, Z, I, J, K, U, V, W) -#define LOGICAL_AXIS_MAP(F) MAP(F, LOGICAL_AXIS_NAMES) -#define STR_AXES_LOGICAL LOGICAL_AXIS_GANG("E", "X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W) +#define LOGICAL_AXIS_ARGS(T) LOGICAL_AXIS_LIST(T e, T x, T y, T z, T i, T j, T k, T u, T v, T w) +#define LOGICAL_AXIS_ELEM(O) LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k, O.u, O.v, O.w) +#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, T u=V, T v=V, T w=V) +#define LOGICAL_AXIS_NAMES LOGICAL_AXIS_LIST(E, X, Y, Z, I, J, K, U, V, W) +#define LOGICAL_AXIS_MAP(F) MAP(F, LOGICAL_AXIS_NAMES) +#define STR_AXES_LOGICAL LOGICAL_AXIS_GANG("E", "X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W) + +#if NUM_AXES + #define NUM_AXES_SEP , + #define MAIN_AXIS_MAP(F) MAP(F, MAIN_AXIS_NAMES) + #define OPTARGS_NUM(T) , NUM_AXIS_ARGS(T) + #define OPTARGS_LOGICAL(T) , LOGICAL_AXIS_ARGS(T) +#else + #define NUM_AXES_SEP + #define MAIN_AXIS_MAP(F) + #define OPTARGS_NUM(T) + #define OPTARGS_LOGICAL(T) +#endif -#define XYZ_GANG(V...) GANG_N(PRIMARY_LINEAR_AXES, V) -#define XYZ_CODE(V...) CODE_N(PRIMARY_LINEAR_AXES, V) +#define NUM_AXIS_GANG_(V...) NUM_AXIS_GANG(V) NUM_AXES_SEP +#define NUM_AXIS_LIST_(V...) NUM_AXIS_LIST(V) NUM_AXES_SEP +#define NUM_AXIS_LIST_1_(V...) NUM_AXIS_LIST_1(V) NUM_AXES_SEP +#define NUM_AXIS_ARGS_(T) NUM_AXIS_ARGS(T) NUM_AXES_SEP +#define NUM_AXIS_ELEM_(T) NUM_AXIS_ELEM(T) NUM_AXES_SEP +#define MAIN_AXIS_NAMES_ MAIN_AXIS_NAMES NUM_AXES_SEP + +#if LOGICAL_AXES + #define LOGICAL_AXES_SEP , +#else + #define LOGICAL_AXES_SEP +#endif + +#define LOGICAL_AXIS_GANG_(V...) LOGICAL_AXIS_GANG(V) LOGICAL_AXES_SEP +#define LOGICAL_AXIS_LIST_(V...) LOGICAL_AXIS_LIST(V) LOGICAL_AXES_SEP +#define LOGICAL_AXIS_LIST_1_(V...) LOGICAL_AXIS_LIST_1(V) LOGICAL_AXES_SEP +#define LOGICAL_AXIS_ARGS_(T) LOGICAL_AXIS_ARGS(T) LOGICAL_AXES_SEP +#define LOGICAL_AXIS_ELEM_(T) LOGICAL_AXIS_ELEM(T) LOGICAL_AXES_SEP +#define LOGICAL_AXIS_NAMES_ LOGICAL_AXIS_NAMES LOGICAL_AXES_SEP #define SECONDARY_AXIS_GANG(V...) GANG_N(SECONDARY_AXES, V) #define SECONDARY_AXIS_CODE(V...) CODE_N(SECONDARY_AXES, V) +#define SECONDARY_AXIS_LIST(V...) LIST_N(SECONDARY_AXES, V) +#define SECONDARY_AXIS_ARGS(T) SECONDARY_AXIS_LIST(T i, T j, T k, T u, T v, T w) + +// Just the XY or XYZ elements +#if HAS_Z_AXIS + #define XYZ_COUNT 3 + #define XY_COUNT 2 +#elif HAS_Y_AXIS + #define XY_COUNT 2 +#elif HAS_X_AXIS + #define XY_COUNT 1 +#else + #define XY_COUNT 0 +#endif +#ifndef XYZ_COUNT + #define XYZ_COUNT XY_COUNT +#endif +#define XY_LIST(V...) LIST_N(XY_COUNT, V) +#define XY_ARRAY(V...) ARRAY_N(XY_COUNT, V) +#define XY_CODE(V...) CODE_N(XY_COUNT, V) +#define XY_GANG(V...) GANG_N(XY_COUNT, V) +#define XYZ_LIST(V...) LIST_N(XYZ_COUNT, V) +#define XYZ_ARRAY(V...) ARRAY_N(XYZ_COUNT, V) +#define XYZ_CODE(V...) CODE_N(XYZ_COUNT, V) +#define XYZ_GANG(V...) GANG_N(XYZ_COUNT, V) #if HAS_ROTATIONAL_AXES #define ROTATIONAL_AXIS_GANG(V...) GANG_N(ROTATIONAL_AXES, V) #endif #if HAS_EXTRUDERS - #define LIST_ITEM_E(N) , N - #define CODE_ITEM_E(N) ; N + #if NUM_AXES + #define LIST_ITEM_E(N) , N + #define CODE_ITEM_E(N) ; N + #else + #define LIST_ITEM_E(N) N + #define CODE_ITEM_E(N) N + #endif #define GANG_ITEM_E(N) N #else #define LIST_ITEM_E(N) @@ -86,58 +142,77 @@ struct IF { typedef L type; }; #define AXIS_COLLISION(L) (AXIS4_NAME == L || AXIS5_NAME == L || AXIS6_NAME == L || AXIS7_NAME == L || AXIS8_NAME == L || AXIS9_NAME == L) +// Helpers +#define _RECIP(N) ((N) ? 1.0f / static_cast(N) : 0.0f) +#define _ABS(N) ((N) < 0 ? -(N) : (N)) +#define _LS(N) T(uint32_t(N) << p) +#define _RS(N) T(uint32_t(N) >> p) +#define _LSE(N) N = T(uint32_t(N) << p) +#define _RSE(N) N = T(uint32_t(N) >> p) +#define FI FORCE_INLINE + +// Define types based on largest bit width stored value required +#define bits_t(W) typename IF<((W)> 16), uint32_t, typename IF<((W)> 8), uint16_t, uint8_t>::type>::type +#define uvalue_t(V) typename IF<((V)>65535), uint32_t, typename IF<((V)>255), uint16_t, uint8_t>::type>::type +#define value_t(V) typename IF<((V)>32767), int32_t, typename IF<((V)>127), int16_t, int8_t>::type>::type + // General Flags for some number of states template struct Flags { - typedef typename IF<(N>8), uint16_t, uint8_t>::type bits_t; + typedef uvalue_t(N) flagbits_t; typedef struct { bool b0:1, b1:1, b2:1, b3:1, b4:1, b5:1, b6:1, b7:1; } N8; typedef struct { bool b0:1, b1:1, b2:1, b3:1, b4:1, b5:1, b6:1, b7:1, b8:1, b9:1, b10:1, b11:1, b12:1, b13:1, b14:1, b15:1; } N16; + typedef struct { bool b0:1, b1:1, b2:1, b3:1, b4:1, b5:1, b6:1, b7:1, b8:1, b9:1, b10:1, b11:1, b12:1, b13:1, b14:1, b15:1, + b16:1, b17:1, b18:1, b19:1, b20:1, b21:1, b22:1, b23:1, b24:1, b25:1, b26:1, b27:1, b28:1, b29:1, b30:1, b31:1; } N32; union { - bits_t b; - typename IF<(N>8), N16, N8>::type flag; + flagbits_t b; + typename IF<(N>16), N32, typename IF<(N>8), N16, N8>::type>::type flag; }; - void reset() { b = 0; } - void set(const int n, const bool onoff) { onoff ? set(n) : clear(n); } - void set(const int n) { b |= (bits_t)_BV(n); } - void clear(const int n) { b &= ~(bits_t)_BV(n); } - bool test(const int n) const { return TEST(b, n); } - bool operator[](const int n) { return test(n); } - bool operator[](const int n) const { return test(n); } - int size() const { return sizeof(b); } + FI void reset() { b = 0; } + FI void set(const int n, const bool onoff) { onoff ? set(n) : clear(n); } + FI void set(const int n) { b |= (flagbits_t)_BV(n); } + FI void clear(const int n) { b &= ~(flagbits_t)_BV(n); } + FI bool test(const int n) const { return TEST(b, n); } + FI bool operator[](const int n) { return test(n); } + FI bool operator[](const int n) const { return test(n); } + FI int size() const { return sizeof(b); } + FI operator bool() const { return b; } }; // Specialization for a single bool flag template<> struct Flags<1> { bool b; - void reset() { b = false; } - void set(const int n, const bool onoff) { onoff ? set(n) : clear(n); } - void set(const int) { b = true; } - void clear(const int) { b = false; } - bool test(const int) const { return b; } - bool& operator[](const int) { return b; } - bool operator[](const int) const { return b; } - int size() const { return sizeof(b); } + FI void reset() { b = false; } + FI void set(const int n, const bool onoff) { onoff ? set(n) : clear(n); } + FI void set(const int) { b = true; } + FI void clear(const int) { b = false; } + FI bool test(const int) const { return b; } + FI bool& operator[](const int) { return b; } + FI bool operator[](const int) const { return b; } + FI int size() const { return sizeof(b); } + FI operator bool() const { return b; } }; typedef Flags<8> flags_8_t; typedef Flags<16> flags_16_t; // Flags for some axis states, with per-axis aliases xyzijkuvwe -typedef struct AxisFlags { +typedef struct { union { struct Flags flags; struct { bool LOGICAL_AXIS_LIST(e:1, x:1, y:1, z:1, i:1, j:1, k:1, u:1, v:1, w:1); }; }; - void reset() { flags.reset(); } - void set(const int n) { flags.set(n); } - void set(const int n, const bool onoff) { flags.set(n, onoff); } - void clear(const int n) { flags.clear(n); } - bool test(const int n) const { return flags.test(n); } - bool operator[](const int n) { return flags[n]; } - bool operator[](const int n) const { return flags[n]; } - int size() const { return sizeof(flags); } -} axis_flags_t; + FI void reset() { flags.reset(); } + FI void set(const int n) { flags.set(n); } + FI void set(const int n, const bool onoff) { flags.set(n, onoff); } + FI void clear(const int n) { flags.clear(n); } + FI bool test(const int n) const { return flags.test(n); } + FI bool operator[](const int n) { return flags[n]; } + FI bool operator[](const int n) const { return flags[n]; } + FI int size() const { return sizeof(flags); } + FI operator bool() const { return flags; } +} AxisFlags; // // Enumerated axis indices @@ -149,37 +224,38 @@ typedef struct AxisFlags { enum AxisEnum : uint8_t { // Linear axes may be controlled directly or indirectly - NUM_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS, U_AXIS, V_AXIS, W_AXIS) + NUM_AXIS_LIST_(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS, U_AXIS, V_AXIS, W_AXIS) - // Extruder axes may be considered distinctly - #define _EN_ITEM(N) , E##N##_AXIS + #define _EN_ITEM(N) E##N##_AXIS, REPEAT(EXTRUDERS, _EN_ITEM) #undef _EN_ITEM // Core also keeps toolhead directions #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) - , X_HEAD, Y_HEAD, Z_HEAD + X_HEAD, Y_HEAD, Z_HEAD, #endif // Distinct axes, including all E and Core - , NUM_AXIS_ENUMS + NUM_AXIS_ENUMS, // Most of the time we refer only to the single E_AXIS #if HAS_EXTRUDERS - , E_AXIS = E0_AXIS + E_AXIS = E0_AXIS, #endif // A, B, and C are for DELTA, SCARA, etc. - , A_AXIS = X_AXIS + #if HAS_X_AXIS + A_AXIS = X_AXIS, + #endif #if HAS_Y_AXIS - , B_AXIS = Y_AXIS + B_AXIS = Y_AXIS, #endif #if HAS_Z_AXIS - , C_AXIS = Z_AXIS + C_AXIS = Z_AXIS, #endif // To refer to all or none - , ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF + ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF }; typedef IF<(NUM_AXIS_ENUMS > 8), uint16_t, uint8_t>::type axis_bits_t; @@ -187,11 +263,11 @@ typedef IF<(NUM_AXIS_ENUMS > 8), uint16_t, uint8_t>::type axis_bits_t; // // Loop over axes // -#define LOOP_ABC(VAR) LOOP_S_LE_N(VAR, A_AXIS, C_AXIS) -#define LOOP_NUM_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, NUM_AXES) -#define LOOP_LOGICAL_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, LOGICAL_AXES) -#define LOOP_DISTINCT_AXES(VAR) LOOP_S_L_N(VAR, X_AXIS, DISTINCT_AXES) -#define LOOP_DISTINCT_E(VAR) LOOP_L_N(VAR, DISTINCT_E) +#define LOOP_ABC(VAR) for (uint8_t VAR = A_AXIS; VAR <= C_AXIS; ++VAR) +#define LOOP_NUM_AXES(VAR) for (uint8_t VAR = 0; VAR < NUM_AXES; ++VAR) +#define LOOP_LOGICAL_AXES(VAR) for (uint8_t VAR = 0; VAR < LOGICAL_AXES; ++VAR) +#define LOOP_DISTINCT_AXES(VAR) for (uint8_t VAR = 0; VAR < DISTINCT_AXES; ++VAR) +#define LOOP_DISTINCT_E(VAR) for (uint8_t VAR = 0; VAR < DISTINCT_E; ++VAR) // // feedRate_t is just a humble float @@ -217,21 +293,47 @@ typedef float celsius_float_t; typedef const_float_t const_feedRate_t; typedef const_float_t const_celsius_float_t; +// Type large enough to count leveling grid points +typedef IF 255)), uint16_t, uint8_t>::type grid_count_t; + // Conversion macros #define MMM_TO_MMS(MM_M) feedRate_t(static_cast(MM_M) / 60.0f) #define MMS_TO_MMM(MM_S) (static_cast(MM_S) * 60.0f) +// Packaged character for C macro and other usage +typedef struct SerialChar { char c; SerialChar(char n) : c(n) { } } serial_char_t; +#define C(c) serial_char_t(c) + +// Packaged types: float with precision and/or width; a repeated space/character +typedef struct WFloat { float value; char width; char prec; + WFloat(float v, char w, char p) : value(v), width(w), prec(p) {} + } w_float_t; +typedef struct PFloat { float value; char prec; + PFloat(float v, char p) : value(v), prec(p) {} + } p_float_t; +typedef struct RepChr { char asc; int8_t count; + RepChr(char a, uint8_t c) : asc(a), count(c) {} + } repchr_t; +typedef struct Spaces { int8_t count; + Spaces(uint8_t c) : count(c) {} + } spaces_t; + +#ifdef __AVR__ + typedef w_float_t w_double_t; + typedef p_float_t p_double_t; +#else + typedef struct WDouble { double value; char width; char prec; + WDouble(double v, char w, char p) : value(v), width(w), prec(p) {} + } w_double_t; + typedef struct PDouble { double value; char prec; + PDouble(double v, char p) : value(v), prec(p) {} + } p_double_t; +#endif + // // Coordinates structures for XY, XYZ, XYZE... // -// Helpers -#define _RECIP(N) ((N) ? 1.0f / static_cast(N) : 0.0f) -#define _ABS(N) ((N) < 0 ? -(N) : (N)) -#define _LS(N) (N = (T)(uint32_t(N) << p)) -#define _RS(N) (N = (T)(uint32_t(N) >> p)) -#define FI FORCE_INLINE - // Forward declarations template struct XYval; template struct XYZval; @@ -315,6 +417,7 @@ void toNative(xyze_pos_t &lpos); // // Paired XY coordinates, counters, flags, etc. +// Always has XY elements regardless of the number of configured axes. // template struct XYval { @@ -325,157 +428,144 @@ struct XYval { }; // Set all to 0 - FI void reset() { x = y = 0; } + FI void reset() { x = y = 0; } // Setters taking struct types and arrays - FI void set(const T px) { x = px; } + #if HAS_X_AXIS + FI void set(const T px) { x = px; } + #endif #if HAS_Y_AXIS - FI void set(const T px, const T py) { x = px; y = py; } - FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } + FI void set(const T px, const T py) { x = px; y = py; } + FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } #endif #if NUM_AXES > XY - FI void set(const T (&arr)[NUM_AXES]) { x = arr[0]; y = arr[1]; } + FI void set(const T (&arr)[NUM_AXES]) { x = arr[0]; y = arr[1]; } #endif #if LOGICAL_AXES > NUM_AXES - FI void set(const T (&arr)[LOGICAL_AXES]) { x = arr[0]; y = arr[1]; } + FI void set(const T (&arr)[LOGICAL_AXES]) { x = arr[0]; y = arr[1]; } #if DISTINCT_AXES > LOGICAL_AXES - FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; } + FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; } #endif #endif // Length reduced to one dimension - FI T magnitude() const { return (T)sqrtf(x*x + y*y); } + FI constexpr T magnitude() const { return (T)sqrtf(x*x + y*y); } // Pointer to the data as a simple array - FI operator T* () { return pos; } + FI operator T* () { return pos; } // If any element is true then it's true - FI operator bool() { return x || y; } + FI constexpr operator bool() const { return x || y; } // Smallest element - FI T small() const { return _MIN(x, y); } + FI constexpr T small() const { return _MIN(x, y); } // Largest element - FI T large() const { return _MAX(x, y); } + FI constexpr T large() const { return _MAX(x, y); } // Explicit copy and copies with conversion - FI XYval copy() const { return *this; } - FI XYval ABS() const { return { T(_ABS(x)), T(_ABS(y)) }; } - FI XYval asInt() { return { int16_t(x), int16_t(y) }; } - FI XYval asInt() const { return { int16_t(x), int16_t(y) }; } - FI XYval asLong() { return { int32_t(x), int32_t(y) }; } - FI XYval asLong() const { return { int32_t(x), int32_t(y) }; } - FI XYval ROUNDL() { return { int32_t(LROUND(x)), int32_t(LROUND(y)) }; } - FI XYval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)) }; } - FI XYval asFloat() { return { static_cast(x), static_cast(y) }; } - FI XYval asFloat() const { return { static_cast(x), static_cast(y) }; } - FI XYval reciprocal() const { return { _RECIP(x), _RECIP(y) }; } + FI constexpr XYval copy() const { return *this; } + FI constexpr XYval ABS() const { return { T(_ABS(x)), T(_ABS(y)) }; } + FI constexpr XYval asInt() const { return { int16_t(x), int16_t(y) }; } + FI constexpr XYval asLong() const { return { int32_t(x), int32_t(y) }; } + FI constexpr XYval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)) }; } + FI constexpr XYval asFloat() const { return { static_cast(x), static_cast(y) }; } + FI constexpr XYval reciprocal() const { return { _RECIP(x), _RECIP(y) }; } // Marlin workspace shifting is done with G92 and M206 - FI XYval asLogical() const { XYval o = asFloat(); toLogical(o); return o; } - FI XYval asNative() const { XYval o = asFloat(); toNative(o); return o; } + FI XYval asLogical() const { XYval o = asFloat(); toLogical(o); return o; } + FI XYval asNative() const { XYval o = asFloat(); toNative(o); return o; } // Cast to a type with more fields by making a new object - FI operator XYZval() { return { x, y }; } - FI operator XYZval() const { return { x, y }; } - FI operator XYZEval() { return { x, y }; } - FI operator XYZEval() const { return { x, y }; } + FI constexpr operator XYZval() const { return { x, y }; } + FI constexpr operator XYZEval() const { return { x, y }; } // Accessor via an AxisEnum (or any integer) [index] - FI T& operator[](const int n) { return pos[n]; } - FI const T& operator[](const int n) const { return pos[n]; } + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } // Assignment operator overrides do the expected thing - FI XYval& operator= (const T v) { set(v, v ); return *this; } - FI XYval& operator= (const XYZval &rs) { set(rs.x, rs.y); return *this; } - FI XYval& operator= (const XYZEval &rs) { set(rs.x, rs.y); return *this; } + FI XYval& operator= (const T v) { set(v, v); return *this; } + FI XYval& operator= (const XYZval &rs) { set(XY_LIST(rs.x, rs.y)); return *this; } + FI XYval& operator= (const XYZEval &rs) { set(XY_LIST(rs.x, rs.y)); return *this; } // Override other operators to get intuitive behaviors - FI XYval operator+ (const XYval &rs) const { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYval operator+ (const XYval &rs) { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYval operator- (const XYval &rs) const { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYval operator- (const XYval &rs) { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYval operator* (const XYval &rs) const { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYval operator* (const XYval &rs) { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYval operator/ (const XYval &rs) const { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYval operator/ (const XYval &rs) { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYval operator+ (const XYZval &rs) const { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYval operator+ (const XYZval &rs) { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYval operator- (const XYZval &rs) const { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYval operator- (const XYZval &rs) { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYval operator* (const XYZval &rs) const { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYval operator* (const XYZval &rs) { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYval operator/ (const XYZval &rs) const { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYval operator/ (const XYZval &rs) { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYval operator+ (const XYZEval &rs) const { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYval operator+ (const XYZEval &rs) { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYval operator- (const XYZEval &rs) const { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYval operator- (const XYZEval &rs) { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYval operator* (const XYZEval &rs) const { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYval operator* (const XYZEval &rs) { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYval operator/ (const XYZEval &rs) const { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYval operator/ (const XYZEval &rs) { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYval operator* (const float &p) const { XYval ls = *this; ls.x *= p; ls.y *= p; return ls; } - FI XYval operator* (const float &p) { XYval ls = *this; ls.x *= p; ls.y *= p; return ls; } - FI XYval operator* (const int &p) const { XYval ls = *this; ls.x *= p; ls.y *= p; return ls; } - FI XYval operator* (const int &p) { XYval ls = *this; ls.x *= p; ls.y *= p; return ls; } - FI XYval operator/ (const float &p) const { XYval ls = *this; ls.x /= p; ls.y /= p; return ls; } - FI XYval operator/ (const float &p) { XYval ls = *this; ls.x /= p; ls.y /= p; return ls; } - FI XYval operator/ (const int &p) const { XYval ls = *this; ls.x /= p; ls.y /= p; return ls; } - FI XYval operator/ (const int &p) { XYval ls = *this; ls.x /= p; ls.y /= p; return ls; } - FI XYval operator>>(const int &p) const { XYval ls = *this; _RS(ls.x); _RS(ls.y); return ls; } - FI XYval operator>>(const int &p) { XYval ls = *this; _RS(ls.x); _RS(ls.y); return ls; } - FI XYval operator<<(const int &p) const { XYval ls = *this; _LS(ls.x); _LS(ls.y); return ls; } - FI XYval operator<<(const int &p) { XYval ls = *this; _LS(ls.x); _LS(ls.y); return ls; } - FI const XYval operator-() const { XYval o = *this; o.x = -x; o.y = -y; return o; } - FI XYval operator-() { XYval o = *this; o.x = -x; o.y = -y; return o; } + #define XY_OP(OP) { x TERN_(HAS_X_AXIS, OP rs.x), y TERN_(HAS_Y_AXIS, OP rs.y) } + FI constexpr XYval operator+ (const XYval &rs) const { return { x + rs.x, y + rs.y }; } + FI constexpr XYval operator- (const XYval &rs) const { return { x - rs.x, y - rs.y }; } + FI constexpr XYval operator* (const XYval &rs) const { return { x * rs.x, y * rs.y }; } + FI constexpr XYval operator/ (const XYval &rs) const { return { x / rs.x, y / rs.y }; } + FI constexpr XYval operator+ (const XYZval &rs) const { return { XY_OP(+) }; } + FI constexpr XYval operator- (const XYZval &rs) const { return { XY_OP(-) }; } + FI constexpr XYval operator* (const XYZval &rs) const { return { XY_OP(*) }; } + FI constexpr XYval operator/ (const XYZval &rs) const { return { XY_OP(/) }; } + FI constexpr XYval operator+ (const XYZEval &rs) const { return { XY_OP(+) }; } + FI constexpr XYval operator- (const XYZEval &rs) const { return { XY_OP(-) }; } + FI constexpr XYval operator* (const XYZEval &rs) const { return { XY_OP(*) }; } + FI constexpr XYval operator/ (const XYZEval &rs) const { return { XY_OP(/) }; } + FI constexpr XYval operator* (const float &p) const { return { (T)(x * p), (T)(y * p) }; } + FI constexpr XYval operator* (const int &p) const { return { x * p, y * p }; } + FI constexpr XYval operator/ (const float &p) const { return { (T)(x / p), (T)(y / p) }; } + FI constexpr XYval operator/ (const int &p) const { return { x / p, y / p }; } + FI constexpr XYval operator>>(const int &p) const { return { _RS(x), _RS(y) }; } + FI constexpr XYval operator<<(const int &p) const { return { _LS(x), _LS(y) }; } + FI constexpr XYval operator-() const { return { -x, -y }; } + #undef XY_OP // Modifier operators - FI XYval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } - FI XYval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } - FI XYval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } - FI XYval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } - FI XYval& operator+=(const XYZval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y,,,,,,, ); return *this; } - FI XYval& operator-=(const XYZval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y,,,,,,, ); return *this; } - FI XYval& operator*=(const XYZval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y,,,,,,, ); return *this; } - FI XYval& operator/=(const XYZval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y,,,,,,, ); return *this; } - FI XYval& operator+=(const XYZEval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y,,,,,,, ); return *this; } - FI XYval& operator-=(const XYZEval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y,,,,,,, ); return *this; } - FI XYval& operator*=(const XYZEval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y,,,,,,, ); return *this; } - FI XYval& operator/=(const XYZEval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y,,,,,,, ); return *this; } - FI XYval& operator*=(const float &p) { x *= p; y *= p; return *this; } - FI XYval& operator*=(const int &p) { x *= p; y *= p; return *this; } - FI XYval& operator>>=(const int &p) { _RS(x); _RS(y); return *this; } - FI XYval& operator<<=(const int &p) { _LS(x); _LS(y); return *this; } + FI XYval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } + FI XYval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } + FI XYval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } + FI XYval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } + FI XYval& operator+=(const XYZval &rs) { XY_CODE(x += rs.x, y += rs.y); return *this; } + FI XYval& operator-=(const XYZval &rs) { XY_CODE(x -= rs.x, y -= rs.y); return *this; } + FI XYval& operator*=(const XYZval &rs) { XY_CODE(x *= rs.x, y *= rs.y); return *this; } + FI XYval& operator/=(const XYZval &rs) { XY_CODE(x /= rs.x, y /= rs.y); return *this; } + FI XYval& operator+=(const XYZEval &rs) { XY_CODE(x += rs.x, y += rs.y); return *this; } + FI XYval& operator-=(const XYZEval &rs) { XY_CODE(x -= rs.x, y -= rs.y); return *this; } + FI XYval& operator*=(const XYZEval &rs) { XY_CODE(x *= rs.x, y *= rs.y); return *this; } + FI XYval& operator/=(const XYZEval &rs) { XY_CODE(x /= rs.x, y /= rs.y); return *this; } + FI XYval& operator*=(const float &p) { x *= p; y *= p; return *this; } + FI XYval& operator*=(const int &p) { x *= p; y *= p; return *this; } + FI XYval& operator>>=(const int &p) { _RSE(x); _RSE(y); return *this; } + FI XYval& operator<<=(const int &p) { _LSE(x); _LSE(y); return *this; } + + // Absolute difference between two objects + FI constexpr XYval diff(const XYZEval &rs) const { return { TERN(HAS_X_AXIS, T(_ABS(x - rs.x)), x), TERN(HAS_Y_AXIS, T(_ABS(y - rs.y)), y) }; } + FI constexpr XYval diff(const XYZval &rs) const { return { TERN(HAS_X_AXIS, T(_ABS(x - rs.x)), x), TERN(HAS_Y_AXIS, T(_ABS(y - rs.y)), y) }; } + FI constexpr XYval diff(const XYval &rs) const { return { T(_ABS(x - rs.x)), T(_ABS(y - rs.y)) }; } // Exact comparisons. For floats a "NEAR" operation may be better. - FI bool operator==(const XYval &rs) const { return NUM_AXIS_GANG(x == rs.x, && y == rs.y,,,,,,, ); } - FI bool operator==(const XYZval &rs) const { return NUM_AXIS_GANG(x == rs.x, && y == rs.y,,,,,,, ); } - FI bool operator==(const XYZEval &rs) const { return NUM_AXIS_GANG(x == rs.x, && y == rs.y,,,,,,, ); } - FI bool operator!=(const XYval &rs) const { return !operator==(rs); } - FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } - FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + FI bool operator==(const XYval &rs) const { return x == rs.x && y == rs.y; } + FI bool operator==(const XYZval &rs) const { return ENABLED(HAS_X_AXIS) XY_GANG(&& x == rs.x, && y == rs.y); } + FI bool operator==(const XYZEval &rs) const { return ENABLED(HAS_X_AXIS) XY_GANG(&& x == rs.x, && y == rs.y); } + FI bool operator!=(const XYval &rs) const { return !operator==(rs); } + FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } + FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } }; // // Linear Axes coordinates, counters, flags, etc. +// May have any number of axes according to configuration, including zero axes. // template struct XYZval { union { - struct { T NUM_AXIS_ARGS(); }; - struct { T NUM_AXIS_LIST(a, b, c, _i, _j, _k, _u, _v, _w); }; + #if NUM_AXES + struct { NUM_AXIS_CODE(T x, T y, T z, T i, T j, T k, T u, T v, T w); }; + struct { NUM_AXIS_CODE(T a, T b, T c, T _i, T _j, T _k, T _u, T _v, T _w); }; + #endif T pos[NUM_AXES]; }; // Set all to 0 - FI void reset() { NUM_AXIS_GANG(x =, y =, z =, i =, j =, k =, u =, v =, w =) 0; } + FI void reset() { NUM_AXIS_CODE(x = 0, y = 0, z = 0, i = 0, j = 0, k = 0, u = 0, v = 0, w = 0); } // Setters taking struct types and arrays - FI void set(const XYval pxy) { NUM_AXIS_CODE(x = pxy.x, y = pxy.y,,,,,,,); } - FI void set(const XYval pxy, const T pz) { NUM_AXIS_CODE(x = pxy.x, y = pxy.y, z = pz,,,,,,); } - FI void set(const T (&arr)[NUM_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } + FI void set(const XYval pxy) { XY_CODE(x = pxy.x, y = pxy.y); } + FI void set(const XYval pxy, const T pz) { XYZ_CODE(x = pxy.x, y = pxy.y, z = pz); } + FI void set(const T (&arr)[NUM_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } #if LOGICAL_AXES > NUM_AXES - FI void set(const T (&arr)[LOGICAL_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } - FI void set(LOGICAL_AXIS_ARGS(const T)) { NUM_AXIS_CODE(a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w ); } + FI void set(const T (&arr)[LOGICAL_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } + FI void set(LOGICAL_AXIS_ARGS(const T)) { NUM_AXIS_CODE(a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); } #if DISTINCT_AXES > LOGICAL_AXES - FI void set(const T (&arr)[DISTINCT_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } + FI void set(const T (&arr)[DISTINCT_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } #endif #endif @@ -509,114 +599,98 @@ struct XYZval { #endif // Length reduced to one dimension - FI T magnitude() const { return (T)sqrtf(NUM_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); } + FI constexpr T magnitude() const { return (T)TERN(HAS_X_AXIS, sqrtf(NUM_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)), 0); } // Pointer to the data as a simple array - FI operator T* () { return pos; } + FI operator T* () { return pos; } // If any element is true then it's true - FI operator bool() { return NUM_AXIS_GANG(x, || y, || z, || i, || j, || k, || u, || v, || w); } + FI constexpr operator bool() const { return 0 NUM_AXIS_GANG(|| x, || y, || z, || i, || j, || k, || u, || v, || w); } // Smallest element - FI T small() const { return _MIN(NUM_AXIS_LIST(x, y, z, i, j, k, u, v, w)); } + FI constexpr T small() const { return TERN(HAS_X_AXIS, _MIN(NUM_AXIS_LIST(x, y, z, i, j, k, u, v, w)), 0); } // Largest element - FI T large() const { return _MAX(NUM_AXIS_LIST(x, y, z, i, j, k, u, v, w)); } + FI constexpr T large() const { return TERN(HAS_X_AXIS, _MAX(NUM_AXIS_LIST(x, y, z, i, j, k, u, v, w)), 0); } // Explicit copy and copies with conversion - FI XYZval copy() const { XYZval o = *this; return o; } - FI XYZval ABS() const { return NUM_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); } - FI XYZval asInt() { return NUM_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } - FI XYZval asInt() const { return NUM_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } - FI XYZval asLong() { return NUM_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } - FI XYZval asLong() const { return NUM_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } - FI XYZval ROUNDL() { return NUM_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } - FI XYZval ROUNDL() const { return NUM_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } - FI XYZval asFloat() { return NUM_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } - FI XYZval asFloat() const { return NUM_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } - FI XYZval reciprocal() const { return NUM_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); } + FI constexpr XYZval copy() const { XYZval o = *this; return o; } + FI constexpr XYZval ABS() const { return NUM_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); } + FI constexpr XYZval asInt() const { return NUM_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } + FI constexpr XYZval asLong() const { return NUM_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } + FI constexpr XYZval ROUNDL() const { return NUM_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } + FI constexpr XYZval asFloat() const { return NUM_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } + FI constexpr XYZval reciprocal() const { return NUM_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); } // Marlin workspace shifting is done with G92 and M206 - FI XYZval asLogical() const { XYZval o = asFloat(); toLogical(o); return o; } - FI XYZval asNative() const { XYZval o = asFloat(); toNative(o); return o; } + FI XYZval asLogical() const { XYZval o = asFloat(); toLogical(o); return o; } + FI XYZval asNative() const { XYZval o = asFloat(); toNative(o); return o; } // In-place cast to types having fewer fields - FI operator XYval&() { return *(XYval*)this; } - FI operator const XYval&() const { return *(const XYval*)this; } + FI operator XYval&() { return *(XYval*)this; } + FI operator const XYval&() const { return *(const XYval*)this; } // Cast to a type with more fields by making a new object - FI operator XYZEval() const { return NUM_AXIS_ARRAY(x, y, z, i, j, k, u, v, w); } + FI constexpr operator XYZEval() const { return NUM_AXIS_ARRAY(x, y, z, i, j, k, u, v, w); } // Accessor via an AxisEnum (or any integer) [index] - FI T& operator[](const int n) { return pos[n]; } - FI const T& operator[](const int n) const { return pos[n]; } + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } // Assignment operator overrides do the expected thing - FI XYZval& operator= (const T v) { set(ARRAY_N_1(NUM_AXES, v)); return *this; } - FI XYZval& operator= (const XYval &rs) { set(rs.x, rs.y ); return *this; } - FI XYZval& operator= (const XYZEval &rs) { set(NUM_AXIS_ELEM(rs)); return *this; } + FI XYZval& operator= (const T v) { set(ARRAY_N_1(NUM_AXES, v)); return *this; } + FI XYZval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } + FI XYZval& operator= (const XYZEval &rs) { set(NUM_AXIS_ELEM(rs)); return *this; } // Override other operators to get intuitive behaviors - FI XYZval operator+ (const XYval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y,,,,,,, ); return ls; } - FI XYZval operator+ (const XYval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y,,,,,,, ); return ls; } - FI XYZval operator- (const XYval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y,,,,,,, ); return ls; } - FI XYZval operator- (const XYval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y,,,,,,, ); return ls; } - FI XYZval operator* (const XYval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y,,,,,,, ); return ls; } - FI XYZval operator* (const XYval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y,,,,,,, ); return ls; } - FI XYZval operator/ (const XYval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y,,,,,,, ); return ls; } - FI XYZval operator/ (const XYval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y,,,,,,, ); return ls; } - FI XYZval operator+ (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZval operator+ (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZval operator- (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZval operator- (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZval operator* (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZval operator* (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZval operator/ (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZval operator/ (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZval operator+ (const XYZEval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZval operator+ (const XYZEval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZval operator- (const XYZEval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZval operator- (const XYZEval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZval operator* (const XYZEval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZval operator* (const XYZEval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZval operator/ (const XYZEval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZval operator/ (const XYZEval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZval operator* (const float &p) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; } - FI XYZval operator* (const float &p) { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; } - FI XYZval operator* (const int &p) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; } - FI XYZval operator* (const int &p) { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; } - FI XYZval operator/ (const float &p) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; } - FI XYZval operator/ (const float &p) { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; } - FI XYZval operator/ (const int &p) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; } - FI XYZval operator/ (const int &p) { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; } - FI XYZval operator>>(const int &p) const { XYZval ls = *this; NUM_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; } - FI XYZval operator>>(const int &p) { XYZval ls = *this; NUM_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; } - FI XYZval operator<<(const int &p) const { XYZval ls = *this; NUM_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; } - FI XYZval operator<<(const int &p) { XYZval ls = *this; NUM_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; } - FI const XYZval operator-() const { XYZval o = *this; NUM_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k, o.u = -u, o.v = -v, o.w = -w); return o; } - FI XYZval operator-() { XYZval o = *this; NUM_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k, o.u = -u, o.v = -v, o.w = -w); return o; } + FI constexpr XYZval operator+ (const XYval &rs) const { return NUM_AXIS_ARRAY(x + rs.x, y + rs.y, z, i, j, k, u, v, w ); } + FI constexpr XYZval operator- (const XYval &rs) const { return NUM_AXIS_ARRAY(x - rs.x, y - rs.y, z, i, j, k, u, v, w ); } + FI constexpr XYZval operator* (const XYval &rs) const { return NUM_AXIS_ARRAY(x * rs.x, y * rs.y, z, i, j, k, u, v, w ); } + FI constexpr XYZval operator/ (const XYval &rs) const { return NUM_AXIS_ARRAY(x / rs.x, y / rs.y, z, i, j, k, u, v, w ); } + FI constexpr XYZval operator+ (const XYZval &rs) const { return NUM_AXIS_ARRAY(x + rs.x, y + rs.y, z + rs.z, i + rs.i, j + rs.j, k + rs.k, u + rs.u, v + rs.v, w + rs.w ); } + FI constexpr XYZval operator- (const XYZval &rs) const { return NUM_AXIS_ARRAY(x - rs.x, y - rs.y, z - rs.z, i - rs.i, j - rs.j, k - rs.k, u - rs.u, v - rs.v, w - rs.w ); } + FI constexpr XYZval operator* (const XYZval &rs) const { return NUM_AXIS_ARRAY(x * rs.x, y * rs.y, z * rs.z, i * rs.i, j * rs.j, k * rs.k, u * rs.u, v * rs.v, w * rs.w ); } + FI constexpr XYZval operator/ (const XYZval &rs) const { return NUM_AXIS_ARRAY(x / rs.x, y / rs.y, z / rs.z, i / rs.i, j / rs.j, k / rs.k, u / rs.u, v / rs.v, w / rs.w ); } + FI constexpr XYZval operator+ (const XYZEval &rs) const { return NUM_AXIS_ARRAY(x + rs.x, y + rs.y, z + rs.z, i + rs.i, j + rs.j, k + rs.k, u + rs.u, v + rs.v, w + rs.w ); } + FI constexpr XYZval operator- (const XYZEval &rs) const { return NUM_AXIS_ARRAY(x - rs.x, y - rs.y, z - rs.z, i - rs.i, j - rs.j, k - rs.k, u - rs.u, v - rs.v, w - rs.w ); } + FI constexpr XYZval operator* (const XYZEval &rs) const { return NUM_AXIS_ARRAY(x * rs.x, y * rs.y, z * rs.z, i * rs.i, j * rs.j, k * rs.k, u * rs.u, v * rs.v, w * rs.w ); } + FI constexpr XYZval operator/ (const XYZEval &rs) const { return NUM_AXIS_ARRAY(x / rs.x, y / rs.y, z / rs.z, i / rs.i, j / rs.j, k / rs.k, u / rs.u, v / rs.v, w / rs.w ); } + FI constexpr XYZval operator* (const float &p) const { return NUM_AXIS_ARRAY((T)(x * p), (T)(y * p), (T)(z * p), (T)(i * p), (T)(j * p), (T)(k * p), (T)(u * p), (T)(v * p), (T)(w * p)); } + FI constexpr XYZval operator* (const int &p) const { return NUM_AXIS_ARRAY(x * p, y * p, z * p, i * p, j * p, k * p, u * p, v * p, w * p); } + FI constexpr XYZval operator/ (const float &p) const { return NUM_AXIS_ARRAY((T)(x / p), (T)(y / p), (T)(z / p), (T)(i / p), (T)(j / p), (T)(k / p), (T)(u / p), (T)(v / p), (T)(w / p)); } + FI constexpr XYZval operator/ (const int &p) const { return NUM_AXIS_ARRAY(x / p, y / p, z / p, i / p, j / p, k / p, u / p, v / p, w / p); } + FI constexpr XYZval operator>>(const int &p) const { return NUM_AXIS_ARRAY(_RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); } + FI constexpr XYZval operator<<(const int &p) const { return NUM_AXIS_ARRAY(_LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); } + FI constexpr XYZval operator-() const { return NUM_AXIS_ARRAY(-x, -y, -z, -i, -j, -k, -u, -v, -w); } + + // Absolute difference between two objects + FI constexpr XYZval diff(const XYZEval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZval diff(const XYZval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZval diff(const XYval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), z, i, j, k, u, v, w ); } // Modifier operators - FI XYZval& operator+=(const XYval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y,,,,,,, ); return *this; } - FI XYZval& operator-=(const XYval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y,,,,,,, ); return *this; } - FI XYZval& operator*=(const XYval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y,,,,,,, ); return *this; } - FI XYZval& operator/=(const XYval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y,,,,,,, ); return *this; } - FI XYZval& operator+=(const XYZval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } - FI XYZval& operator-=(const XYZval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } - FI XYZval& operator*=(const XYZval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } - FI XYZval& operator/=(const XYZval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } - FI XYZval& operator+=(const XYZEval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } - FI XYZval& operator-=(const XYZEval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } - FI XYZval& operator*=(const XYZEval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } - FI XYZval& operator/=(const XYZEval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } - FI XYZval& operator*=(const float &p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; } - FI XYZval& operator*=(const int &p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; } - FI XYZval& operator>>=(const int &p) { NUM_AXIS_CODE(_RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); return *this; } - FI XYZval& operator<<=(const int &p) { NUM_AXIS_CODE(_LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); return *this; } + FI XYZval& operator+=(const XYval &rs) { XY_CODE(x += rs.x, y += rs.y); return *this; } + FI XYZval& operator-=(const XYval &rs) { XY_CODE(x -= rs.x, y -= rs.y); return *this; } + FI XYZval& operator*=(const XYval &rs) { XY_CODE(x *= rs.x, y *= rs.y); return *this; } + FI XYZval& operator/=(const XYval &rs) { XY_CODE(x /= rs.x, y /= rs.y); return *this; } + FI XYZval& operator+=(const XYZval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } + FI XYZval& operator-=(const XYZval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } + FI XYZval& operator*=(const XYZval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } + FI XYZval& operator/=(const XYZval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } + FI XYZval& operator+=(const XYZEval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } + FI XYZval& operator-=(const XYZEval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } + FI XYZval& operator*=(const XYZEval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } + FI XYZval& operator/=(const XYZEval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } + FI XYZval& operator*=(const float &p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; } + FI XYZval& operator*=(const int &p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; } + FI XYZval& operator>>=(const int &p) { NUM_AXIS_CODE(_RSE(x), _RSE(y), _RSE(z), _RSE(i), _RSE(j), _RSE(k), _RSE(u), _RSE(v), _RSE(w)); return *this; } + FI XYZval& operator<<=(const int &p) { NUM_AXIS_CODE(_LSE(x), _LSE(y), _LSE(z), _LSE(i), _LSE(j), _LSE(k), _LSE(u), _LSE(v), _LSE(w)); return *this; } // Exact comparisons. For floats a "NEAR" operation may be better. - FI bool operator==(const XYZEval &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } - FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + FI bool operator==(const XYZEval &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } + FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } }; // // Logical Axes coordinates, counters, etc. +// May have any number of axes according to configuration, including zero axes. +// When there is no extruder, essentially identical to XYZval. // template struct XYZEval { @@ -626,12 +700,12 @@ struct XYZEval { T pos[LOGICAL_AXES]; }; // Reset all to 0 - FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =, u =, v =, w =) 0; } + FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =, u =, v =, w =) 0; } // Setters taking struct types and arrays - FI void set(const XYval pxy) { x = pxy.x; OPTCODE(HAS_Y_AXIS, y = pxy.y) } + FI void set(const XYval pxy) { XY_CODE(x = pxy.x, y = pxy.y); } + FI void set(const XYval pxy, const T pz) { XYZ_CODE(x = pxy.x, y = pxy.y, z = pz); } FI void set(const XYZval pxyz) { set(NUM_AXIS_ELEM(pxyz)); } - FI void set(const XYval pxy, const T pz) { set(pxy); TERN_(HAS_Z_AXIS, z = pz); } FI void set(const T (&arr)[NUM_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } #if LOGICAL_AXES > NUM_AXES FI void set(const T (&arr)[LOGICAL_AXES]) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } @@ -673,32 +747,28 @@ struct XYZEval { #endif // Length reduced to one dimension - FI T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); } + FI constexpr T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); } // Pointer to the data as a simple array - FI operator T* () { return pos; } + FI operator T* () { return pos; } // If any element is true then it's true - FI operator bool() { return 0 LOGICAL_AXIS_GANG(|| e, || x, || y, || z, || i, || j, || k, || u, || v, || w); } + FI constexpr operator bool() const { return 0 LOGICAL_AXIS_GANG(|| e, || x, || y, || z, || i, || j, || k, || u, || v, || w); } // Smallest element - FI T small() const { return _MIN(LOGICAL_AXIS_LIST(e, x, y, z, i, j, k, u, v, w)); } + FI constexpr T small() const { return _MIN(LOGICAL_AXIS_LIST(e, x, y, z, i, j, k, u, v, w)); } // Largest element - FI T large() const { return _MAX(LOGICAL_AXIS_LIST(e, x, y, z, i, j, k, u, v, w)); } + FI constexpr T large() const { return _MAX(LOGICAL_AXIS_LIST(e, x, y, z, i, j, k, u, v, w)); } // Explicit copy and copies with conversion - FI XYZEval copy() const { XYZEval v = *this; return v; } - FI XYZEval ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); } - FI XYZEval asInt() { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } - FI XYZEval asInt() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } - FI XYZEval asLong() { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } - FI XYZEval asLong() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } - FI XYZEval ROUNDL() { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } - FI XYZEval ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } - FI XYZEval asFloat() { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } - FI XYZEval asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } - FI XYZEval reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); } + FI constexpr XYZEval copy() const { XYZEval v = *this; return v; } + FI constexpr XYZEval ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); } + FI constexpr XYZEval asInt() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } + FI constexpr XYZEval asLong() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } + FI constexpr XYZEval ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } + FI constexpr XYZEval asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } + FI constexpr XYZEval reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); } // Marlin workspace shifting is done with G92 and M206 - FI XYZEval asLogical() const { XYZEval o = asFloat(); toLogical(o); return o; } - FI XYZEval asNative() const { XYZEval o = asFloat(); toNative(o); return o; } + FI XYZEval asLogical() const { XYZEval o = asFloat(); toLogical(o); return o; } + FI XYZEval asNative() const { XYZEval o = asFloat(); toNative(o); return o; } // In-place cast to types having fewer fields FI operator XYval&() { return *(XYval*)this; } @@ -707,80 +777,349 @@ struct XYZEval { FI operator const XYZval&() const { return *(const XYZval*)this; } // Accessor via an AxisEnum (or any integer) [index] - FI T& operator[](const int n) { return pos[n]; } - FI const T& operator[](const int n) const { return pos[n]; } + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } // Assignment operator overrides do the expected thing - FI XYZEval& operator= (const T v) { set(LOGICAL_AXIS_LIST_1(v)); return *this; } - FI XYZEval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } - FI XYZEval& operator= (const XYZval &rs) { set(NUM_AXIS_ELEM(rs)); return *this; } + FI XYZEval& operator= (const T v) { set(LOGICAL_AXIS_LIST_1(v)); return *this; } + FI XYZEval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } + FI XYZEval& operator= (const XYZval &rs) { set(NUM_AXIS_ELEM(rs)); return *this; } // Override other operators to get intuitive behaviors - FI XYZEval operator+ (const XYval &rs) const { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYZEval operator+ (const XYval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } - FI XYZEval operator- (const XYval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYZEval operator- (const XYval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } - FI XYZEval operator* (const XYval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYZEval operator* (const XYval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } - FI XYZEval operator/ (const XYval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYZEval operator/ (const XYval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } - FI XYZEval operator+ (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZEval operator+ (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZEval operator- (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZEval operator- (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZEval operator* (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZEval operator* (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZEval operator/ (const XYZval &rs) const { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZEval operator/ (const XYZval &rs) { XYZval ls = *this; NUM_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZEval operator+ (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZEval operator+ (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k, ls.u += rs.u, ls.v += rs.v, ls.w += rs.w); return ls; } - FI XYZEval operator- (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZEval operator- (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k, ls.u -= rs.u, ls.v -= rs.v, ls.w -= rs.w); return ls; } - FI XYZEval operator* (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZEval operator* (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k, ls.u *= rs.u, ls.v *= rs.v, ls.w *= rs.w); return ls; } - FI XYZEval operator/ (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZEval operator/ (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k, ls.u /= rs.u, ls.v /= rs.v, ls.w /= rs.w); return ls; } - FI XYZEval operator* (const float &p) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= p, ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; } - FI XYZEval operator* (const float &p) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= p, ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; } - FI XYZEval operator* (const int &p) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= p, ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; } - FI XYZEval operator* (const int &p) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= p, ls.x *= p, ls.y *= p, ls.z *= p, ls.i *= p, ls.j *= p, ls.k *= p, ls.u *= p, ls.v *= p, ls.w *= p ); return ls; } - FI XYZEval operator/ (const float &p) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= p, ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; } - FI XYZEval operator/ (const float &p) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= p, ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; } - FI XYZEval operator/ (const int &p) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= p, ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; } - FI XYZEval operator/ (const int &p) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= p, ls.x /= p, ls.y /= p, ls.z /= p, ls.i /= p, ls.j /= p, ls.k /= p, ls.u /= p, ls.v /= p, ls.w /= p ); return ls; } - FI XYZEval operator>>(const int &p) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; } - FI XYZEval operator>>(const int &p) { XYZEval ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k), _RS(ls.u), _RS(ls.v), _RS(ls.w) ); return ls; } - FI XYZEval operator<<(const int &p) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; } - FI XYZEval operator<<(const int &p) { XYZEval ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k), _LS(ls.u), _LS(ls.v), _LS(ls.w) ); return ls; } - FI const XYZEval operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); } - FI XYZEval operator-() { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); } + FI constexpr XYZEval operator+ (const XYval &rs) const { return LOGICAL_AXIS_ARRAY(e, x + rs.x, y + rs.y, z, i, j, k, u, v, w); } + FI constexpr XYZEval operator- (const XYval &rs) const { return LOGICAL_AXIS_ARRAY(e, x - rs.x, y - rs.y, z, i, j, k, u, v, w); } + FI constexpr XYZEval operator* (const XYval &rs) const { return LOGICAL_AXIS_ARRAY(e, x * rs.x, y * rs.y, z, i, j, k, u, v, w); } + FI constexpr XYZEval operator/ (const XYval &rs) const { return LOGICAL_AXIS_ARRAY(e, x / rs.x, y / rs.y, z, i, j, k, u, v, w); } + FI constexpr XYZEval operator+ (const XYZval &rs) const { return LOGICAL_AXIS_ARRAY(e, x + rs.x, y + rs.y, z + rs.z, i + rs.i, j + rs.j, k + rs.k, u + rs.u, v + rs.v, w + rs.w); } + FI constexpr XYZEval operator- (const XYZval &rs) const { return LOGICAL_AXIS_ARRAY(e, x - rs.x, y - rs.y, z - rs.z, i - rs.i, j - rs.j, k - rs.k, u - rs.u, v - rs.v, w - rs.w); } + FI constexpr XYZEval operator* (const XYZval &rs) const { return LOGICAL_AXIS_ARRAY(e, x * rs.x, y * rs.y, z * rs.z, i * rs.i, j * rs.j, k * rs.k, u * rs.u, v * rs.v, w * rs.w); } + FI constexpr XYZEval operator/ (const XYZval &rs) const { return LOGICAL_AXIS_ARRAY(e, x / rs.x, y / rs.y, z / rs.z, i / rs.i, j / rs.j, k / rs.k, u / rs.u, v / rs.v, w / rs.w); } + FI constexpr XYZEval operator+ (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(e + rs.e, x + rs.x, y + rs.y, z + rs.z, i + rs.i, j + rs.j, k + rs.k, u + rs.u, v + rs.v, w + rs.w); } + FI constexpr XYZEval operator- (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(e - rs.e, x - rs.x, y - rs.y, z - rs.z, i - rs.i, j - rs.j, k - rs.k, u - rs.u, v - rs.v, w - rs.w); } + FI constexpr XYZEval operator* (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(e * rs.e, x * rs.x, y * rs.y, z * rs.z, i * rs.i, j * rs.j, k * rs.k, u * rs.u, v * rs.v, w * rs.w); } + FI constexpr XYZEval operator/ (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(e / rs.e, x / rs.x, y / rs.y, z / rs.z, i / rs.i, j / rs.j, k / rs.k, u / rs.u, v / rs.v, w / rs.w); } + FI constexpr XYZEval operator* (const float &p) const { return LOGICAL_AXIS_ARRAY((T)(e * p), (T)(x * p), (T)(y * p), (T)(z * p), (T)(i * p), (T)(j * p), (T)(k * p), (T)(u * p), (T)(v * p), (T)(w * p)); } + FI constexpr XYZEval operator* (const int &p) const { return LOGICAL_AXIS_ARRAY(e * p, x * p, y * p, z * p, i * p, j * p, k * p, u * p, v * p, w * p); } + FI constexpr XYZEval operator/ (const float &p) const { return LOGICAL_AXIS_ARRAY((T)(e / p), (T)(x / p), (T)(y / p), (T)(z / p), (T)(i / p), (T)(j / p), (T)(k / p), (T)(u / p), (T)(v / p), (T)(w / p)); } + FI constexpr XYZEval operator/ (const int &p) const { return LOGICAL_AXIS_ARRAY(e / p, x / p, y / p, z / p, i / p, j / p, k / p, u / p, v / p, w / p); } + FI constexpr XYZEval operator>>(const int &p) const { return LOGICAL_AXIS_ARRAY(_RS(e), _RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); } + FI constexpr XYZEval operator<<(const int &p) const { return LOGICAL_AXIS_ARRAY(_LS(e), _LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); } + FI constexpr XYZEval operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); } + + // Absolute difference between two objects + FI constexpr XYZEval diff(const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(T(_ABS(e - rs.e)), T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZEval diff(const XYZval &rs) const { return LOGICAL_AXIS_ARRAY(0 , T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZEval diff(const XYval &rs) const { return LOGICAL_AXIS_ARRAY(0 , T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), z, i, j, k, u, v, w ); } // Modifier operators - FI XYZEval& operator+=(const XYval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y,,,,,,, ); return *this; } - FI XYZEval& operator-=(const XYval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y,,,,,,, ); return *this; } - FI XYZEval& operator*=(const XYval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y,,,,,,, ); return *this; } - FI XYZEval& operator/=(const XYval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y,,,,,,, ); return *this; } - FI XYZEval& operator+=(const XYZval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } - FI XYZEval& operator-=(const XYZval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } - FI XYZEval& operator*=(const XYZval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } - FI XYZEval& operator/=(const XYZval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } - FI XYZEval& operator+=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } - FI XYZEval& operator-=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } - FI XYZEval& operator*=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } - FI XYZEval& operator/=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } - FI XYZEval& operator*=(const T &p) { LOGICAL_AXIS_CODE(e *= p, x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; } - FI XYZEval& operator>>=(const int &p) { LOGICAL_AXIS_CODE(_RS(e), _RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); return *this; } - FI XYZEval& operator<<=(const int &p) { LOGICAL_AXIS_CODE(_LS(e), _LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); return *this; } + FI XYZEval& operator+=(const XYval &rs) { XY_CODE(x += rs.x, y += rs.y); return *this; } + FI XYZEval& operator-=(const XYval &rs) { XY_CODE(x -= rs.x, y -= rs.y); return *this; } + FI XYZEval& operator*=(const XYval &rs) { XY_CODE(x *= rs.x, y *= rs.y); return *this; } + FI XYZEval& operator/=(const XYval &rs) { XY_CODE(x /= rs.x, y /= rs.y); return *this; } + FI XYZEval& operator+=(const XYZval &rs) { NUM_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } + FI XYZEval& operator-=(const XYZval &rs) { NUM_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } + FI XYZEval& operator*=(const XYZval &rs) { NUM_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } + FI XYZEval& operator/=(const XYZval &rs) { NUM_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } + FI XYZEval& operator+=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k, u += rs.u, v += rs.v, w += rs.w); return *this; } + FI XYZEval& operator-=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; } + FI XYZEval& operator*=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; } + FI XYZEval& operator/=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; } + FI XYZEval& operator*=(const T &p) { LOGICAL_AXIS_CODE(e *= p, x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; } + FI XYZEval& operator>>=(const int &p) { LOGICAL_AXIS_CODE(_RSE(e), _RSE(x), _RSE(y), _RSE(z), _RSE(i), _RSE(j), _RSE(k), _RSE(u), _RSE(v), _RSE(w)); return *this; } + FI XYZEval& operator<<=(const int &p) { LOGICAL_AXIS_CODE(_LSE(e), _LSE(x), _LSE(y), _LSE(z), _LSE(i), _LSE(j), _LSE(k), _LSE(u), _LSE(v), _LSE(w)); return *this; } // Exact comparisons. For floats a "NEAR" operation may be better. - FI bool operator==(const XYZval &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } - FI bool operator==(const XYZEval &rs) const { return true LOGICAL_AXIS_GANG(&& e == rs.e, && x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } - FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } - FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + FI bool operator==(const XYZval &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } + FI bool operator==(const XYZEval &rs) const { return true LOGICAL_AXIS_GANG(&& e == rs.e, && x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } + FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } + FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } +}; + +#include // for memset + +template +struct XYZarray { + typedef T el[SIZE]; + union { + el data[LOGICAL_AXES]; + struct { NUM_AXIS_CODE(T x, T y, T z, T i, T j, T k, T u, T v, T w); }; + struct { NUM_AXIS_CODE(T a, T b, T c, T _i, T _j, T _k, T _u, T _v, T _w); }; + }; + FI void reset() { ZERO(data); } + + FI void set(const int n, const XYval p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y,,,,,,,); } + FI void set(const int n, const XYZval p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } + FI void set(const int n, const XYZEval p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } + + // Setter for all individual args + FI void set(const int n OPTARGS_NUM(const T)) { NUM_AXIS_CODE(a[n] = x, b[n] = y, c[n] = z, _i[n] = i, _j[n] = j, _k[n] = k, _u[n] = u, _v[n] = v, _w[n] = w); } + + // Setters with fewer elements leave the rest untouched + #if HAS_Y_AXIS + FI void set(const int n, const T px) { x[n] = px; } + #endif + #if HAS_Z_AXIS + FI void set(const int n, const T px, const T py) { x[n] = px; y[n] = py; } + #endif + #if HAS_I_AXIS + FI void set(const int n, const T px, const T py, const T pz) { x[n] = px; y[n] = py; z[n] = pz; } + #endif + #if HAS_J_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; } + #endif + #if HAS_K_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; } + #endif + #if HAS_U_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj, const T pk) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; k[n] = pk; } + #endif + #if HAS_V_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; k[n] = pk; u[n] = pu; } + #endif + #if HAS_W_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu, const T pv) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; k[n] = pk; u[n] = pu; v[n] = pv; } + #endif + + FI XYZval operator[](const int n) const { return XYZval(NUM_AXIS_ARRAY(x[n], y[n], z[n], i[n], j[n], k[n], u[n], v[n], w[n])); } +}; + +template +struct XYZEarray { + typedef T el[SIZE]; + union { + el data[LOGICAL_AXES]; + struct { el LOGICAL_AXIS_ARGS(); }; + struct { el LOGICAL_AXIS_LIST(_e, a, b, c, _i, _j, _k, _u, _v, _w); }; + }; + FI void reset() { ZERO(data); } + + FI void set(const int n, const XYval p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y,,,,,,,); } + FI void set(const int n, const XYZval p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } + FI void set(const int n, const XYZEval p) { LOGICAL_AXIS_CODE(e[n]=p.e, x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } + + // Setter for all individual args + FI void set(const int n OPTARGS_NUM(const T)) { NUM_AXIS_CODE(a[n] = x, b[n] = y, c[n] = z, _i[n] = i, _j[n] = j, _k[n] = k, _u[n] = u, _v[n] = v, _w[n] = w); } + #if LOGICAL_AXES > NUM_AXES + FI void set(const int n, LOGICAL_AXIS_ARGS(const T)) { LOGICAL_AXIS_CODE(_e[n] = e, a[n] = x, b[n] = y, c[n] = z, _i[n] = i, _j[n] = j, _k[n] = k, _u[n] = u, _v[n] = v, _w[n] = w); } + #endif + + // Setters with fewer elements leave the rest untouched + #if HAS_Y_AXIS + FI void set(const int n, const T px) { x[n] = px; } + #endif + #if HAS_Z_AXIS + FI void set(const int n, const T px, const T py) { x[n] = px; y[n] = py; } + #endif + #if HAS_I_AXIS + FI void set(const int n, const T px, const T py, const T pz) { x[n] = px; y[n] = py; z[n] = pz; } + #endif + #if HAS_J_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; } + #endif + #if HAS_K_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; } + #endif + #if HAS_U_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj, const T pk) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; k[n] = pk; } + #endif + #if HAS_V_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; k[n] = pk; u[n] = pu; } + #endif + #if HAS_W_AXIS + FI void set(const int n, const T px, const T py, const T pz, const T pi, const T pj, const T pk, const T pu, const T pv) { x[n] = px; y[n] = py; z[n] = pz; i[n] = pi; j[n] = pj; k[n] = pk; u[n] = pu; v[n] = pv; } + #endif + + FI XYZEval operator[](const int n) const { return XYZval(LOGICAL_AXIS_ARRAY(e[n], x[n], y[n], z[n], i[n], j[n], k[n], u[n], v[n], w[n])); } +}; + +class AxisBits; + +class AxisBits { +public: + typedef bits_t(NUM_AXIS_ENUMS) el; + union { + el bits; + // Axes x, y, z ... e0, e1, e2 ... hx, hy, hz + struct { + #if NUM_AXES + bool NUM_AXIS_LIST(x:1, y:1, z:1, i:1, j:1, k:1, u:1, v:1, w:1); + #endif + #define _EN_ITEM(N) bool e##N:1; + REPEAT(EXTRUDERS,_EN_ITEM) + #undef _EN_ITEM + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) + bool hx:1, hy:1, hz:1; + #endif + }; + // Axes X, Y, Z ... E0, E1, E2 ... HX, HY, HZ + struct { + #if NUM_AXES + bool NUM_AXIS_LIST(X:1, Y:1, Z:1, I:1, J:1, K:1, U:1, V:1, W:1); + #endif + #define _EN_ITEM(N) bool E##N:1; + REPEAT(EXTRUDERS,_EN_ITEM) + #undef _EN_ITEM + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) + bool HX:1, HY:1, HZ:1; + #endif + }; + // a, b, c, e ... ha, hb, hc + struct { + bool LOGICAL_AXIS_LIST(e:1, a:1, b:1, c:1, ii:1, jj:1, kk:1, uu:1, vv:1, ww:1); + #if EXTRUDERS > 1 + #define _EN_ITEM(N) bool _e##N:1; + REPEAT_S(1,EXTRUDERS,_EN_ITEM) + #undef _EN_ITEM + #endif + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) + bool ha:1, hb:1, hc:1; + #endif + }; + // A, B, C, E ... HA, HB, HC + struct { + bool LOGICAL_AXIS_LIST(E:1, A:1, B:1, C:1, II:1, JJ:1, KK:1, UU:1, VV:1, WW:1); + #if EXTRUDERS > 1 + #define _EN_ITEM(N) bool _E##N:1; + REPEAT_S(1,EXTRUDERS,_EN_ITEM) + #undef _EN_ITEM + #endif + #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) + bool HA:1, HB:1, HC:1; + #endif + }; + }; + + AxisBits() { reset(); } + + // Constructor, setter, and operator= for bit mask + AxisBits(const el p) { set(p); } + FI void set(const el p) { bits = el(p); } + FI AxisBits& operator=(const el p) { set(p); return *this; } + + FI void reset() { set(0); } + FI void fill() { set(_BV(NUM_AXIS_ENUMS) - 1); } + + #define MSET(pE,pX,pY,pZ,pI,pJ,pK,pU,pV,pW) LOGICAL_AXIS_CODE(e=pE, x=pX, y=pY, z=pZ, i=pI, j=pJ, k=pK, u=pU, v=pV, w=pW) + + // Constructor, setter, and operator= for XYZE type + AxisBits(const xyze_bool_t &p) { set(p); } + FI void set(const xyze_bool_t &p) { + MSET(p.e, p.x, p.y, p.z, p.i, p.j, p.k, p.u, p.v, p.w); + } + FI AxisBits& operator=(const xyze_bool_t &p) { set(p); return *this; } + + // Constructor, setter, and operator= for bool array + AxisBits(const bool (&p)[LOGICAL_AXES]) { set(p); } + FI void set(const bool (&p)[LOGICAL_AXES]) { + MSET(p[E_AXIS], p[X_AXIS], p[Y_AXIS], p[Z_AXIS], + p[I_AXIS], p[J_AXIS], p[K_AXIS], + p[U_AXIS], p[V_AXIS], p[W_AXIS]); + } + FI AxisBits& operator=(const bool (&p)[LOGICAL_AXES]) { set(p); return *this; } + + // Constructor, setter, and operator= for undersized bool arrays + #if LOGICAL_AXES > 1 + AxisBits(const bool (&p)[1]) { set(p); } + FI void set(const bool (&p)[1]) { + MSET(0, p[X_AXIS], 0, 0, 0, 0, 0, 0, 0, 0); + } + FI AxisBits& operator=(const bool (&p)[1]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 2 + AxisBits(const bool (&p)[2]) { set(p); } + FI void set(const bool (&p)[2]) { + MSET(0, p[X_AXIS], p[Y_AXIS], 0, 0, 0, 0, 0, 0, 0); + } + FI AxisBits& operator=(const bool (&p)[2]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 3 + AxisBits(const bool (&p)[3]) { set(p); } + FI void set(const bool (&p)[3]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], 0, 0, 0, 0, 0, 0); + } + FI AxisBits& operator=(const bool (&p)[3]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 4 + AxisBits(const bool (&p)[4]) { set(p); } + FI void set(const bool (&p)[4]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], p[I_AXIS], 0, 0, 0, 0, 0); + } + FI AxisBits& operator=(const bool (&p)[4]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 5 + AxisBits(const bool (&p)[5]) { set(p); } + FI void set(const bool (&p)[5]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], p[I_AXIS], p[J_AXIS], 0, 0, 0, 0); + } + FI AxisBits& operator=(const bool (&p)[5]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 6 + AxisBits(const bool (&p)[6]) { set(p); } + FI void set(const bool (&p)[6]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], p[I_AXIS], p[J_AXIS], p[K_AXIS], 0, 0, 0); + } + FI AxisBits& operator=(const bool (&p)[6]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 7 + AxisBits(const bool (&p)[7]) { set(p); } + FI void set(const bool (&p)[7]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], p[I_AXIS], p[J_AXIS], p[K_AXIS], p[U_AXIS], 0, 0); + } + FI AxisBits& operator=(const bool (&p)[7]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 8 + AxisBits(const bool (&p)[8]) { set(p); } + FI void set(const bool (&p)[8]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], p[I_AXIS], p[J_AXIS], p[K_AXIS], p[U_AXIS], p[V_AXIS], 0); + } + FI AxisBits& operator=(const bool (&p)[8]) { set(p); return *this; } + #endif + #if LOGICAL_AXES > 9 + AxisBits(const bool (&p)[9]) { set(p); } + FI void set(const bool (&p)[9]) { + MSET(0, p[X_AXIS], p[Y_AXIS], p[Z_AXIS], p[I_AXIS], p[J_AXIS], p[K_AXIS], p[U_AXIS], p[V_AXIS], p[W_AXIS]); + } + FI AxisBits& operator=(const bool (&p)[9]) { set(p); return *this; } + #endif + #undef MSET + + FI bool toggle(const AxisEnum n) { TBI(bits, n); return TEST(bits, n); } + FI void bset(const AxisEnum n) { SBI(bits, n); } + FI void bclr(const AxisEnum n) { CBI(bits, n); } + + // Accessor via an AxisEnum (or any integer) [index] + FI bool operator[](const int n) const { return TEST(bits, n); } + FI bool operator[](const AxisEnum n) const { return TEST(bits, n); } + + FI AxisBits& operator|=(const el &p) { bits |= el(p); return *this; } + FI AxisBits& operator&=(const el &p) { bits &= el(p); return *this; } + FI AxisBits& operator^=(const el &p) { bits ^= el(p); return *this; } + + FI AxisBits& operator|=(const AxisBits &p) { bits |= p.bits; return *this; } + FI AxisBits& operator&=(const AxisBits &p) { bits &= p.bits; return *this; } + FI AxisBits& operator^=(const AxisBits &p) { bits ^= p.bits; return *this; } + + FI bool operator==(const AxisBits &p) const { return p.bits == bits; } + FI bool operator!=(const AxisBits &p) const { return p.bits != bits; } + + FI el operator|(const el &p) const { return bits | el(p); } + FI el operator&(const el &p) const { return bits & el(p); } + FI el operator^(const el &p) const { return bits ^ el(p); } + + FI AxisBits operator|(const AxisBits &p) const { return AxisBits(bits | p.bits); } + FI AxisBits operator&(const AxisBits &p) const { return AxisBits(bits & p.bits); } + FI AxisBits operator^(const AxisBits &p) const { return AxisBits(bits ^ p.bits); } + + FI operator bool() const { return !!bits; } + FI operator uint16_t() const { return uint16_t(bits & 0xFFFF); } + FI operator uint32_t() const { return uint32_t(bits); } + }; #undef _RECIP #undef _ABS #undef _LS #undef _RS +#undef _LSE +#undef _RSE #undef FI diff --git a/Marlin/src/core/utility.h b/Marlin/src/core/utility.h index 2731e62b6754..0d8416ac3a64 100644 --- a/Marlin/src/core/utility.h +++ b/Marlin/src/core/utility.h @@ -33,17 +33,17 @@ void safe_delay(millis_t ms); // Delay ensuring that temperatures are inline void serial_delay(const millis_t) {} #endif -#if (GRID_MAX_POINTS_X) && (GRID_MAX_POINTS_Y) +#if GRID_MAX_POINTS // 16x16 bit arrays template struct FlagBits { - typename IF<(W>8), uint16_t, uint8_t>::type bits[H]; - void fill() { memset(bits, 0xFF, sizeof(bits)); } - void reset() { memset(bits, 0x00, sizeof(bits)); } - void unmark(const uint8_t x, const uint8_t y) { CBI(bits[y], x); } - void mark(const uint8_t x, const uint8_t y) { SBI(bits[y], x); } - bool marked(const uint8_t x, const uint8_t y) { return TEST(bits[y], x); } + bits_t(W) flags[H]; + void fill() { memset(flags, 0xFF, sizeof(flags)); } + void reset() { memset(flags, 0x00, sizeof(flags)); } + void unmark(const uint8_t x, const uint8_t y) { CBI(flags[y], x); } + void mark(const uint8_t x, const uint8_t y) { SBI(flags[y], x); } + bool marked(const uint8_t x, const uint8_t y) { return TEST(flags[y], x); } inline void unmark(const xy_int8_t &xy) { unmark(xy.x, xy.y); } inline void mark(const xy_int8_t &xy) { mark(xy.x, xy.y); } inline bool marked(const xy_int8_t &xy) { return marked(xy.x, xy.y); } diff --git a/Marlin/src/feature/babystep.h b/Marlin/src/feature/babystep.h index bbf0c5a26060..32e1375535a6 100644 --- a/Marlin/src/feature/babystep.h +++ b/Marlin/src/feature/babystep.h @@ -31,7 +31,7 @@ #define BABYSTEP_TICKS ((TEMP_TIMER_RATE) / (BABYSTEPS_PER_SEC)) #endif -#if IS_CORE || EITHER(BABYSTEP_XY, I2C_POSITION_ENCODERS) +#if ANY(IS_CORE, BABYSTEP_XY, I2C_POSITION_ENCODERS) #define BS_AXIS_IND(A) A #define BS_AXIS(I) AxisEnum(I) #else @@ -76,7 +76,7 @@ class Babystep { // apply accumulated babysteps to the axes. // static void task() { - LOOP_LE_N(i, BS_AXIS_IND(Z_AXIS)) step_axis(BS_AXIS(i)); + for (uint8_t i = 0; i <= BS_AXIS_IND(Z_AXIS); ++i) step_axis(BS_AXIS(i)); } private: diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 13e2cd99eccb..2aa78e6c14bb 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -66,7 +66,7 @@ Backlash backlash; void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const axis_bits_t dm, block_t * const block) { axis_bits_t changed_dir = last_direction_bits ^ dm; // Ignore direction change unless steps are taken in that direction - #if DISABLED(CORE_BACKLASH) || EITHER(MARKFORGED_XY, MARKFORGED_YX) + #if DISABLED(CORE_BACKLASH) || ANY(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/feature/bedlevel/abl/bbl.cpp b/Marlin/src/feature/bedlevel/abl/bbl.cpp index be0e862cc16a..68d29071aae1 100644 --- a/Marlin/src/feature/bedlevel/abl/bbl.cpp +++ b/Marlin/src/feature/bedlevel/abl/bbl.cpp @@ -133,8 +133,8 @@ void LevelingBilinear::extrapolate_unprobed_bed_level() { yend = ctry1; #endif - LOOP_LE_N(xo, xend) - LOOP_LE_N(yo, yend) { + for (uint8_t xo = 0; xo <= xend; ++xo) + for (uint8_t yo = 0; yo <= yend; ++yo) { uint8_t x2 = ctrx2 + xo, y2 = ctry2 + yo; #ifndef HALF_IN_X const uint8_t x1 = ctrx1 - xo; @@ -153,7 +153,7 @@ void LevelingBilinear::extrapolate_unprobed_bed_level() { } } -void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL*/) { +void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values/*=nullptr*/) { // print internal grid(s) or just the one passed as a parameter SERIAL_ECHOLNPGM("Bilinear Leveling Grid:"); print_2d_array(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y, 3, _z_values ? *_z_values[0] : z_values[0]); @@ -175,13 +175,13 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL* xy_float_t LevelingBilinear::grid_factor_virt; #define LINEAR_EXTRAPOLATION(E, I) ((E) * 2 - (I)) - float LevelingBilinear::bed_level_virt_coord(const uint8_t x, const uint8_t y) { + float LevelingBilinear::virt_coord(const uint8_t x, const uint8_t y) { uint8_t ep = 0, ip = 1; if (x > (GRID_MAX_POINTS_X) + 1 || y > (GRID_MAX_POINTS_Y) + 1) { // The requested point requires extrapolating two points beyond the mesh. // These values are only requested for the edges of the mesh, which are always an actual mesh point, // and do not require interpolation. When interpolation is not needed, this "Mesh + 2" point is - // cancelled out in bed_level_virt_cmr and does not impact the result. Return 0.0 rather than + // cancelled out in virt_cmr and does not impact the result. Return 0.0 rather than // making this function more complex by extrapolating two points. return 0.0; } @@ -197,8 +197,8 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL* ); else return LINEAR_EXTRAPOLATION( - bed_level_virt_coord(ep + 1, y), - bed_level_virt_coord(ip + 1, y) + virt_coord(ep + 1, y), + virt_coord(ip + 1, y) ); } if (!y || y == ABL_TEMP_POINTS_Y - 1) { @@ -213,14 +213,14 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL* ); else return LINEAR_EXTRAPOLATION( - bed_level_virt_coord(x, ep + 1), - bed_level_virt_coord(x, ip + 1) + virt_coord(x, ep + 1), + virt_coord(x, ip + 1) ); } return z_values[x - 1][y - 1]; } - float LevelingBilinear::bed_level_virt_cmr(const float p[4], const uint8_t i, const float t) { + float LevelingBilinear::virt_cmr(const float p[4], const uint8_t i, const float t) { return ( p[i-1] * -t * sq(1 - t) + p[i] * (2 - 5 * sq(t) + 3 * t * sq(t)) @@ -229,28 +229,28 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL* ) * 0.5f; } - float LevelingBilinear::bed_level_virt_2cmr(const uint8_t x, const uint8_t y, const_float_t tx, const_float_t ty) { + float LevelingBilinear::virt_2cmr(const uint8_t x, const uint8_t y, const_float_t tx, const_float_t ty) { float row[4], column[4]; - LOOP_L_N(i, 4) { - LOOP_L_N(j, 4) { - column[j] = bed_level_virt_coord(i + x - 1, j + y - 1); + for (uint8_t i = 0; i < 4; ++i) { + for (uint8_t j = 0; j < 4; ++j) { + column[j] = virt_coord(i + x - 1, j + y - 1); } - row[i] = bed_level_virt_cmr(column, 1, ty); + row[i] = virt_cmr(column, 1, ty); } - return bed_level_virt_cmr(row, 1, tx); + return virt_cmr(row, 1, tx); } - void LevelingBilinear::bed_level_virt_interpolate() { + void LevelingBilinear::subdivide_mesh() { grid_spacing_virt = grid_spacing / (BILINEAR_SUBDIVISIONS); grid_factor_virt = grid_spacing_virt.reciprocal(); - LOOP_L_N(y, GRID_MAX_POINTS_Y) - LOOP_L_N(x, GRID_MAX_POINTS_X) - LOOP_L_N(ty, BILINEAR_SUBDIVISIONS) - LOOP_L_N(tx, BILINEAR_SUBDIVISIONS) { + for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; ++y) + for (uint8_t x = 0; x < GRID_MAX_POINTS_X; ++x) + for (uint8_t ty = 0; ty < BILINEAR_SUBDIVISIONS; ++ty) + for (uint8_t tx = 0; tx < BILINEAR_SUBDIVISIONS; ++tx) { if ((ty && y == (GRID_MAX_POINTS_Y) - 1) || (tx && x == (GRID_MAX_POINTS_X) - 1)) continue; z_values_virt[x * (BILINEAR_SUBDIVISIONS) + tx][y * (BILINEAR_SUBDIVISIONS) + ty] = - bed_level_virt_2cmr( + virt_2cmr( x + 1, y + 1, (float)tx / (BILINEAR_SUBDIVISIONS), @@ -263,7 +263,7 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL* // Refresh after other values have been updated void LevelingBilinear::refresh_bed_level() { - TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); + TERN_(ABL_BILINEAR_SUBDIVISION, subdivide_mesh()); cached_rel.x = cached_rel.y = -999.999; cached_g.x = cached_g.y = -99; } diff --git a/Marlin/src/feature/bedlevel/abl/bbl.h b/Marlin/src/feature/bedlevel/abl/bbl.h index c2be4fee821c..ca2e96593fde 100644 --- a/Marlin/src/feature/bedlevel/abl/bbl.h +++ b/Marlin/src/feature/bedlevel/abl/bbl.h @@ -43,17 +43,17 @@ class LevelingBilinear { static xy_pos_t grid_spacing_virt; static xy_float_t grid_factor_virt; - static float bed_level_virt_coord(const uint8_t x, const uint8_t y); - static float bed_level_virt_cmr(const float p[4], const uint8_t i, const float t); - static float bed_level_virt_2cmr(const uint8_t x, const uint8_t y, const_float_t tx, const_float_t ty); - static void bed_level_virt_interpolate(); + static float virt_coord(const uint8_t x, const uint8_t y); + static float virt_cmr(const float p[4], const uint8_t i, const float t); + static float virt_2cmr(const uint8_t x, const uint8_t y, const_float_t tx, const_float_t ty); + static void subdivide_mesh(); #endif public: static void reset(); static void set_grid(const xy_pos_t& _grid_spacing, const xy_pos_t& _grid_start); static void extrapolate_unprobed_bed_level(); - static void print_leveling_grid(const bed_mesh_t* _z_values = NULL); + static void print_leveling_grid(const bed_mesh_t *_z_values=nullptr); static void refresh_bed_level(); static bool has_mesh() { return !!grid_spacing.x; } static bool mesh_is_valid() { return has_mesh(); } diff --git a/Marlin/src/feature/bedlevel/bdl/bdl.cpp b/Marlin/src/feature/bedlevel/bdl/bdl.cpp index 1a27011a4b8f..3297872ddffd 100644 --- a/Marlin/src/feature/bedlevel/bdl/bdl.cpp +++ b/Marlin/src/feature/bedlevel/bdl/bdl.cpp @@ -110,7 +110,7 @@ void BDS_Leveling::process() { } else { babystep.set_mm(Z_AXIS, 0); //if (old_cur_z <= cur_z) Z_DIR_WRITE(!INVERT_Z_DIR); - stepper.set_directions(); + stepper.apply_directions(); } #endif old_cur_z = cur_z; @@ -119,7 +119,7 @@ void BDS_Leveling::process() { //endstops.update(); } else - stepper.set_directions(); + stepper.apply_directions(); #if ENABLED(DEBUG_OUT_BD) SERIAL_ECHOLNPGM("BD:", tmp & 0x3FF, ", Z:", cur_z, "|", current_position.z); @@ -150,7 +150,7 @@ void BDS_Leveling::process() { if (config_state == -6) { //BD_I2C_SENSOR.BD_i2c_write(1019); // begin calibrate //delay(1000); - gcode.stepper_inactive_time = SEC_TO_MS(60 * 5); + TERN_(HAS_DISABLE_IDLE_AXES, gcode.stepper_inactive_time = SEC_TO_MS(60 * 5)); gcode.process_subcommands_now(F("M17 Z")); gcode.process_subcommands_now(F("G1 Z0.0")); z_pose = 0; diff --git a/Marlin/src/feature/bedlevel/bedlevel.cpp b/Marlin/src/feature/bedlevel/bedlevel.cpp index 03b67745ec16..17407eafb958 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.cpp +++ b/Marlin/src/feature/bedlevel/bedlevel.cpp @@ -27,7 +27,7 @@ #include "bedlevel.h" #include "../../module/planner.h" -#if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) +#if ANY(MESH_BED_LEVELING, PROBE_MANUALLY) #include "../../module/motion.h" #endif @@ -120,7 +120,7 @@ void reset_bed_level() { TERN_(ABL_PLANAR, planner.bed_level_matrix.set_to_identity()); } -#if EITHER(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) +#if ANY(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) /** * Enable to produce output in JSON format suitable @@ -137,7 +137,7 @@ void reset_bed_level() { */ void print_2d_array(const uint8_t sx, const uint8_t sy, const uint8_t precision, const float *values) { #ifndef SCAD_MESH_OUTPUT - LOOP_L_N(x, sx) { + for (uint8_t x = 0; x < sx; ++x) { serial_spaces(precision + (x < 10 ? 3 : 2)); SERIAL_ECHO(x); } @@ -146,14 +146,14 @@ void reset_bed_level() { #ifdef SCAD_MESH_OUTPUT SERIAL_ECHOLNPGM("measured_z = ["); // open 2D array #endif - LOOP_L_N(y, sy) { + for (uint8_t y = 0; y < sy; ++y) { #ifdef SCAD_MESH_OUTPUT SERIAL_ECHOPGM(" ["); // open sub-array #else if (y < 10) SERIAL_CHAR(' '); SERIAL_ECHO(y); #endif - LOOP_L_N(x, sx) { + for (uint8_t x = 0; x < sx; ++x) { SERIAL_CHAR(' '); const float offset = values[x * sy + y]; if (!isnan(offset)) { @@ -166,7 +166,7 @@ void reset_bed_level() { SERIAL_CHAR(' '); SERIAL_ECHOPGM("NAN"); #else - LOOP_L_N(i, precision + 3) + for (uint8_t i = 0; i < precision + 3; ++i) SERIAL_CHAR(i ? '=' : ' '); #endif } @@ -188,7 +188,7 @@ void reset_bed_level() { #endif // AUTO_BED_LEVELING_BILINEAR || MESH_BED_LEVELING -#if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) +#if ANY(MESH_BED_LEVELING, PROBE_MANUALLY) void _manual_goto_xy(const xy_pos_t &pos) { diff --git a/Marlin/src/feature/bedlevel/bedlevel.h b/Marlin/src/feature/bedlevel/bedlevel.h index aeafec10d6ab..ccb9543e72e5 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.h +++ b/Marlin/src/feature/bedlevel/bedlevel.h @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfigPre.h" -#if EITHER(RESTORE_LEVELING_AFTER_G28, ENABLE_LEVELING_AFTER_G28) +#if ANY(RESTORE_LEVELING_AFTER_G28, ENABLE_LEVELING_AFTER_G28) #define CAN_SET_LEVELING_AFTER_G28 1 #endif @@ -41,7 +41,7 @@ void reset_bed_level(); void set_z_fade_height(const_float_t zfh, const bool do_report=true); #endif -#if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) +#if ANY(MESH_BED_LEVELING, PROBE_MANUALLY) void _manual_goto_xy(const xy_pos_t &pos); #endif @@ -69,7 +69,7 @@ class TemporaryBedLevelingState { #include "mbl/mesh_bed_leveling.h" #endif - #if EITHER(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) + #if ANY(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) #include diff --git a/Marlin/src/feature/bedlevel/hilbert_curve.cpp b/Marlin/src/feature/bedlevel/hilbert_curve.cpp index 7474123e3fe1..57cbdfb34ddd 100644 --- a/Marlin/src/feature/bedlevel/hilbert_curve.cpp +++ b/Marlin/src/feature/bedlevel/hilbert_curve.cpp @@ -28,8 +28,8 @@ constexpr int8_t to_fix(int8_t v) { return v * 2; } constexpr int8_t to_int(int8_t v) { return v / 2; } -constexpr uint8_t log2(uint8_t n) { return (n > 1) ? 1 + log2(n >> 1) : 0; } -constexpr uint8_t order(uint8_t n) { return uint8_t(log2(n - 1)) + 1; } +constexpr uint8_t log2(uint8_t n) { return (n > 1) ? 1 + log2(uint8_t(n >> 1)) : 0; } +constexpr uint8_t order(uint8_t n) { return uint8_t(log2(uint8_t(n - 1))) + 1; } constexpr uint8_t ord = order(_MAX(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y)); constexpr uint8_t dim = _BV(ord); diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp index 193cbbf7654a..787827bb9bfc 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp @@ -40,9 +40,9 @@ mesh_bed_leveling::index_to_ypos[GRID_MAX_POINTS_Y]; mesh_bed_leveling::mesh_bed_leveling() { - LOOP_L_N(i, GRID_MAX_POINTS_X) + for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) index_to_xpos[i] = MESH_MIN_X + i * (MESH_X_DIST); - LOOP_L_N(i, GRID_MAX_POINTS_Y) + for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; ++i) index_to_ypos[i] = MESH_MIN_Y + i * (MESH_Y_DIST); reset(); } diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h index 0193b4f43e5b..cb4f36cd59f2 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h @@ -72,18 +72,18 @@ class mesh_bed_leveling { static float get_mesh_x(const uint8_t i) { return index_to_xpos[i]; } static float get_mesh_y(const uint8_t i) { return index_to_ypos[i]; } - static int8_t cell_index_x(const_float_t x) { + static uint8_t cell_index_x(const_float_t x) { int8_t cx = (x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST); return constrain(cx, 0, GRID_MAX_CELLS_X - 1); } - static int8_t cell_index_y(const_float_t y) { + static uint8_t cell_index_y(const_float_t y) { int8_t cy = (y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST); return constrain(cy, 0, GRID_MAX_CELLS_Y - 1); } - static xy_int8_t cell_indexes(const_float_t x, const_float_t y) { + static xy_uint8_t cell_indexes(const_float_t x, const_float_t y) { return { cell_index_x(x), cell_index_y(y) }; } - static xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } + static xy_uint8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } static int8_t probe_index_x(const_float_t x) { int8_t px = (x - (MESH_MIN_X) + 0.5f * (MESH_X_DIST)) * RECIPROCAL(MESH_X_DIST); @@ -107,7 +107,7 @@ class mesh_bed_leveling { static float get_z_offset() { return z_offset; } static float get_z_correction(const xy_pos_t &pos) { - const xy_int8_t ind = cell_indexes(pos); + const xy_uint8_t ind = cell_indexes(pos); const float x1 = index_to_xpos[ind.x], x2 = index_to_xpos[ind.x+1], y1 = index_to_ypos[ind.y], y2 = index_to_ypos[ind.y+1], z1 = calc_z0(pos.x, x1, z_values[ind.x][ind.y ], x2, z_values[ind.x+1][ind.y ]), diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index b7ee6aeef8a2..46356004e71c 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -149,7 +149,7 @@ static void serial_echo_xy(const uint8_t sp, const int16_t x, const int16_t y) { static void serial_echo_column_labels(const uint8_t sp) { SERIAL_ECHO_SP(7); - LOOP_L_N(i, GRID_MAX_POINTS_X) { + for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) { if (i < 10) SERIAL_CHAR(' '); SERIAL_ECHO(i); SERIAL_ECHO_SP(sp); @@ -199,7 +199,7 @@ void unified_bed_leveling::display_map(const uint8_t map_type) { } // Row Values (I indexes) - LOOP_L_N(i, GRID_MAX_POINTS_X) { + for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) { // Opening Brace or Space const bool is_current = i == curr.x && j == curr.y; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index 05a937c9853d..593722da85ac 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -48,8 +48,8 @@ struct mesh_index_pair; typedef struct { bool C_seen; int8_t KLS_storage_slot; - uint8_t R_repetition, - V_verbosity, + grid_count_t R_repetition; + uint8_t V_verbosity, P_phase, T_map_type; float B_shim_thickness, @@ -77,7 +77,6 @@ class unified_bed_leveling { static bool G29_parse_parameters() __O0; static void shift_mesh_height(); static void probe_entire_mesh(const xy_pos_t &near, const bool do_ubl_mesh_map, const bool stow_probe, const bool do_furthest) __O0; - 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 bool smart_fill_one(const xy_uint8_t &pos, const xy_uint8_t &dir) { @@ -141,26 +140,26 @@ class unified_bed_leveling { return FLOOR((y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST)); } - static int8_t cell_index_x_valid(const_float_t x) { + static bool cell_index_x_valid(const_float_t x) { return WITHIN(cell_index_x_raw(x), 0, GRID_MAX_CELLS_X - 1); } - static int8_t cell_index_y_valid(const_float_t y) { + static bool cell_index_y_valid(const_float_t y) { return WITHIN(cell_index_y_raw(y), 0, GRID_MAX_CELLS_Y - 1); } - static int8_t cell_index_x(const_float_t x) { + static uint8_t cell_index_x(const_float_t x) { return constrain(cell_index_x_raw(x), 0, GRID_MAX_CELLS_X - 1); } - static int8_t cell_index_y(const_float_t y) { + static uint8_t cell_index_y(const_float_t y) { return constrain(cell_index_y_raw(y), 0, GRID_MAX_CELLS_Y - 1); } - static xy_int8_t cell_indexes(const_float_t x, const_float_t y) { + static xy_uint8_t cell_indexes(const_float_t x, const_float_t y) { return { cell_index_x(x), cell_index_y(y) }; } - static xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } + static xy_uint8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } static int8_t closest_x_index(const_float_t x) { const int8_t px = (x - (MESH_MIN_X) + (MESH_X_DIST) * 0.5) * RECIPROCAL(MESH_X_DIST); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index aa69b9467096..bc07d7df85b5 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -354,7 +354,7 @@ void unified_bed_leveling::G29() { // Invalidate one or more nearby mesh points, possibly all. if (parser.seen('I')) { - uint8_t count = parser.has_value() ? parser.value_byte() : 1; + grid_count_t count = parser.has_value() ? parser.value_ushort() : 1; bool invalidate_all = count >= GRID_MAX_POINTS; if (!invalidate_all) { while (count--) { @@ -399,7 +399,7 @@ void unified_bed_leveling::G29() { break; case 1: - LOOP_L_N(x, GRID_MAX_POINTS_X) { // Create a diagonal line several Mesh cells thick that is raised + for (uint8_t x = 0; x < GRID_MAX_POINTS_X; ++x) { // Create a diagonal line several Mesh cells thick that is raised const uint8_t x2 = x + (x < (GRID_MAX_POINTS_Y) - 1 ? 1 : -1); z_values[x][x] += 9.999f; z_values[x][x2] += 9.999f; // We want the altered line several mesh points thick @@ -620,7 +620,6 @@ void unified_bed_leveling::G29() { #endif // UBL_DEVEL_DEBUGGING - // // Load a Mesh from the EEPROM // @@ -763,14 +762,14 @@ void unified_bed_leveling::shift_mesh_height() { TERN_(DWIN_LCD_PROUI, DWIN_LevelingStart()); save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained - uint8_t count = GRID_MAX_POINTS; + grid_count_t count = GRID_MAX_POINTS; mesh_index_pair best; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::G29_START)); do { if (do_ubl_mesh_map) display_map(param.T_map_type); - const uint8_t point_num = (GRID_MAX_POINTS - count) + 1; + const grid_count_t point_num = (GRID_MAX_POINTS - count) + 1; SERIAL_ECHOLNPGM("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, "."); TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), point_num, int(GRID_MAX_POINTS))); @@ -1067,7 +1066,7 @@ void set_message_with_feedback(FSTR_P const fstr) { KEEPALIVE_STATE(PAUSED_FOR_USER); - if (do_ubl_mesh_map) display_map(param.T_map_type); // Display the current point + if (do_ubl_mesh_map) display_map(param.T_map_type); // Display the current point #if IS_TFTGLCD_PANEL ui.ubl_plot(lpos.x, lpos.y); // update plot screen @@ -1142,7 +1141,7 @@ bool unified_bed_leveling::G29_parse_parameters() { param.R_repetition = 0; if (parser.seen('R')) { - param.R_repetition = parser.has_value() ? parser.value_byte() : GRID_MAX_POINTS; + param.R_repetition = parser.has_value() ? parser.value_ushort() : GRID_MAX_POINTS; NOMORE(param.R_repetition, GRID_MAX_POINTS); if (param.R_repetition < 1) { SERIAL_ECHOLNPGM("?(R)epetition count invalid (1+).\n"); @@ -1452,7 +1451,7 @@ void unified_bed_leveling::smart_fill_mesh() { info3 PROGMEM = { (GRID_MAX_POINTS_X) - 1, 0, 0, GRID_MAX_POINTS_Y, true }; // Right side of the mesh looking left static const smart_fill_info * const info[] PROGMEM = { &info0, &info1, &info2, &info3 }; - LOOP_L_N(i, COUNT(info)) { + for (uint8_t i = 0; i < COUNT(info); ++i) { const smart_fill_info *f = (smart_fill_info*)pgm_read_ptr(&info[i]); const int8_t sx = pgm_read_byte(&f->sx), sy = pgm_read_byte(&f->sy), ex = pgm_read_byte(&f->ex), ey = pgm_read_byte(&f->ey); @@ -1565,9 +1564,9 @@ void unified_bed_leveling::smart_fill_mesh() { uint16_t point_num = 1; xy_pos_t rpos; - LOOP_L_N(ix, param.J_grid_size) { + for (uint8_t ix = 0; ix < param.J_grid_size; ++ix) { rpos.x = x_min + ix * dx; - LOOP_L_N(iy, param.J_grid_size) { + for (uint8_t iy = 0; iy < param.J_grid_size; ++iy) { rpos.y = y_min + dy * (zig_zag ? param.J_grid_size - 1 - iy : iy); if (!abort_flag) { @@ -1614,7 +1613,7 @@ void unified_bed_leveling::smart_fill_mesh() { probe.move_z_after_probing(); if (abort_flag || finish_incremental_LSF(&lsf_results)) { - SERIAL_ECHOPGM("Could not complete LSF!"); + SERIAL_ECHOLNPGM("Could not complete LSF!"); return; } @@ -1728,17 +1727,17 @@ void unified_bed_leveling::smart_fill_mesh() { GRID_LOOP(jx, jy) if (!isnan(z_values[jx][jy])) SBI(bitmap[jx], jy); xy_pos_t ppos; - LOOP_L_N(ix, GRID_MAX_POINTS_X) { + for (uint8_t ix = 0; ix < GRID_MAX_POINTS_X; ++ix) { ppos.x = get_mesh_x(ix); - LOOP_L_N(iy, GRID_MAX_POINTS_Y) { + for (uint8_t iy = 0; iy < GRID_MAX_POINTS_Y; ++iy) { ppos.y = get_mesh_y(iy); if (isnan(z_values[ix][iy])) { // undefined mesh point at (ppos.x,ppos.y), compute weighted LSF from original valid mesh points. incremental_LSF_reset(&lsf_results); xy_pos_t rpos; - LOOP_L_N(jx, GRID_MAX_POINTS_X) { + for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; ++jx) { rpos.x = get_mesh_x(jx); - LOOP_L_N(jy, GRID_MAX_POINTS_Y) { + for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; ++jy) { if (TEST(bitmap[jx], jy)) { rpos.y = get_mesh_y(jy); const float rz = z_values[jx][jy], @@ -1748,7 +1747,7 @@ void unified_bed_leveling::smart_fill_mesh() { } } if (finish_incremental_LSF(&lsf_results)) { - SERIAL_ECHOLNPGM("Insufficient data"); + SERIAL_ECHOLNPGM(" Insufficient data"); return; } const float ez = -lsf_results.D - lsf_results.A * ppos.x - lsf_results.B * ppos.y; @@ -1759,7 +1758,7 @@ void unified_bed_leveling::smart_fill_mesh() { } } - SERIAL_ECHOLNPGM("done"); + SERIAL_ECHOLNPGM(" done."); } #endif // UBL_G29_P31 @@ -1772,10 +1771,9 @@ void unified_bed_leveling::smart_fill_mesh() { report_state(); if (storage_slot == -1) - SERIAL_ECHOPGM("No Mesh Loaded."); + SERIAL_ECHOLNPGM("No Mesh Loaded."); else - SERIAL_ECHOPGM("Mesh ", storage_slot, " Loaded."); - SERIAL_EOL(); + SERIAL_ECHOLNPGM("Mesh ", storage_slot, " Loaded."); serial_delay(50); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) @@ -1798,7 +1796,7 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_ECHOLNPGM("MESH_Y_DIST ", MESH_Y_DIST); serial_delay(50); SERIAL_ECHOPGM("X-Axis Mesh Points at: "); - LOOP_L_N(i, GRID_MAX_POINTS_X) { + for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) { SERIAL_ECHO_F(LOGICAL_X_POSITION(get_mesh_x(i)), 3); SERIAL_ECHOPGM(" "); serial_delay(25); @@ -1806,7 +1804,7 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_EOL(); SERIAL_ECHOPGM("Y-Axis Mesh Points at: "); - LOOP_L_N(i, GRID_MAX_POINTS_Y) { + for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; ++i) { SERIAL_ECHO_F(LOGICAL_Y_POSITION(get_mesh_y(i)), 3); SERIAL_ECHOPGM(" "); serial_delay(25); @@ -1820,23 +1818,21 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_EOL(); serial_delay(50); - #if ENABLED(UBL_DEVEL_DEBUGGING) - SERIAL_ECHOLNPGM("ubl_state_at_invocation :", ubl_state_at_invocation, "\nubl_state_recursion_chk :", ubl_state_recursion_chk); - serial_delay(50); + SERIAL_ECHOLNPGM("ubl_state_at_invocation :", ubl_state_at_invocation, "\nubl_state_recursion_chk :", ubl_state_recursion_chk); + serial_delay(50); - SERIAL_ECHOLNPGM("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index())); - serial_delay(50); + SERIAL_ECHOLNPGM("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index())); + serial_delay(50); - SERIAL_ECHOLNPGM("sizeof(ubl) : ", sizeof(ubl)); SERIAL_EOL(); - SERIAL_ECHOLNPGM("z_value[][] size: ", sizeof(z_values)); SERIAL_EOL(); - serial_delay(25); + SERIAL_ECHOLNPGM("sizeof(unified_bed_leveling) : ", sizeof(unified_bed_leveling)); + SERIAL_ECHOLNPGM("z_value[][] size: ", sizeof(z_values)); + serial_delay(25); - SERIAL_ECHOLNPGM("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index()))); - serial_delay(50); + SERIAL_ECHOLNPGM("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index()))); + serial_delay(50); - SERIAL_ECHOLNPGM("EEPROM can hold ", settings.calc_num_meshes(), " meshes.\n"); - serial_delay(25); - #endif // UBL_DEVEL_DEBUGGING + SERIAL_ECHOLNPGM("EEPROM can hold ", settings.calc_num_meshes(), " meshes.\n"); + serial_delay(25); if (!sanity_check()) { echo_name(); @@ -1858,7 +1854,8 @@ void unified_bed_leveling::smart_fill_mesh() { print_hex_word(i); SERIAL_ECHOPGM(": "); for (uint16_t j = 0; j < 16; j++) { - persistentStore.read_data(i + j, &cccc, sizeof(uint8_t)); + int pos = i + j; + persistentStore.read_data(pos, &cccc, sizeof(uint8_t)); print_hex_byte(cccc); SERIAL_CHAR(' '); } diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index 96c30a0efd89..6c6075af638b 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -61,7 +61,7 @@ const xyze_pos_t &start = current_position, &end = destination; #endif - const xy_int8_t istart = cell_indexes(start), iend = cell_indexes(end); + const xy_uint8_t istart = cell_indexes(start), iend = cell_indexes(end); // A move within the same cell needs no splitting if (istart == iend) { @@ -108,7 +108,7 @@ const xy_float_t dist = end - start; const xy_bool_t neg { dist.x < 0, dist.y < 0 }; - const xy_int8_t ineg { int8_t(neg.x), int8_t(neg.y) }; + const xy_uint8_t ineg { uint8_t(neg.x), uint8_t(neg.y) }; const xy_float_t sign { neg.x ? -1.0f : 1.0f, neg.y ? -1.0f : 1.0f }; const xy_int8_t iadd { int8_t(iend.x == istart.x ? 0 : sign.x), int8_t(iend.y == istart.y ? 0 : sign.y) }; @@ -131,7 +131,7 @@ const bool inf_normalized_flag = isinf(e_normalized_dist); #endif - xy_int8_t icell = istart; + xy_uint8_t icell = istart; const float ratio = dist.y / dist.x, // Allow divide by zero c = start.y - ratio * start.x; @@ -252,7 +252,7 @@ * Generic case of a line crossing both X and Y Mesh lines. */ - xy_int8_t cnt = (istart - iend).ABS(); + xy_uint8_t cnt = istart.diff(iend); icell += ineg; @@ -334,16 +334,14 @@ #else // UBL_SEGMENTED #if IS_SCARA - #define DELTA_SEGMENT_MIN_LENGTH 0.25 // SCARA minimum segment size is 0.25mm - #elif ENABLED(DELTA) - #define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DEFAULT_SEGMENTS_PER_SECOND) - #elif ENABLED(POLARGRAPH) - #define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DEFAULT_SEGMENTS_PER_SECOND) + #define SEGMENT_MIN_LENGTH 0.25 // SCARA minimum segment size is 0.25mm + #elif IS_KINEMATIC + #define SEGMENT_MIN_LENGTH 0.10 // (mm) Still subject to DEFAULT_SEGMENTS_PER_SECOND #else // CARTESIAN #ifdef LEVELED_SEGMENT_LENGTH - #define DELTA_SEGMENT_MIN_LENGTH LEVELED_SEGMENT_LENGTH + #define SEGMENT_MIN_LENGTH LEVELED_SEGMENT_LENGTH #else - #define DELTA_SEGMENT_MIN_LENGTH 1.00 // mm (similar to G2/G3 arc segmentation) + #define SEGMENT_MIN_LENGTH 1.00 // (mm) Similar to G2/G3 arc segmentation #endif #endif @@ -361,22 +359,22 @@ const xyze_pos_t total = destination - current_position; const float cart_xy_mm_2 = HYPOT2(total.x, total.y), - cart_xy_mm = SQRT(cart_xy_mm_2); // Total XY distance + cart_xy_mm = SQRT(cart_xy_mm_2); // Total XY distance #if IS_KINEMATIC - const float seconds = cart_xy_mm / scaled_fr_mm_s; // Duration of XY move at requested rate - uint16_t segments = LROUND(segments_per_second * seconds), // Preferred number of segments for distance @ feedrate - seglimit = LROUND(cart_xy_mm * RECIPROCAL(DELTA_SEGMENT_MIN_LENGTH)); // Number of segments at minimum segment length - NOMORE(segments, seglimit); // Limit to minimum segment length (fewer segments) + const float seconds = cart_xy_mm / scaled_fr_mm_s; // Duration of XY move at requested rate + uint16_t segments = LROUND(segments_per_second * seconds), // Preferred number of segments for distance @ feedrate + seglimit = LROUND(cart_xy_mm * RECIPROCAL(SEGMENT_MIN_LENGTH)); // Number of segments at minimum segment length + NOMORE(segments, seglimit); // Limit to minimum segment length (fewer segments) #else - uint16_t segments = LROUND(cart_xy_mm * RECIPROCAL(DELTA_SEGMENT_MIN_LENGTH)); // Cartesian fixed segment length + uint16_t segments = LROUND(cart_xy_mm * RECIPROCAL(SEGMENT_MIN_LENGTH)); // Cartesian fixed segment length #endif - NOLESS(segments, 1U); // Must have at least one segment - const float inv_segments = 1.0f / segments; // Reciprocal to save calculation + NOLESS(segments, 1U); // Must have at least one segment + const float inv_segments = 1.0f / segments; // Reciprocal to save calculation // Add hints to help optimize the move - PlannerHints hints(SQRT(cart_xy_mm_2 + sq(total.z)) * inv_segments); // Length of each segment + PlannerHints hints(SQRT(cart_xy_mm_2 + sq(total.z)) * inv_segments); // Length of each segment #if ENABLED(SCARA_FEEDRATE_SCALING) hints.inv_duration = scaled_fr_mm_s / hints.millimeters; #endif diff --git a/Marlin/src/feature/binary_stream.h b/Marlin/src/feature/binary_stream.h index 417e39c74507..a9cd12b85e9a 100644 --- a/Marlin/src/feature/binary_stream.h +++ b/Marlin/src/feature/binary_stream.h @@ -281,7 +281,7 @@ class BinaryStream { uint8_t data = 0; millis_t transfer_window = millis() + RX_TIMESLICE; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA PORT_REDIRECT(SERIAL_PORTMASK(card.transfer_port_index)); #endif diff --git a/Marlin/src/feature/cancel_object.cpp b/Marlin/src/feature/cancel_object.cpp index bffd2bb72020..9b658315ed8b 100644 --- a/Marlin/src/feature/cancel_object.cpp +++ b/Marlin/src/feature/cancel_object.cpp @@ -44,7 +44,7 @@ void CancelObject::set_active_object(const int8_t obj) { else skipping = false; - #if BOTH(HAS_STATUS_MESSAGE, CANCEL_OBJECTS_REPORTING) + #if ALL(HAS_STATUS_MESSAGE, CANCEL_OBJECTS_REPORTING) if (active_object >= 0) ui.status_printf(0, F(S_FMT " %i"), GET_TEXT(MSG_PRINTING_OBJECT), int(active_object)); else diff --git a/Marlin/src/feature/caselight.h b/Marlin/src/feature/caselight.h index 17e1222acbfa..d88b3d67bf83 100644 --- a/Marlin/src/feature/caselight.h +++ b/Marlin/src/feature/caselight.h @@ -30,7 +30,7 @@ class CaseLight { public: static bool on; - #if ENABLED(CASELIGHT_USES_BRIGHTNESS) + #if CASELIGHT_USES_BRIGHTNESS static uint8_t brightness; #endif diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index 6e5278ce7451..a64f2e686869 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -38,6 +38,10 @@ uint8_t ControllerFan::speed; const controllerFan_settings_t &ControllerFan::settings = controllerFan_defaults; #endif +#if ENABLED(FAN_SOFT_PWM) + uint8_t ControllerFan::soft_pwm_speed; +#endif + void ControllerFan::setup() { SET_OUTPUT(CONTROLLER_FAN_PIN); #ifdef CONTROLLER_FAN2_PIN @@ -92,7 +96,7 @@ void ControllerFan::update() { #endif #if ENABLED(FAN_SOFT_PWM) - thermalManager.soft_pwm_controller_speed = speed; + soft_pwm_speed = speed; #else if (PWM_PIN(CONTROLLER_FAN_PIN)) hal.set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); diff --git a/Marlin/src/feature/controllerfan.h b/Marlin/src/feature/controllerfan.h index 55eb2359b067..68502afa6667 100644 --- a/Marlin/src/feature/controllerfan.h +++ b/Marlin/src/feature/controllerfan.h @@ -60,6 +60,9 @@ class ControllerFan { #else static const controllerFan_settings_t &settings; #endif + #if ENABLED(FAN_SOFT_PWM) + static uint8_t soft_pwm_speed; + #endif static bool state() { return speed > 0; } static void init() { reset(); } static void reset() { TERN_(CONTROLLER_FAN_EDITABLE, settings = controllerFan_defaults); } diff --git a/Marlin/src/feature/cooler.cpp b/Marlin/src/feature/cooler.cpp index e0f99777d19a..6c45e992262e 100644 --- a/Marlin/src/feature/cooler.cpp +++ b/Marlin/src/feature/cooler.cpp @@ -22,7 +22,7 @@ #include "../inc/MarlinConfig.h" -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "cooler.h" Cooler cooler; diff --git a/Marlin/src/feature/digipot/digipot_mcp4018.cpp b/Marlin/src/feature/digipot/digipot_mcp4018.cpp index 3f2ecbfcdc0b..48d7ff492c40 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4018.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4018.cpp @@ -37,7 +37,7 @@ #ifndef DIGIPOT_A4988_Vrefmax #define DIGIPOT_A4988_Vrefmax 1.666 #endif -#define DIGIPOT_MCP4018_MAX_VALUE 127 +#define DIGIPOT_MCP4018_MAX_VALUE 127 #define DIGIPOT_A4988_Itripmax(Vref) ((Vref) / (8.0 * DIGIPOT_A4988_Rsx)) @@ -89,7 +89,7 @@ void DigipotI2C::set_current(const uint8_t channel, const float current) { } void DigipotI2C::init() { - LOOP_L_N(i, DIGIPOT_I2C_NUM_CHANNELS) pots[i].i2c_init(); + for (uint8_t i = 0; i < DIGIPOT_I2C_NUM_CHANNELS; ++i) pots[i].i2c_init(); // Init currents according to Configuration_adv.h static const float digipot_motor_current[] PROGMEM = @@ -99,7 +99,7 @@ void DigipotI2C::init() { DIGIPOT_I2C_MOTOR_CURRENTS #endif ; - LOOP_L_N(i, COUNT(digipot_motor_current)) + for (uint8_t i = 0; i < COUNT(digipot_motor_current); ++i) set_current(i, pgm_read_float(&digipot_motor_current[i])); } diff --git a/Marlin/src/feature/digipot/digipot_mcp4451.cpp b/Marlin/src/feature/digipot/digipot_mcp4451.cpp index ba5ecdad050a..e35b42a28bd5 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4451.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4451.cpp @@ -35,8 +35,8 @@ // Settings for the I2C based DIGIPOT (MCP4451) on Azteeg X3 Pro #if MB(5DPRINT) - #define DIGIPOT_I2C_FACTOR 117.96f - #define DIGIPOT_I2C_MAX_CURRENT 1.736f + #define DIGIPOT_I2C_FACTOR 117.96f + #define DIGIPOT_I2C_MAX_CURRENT 1.736f #elif MB(AZTEEG_X5_MINI, AZTEEG_X5_MINI_WIFI) #define DIGIPOT_I2C_FACTOR 113.5f #define DIGIPOT_I2C_MAX_CURRENT 2.0f @@ -94,7 +94,7 @@ void DigipotI2C::init() { DIGIPOT_I2C_MOTOR_CURRENTS #endif ; - LOOP_L_N(i, COUNT(digipot_motor_current)) + for (uint8_t i = 0; i < COUNT(digipot_motor_current); ++i) set_current(i, pgm_read_float(&digipot_motor_current[i])); } diff --git a/Marlin/src/feature/direct_stepping.h b/Marlin/src/feature/direct_stepping.h index 962310281edb..b8a803f8115b 100644 --- a/Marlin/src/feature/direct_stepping.h +++ b/Marlin/src/feature/direct_stepping.h @@ -80,9 +80,6 @@ namespace DirectStepping { static void set_page_state(const page_idx_t page_idx, const PageState page_state); }; - template struct TypeSelector { typedef T type;} ; - template struct TypeSelector { typedef F type; }; - template struct config_t { static constexpr char CONTROL_CHAR = '!'; @@ -98,8 +95,8 @@ namespace DirectStepping { static constexpr int TOTAL_STEPS = SEGMENT_STEPS * SEGMENTS; static constexpr int PAGE_SIZE = (AXIS_COUNT * BITS_SEGMENT * SEGMENTS) / 8; - typedef typename TypeSelector<(PAGE_SIZE>256), uint16_t, uint8_t>::type write_byte_idx_t; - typedef typename TypeSelector<(PAGE_COUNT>256), uint16_t, uint8_t>::type page_idx_t; + typedef uvalue_t(PAGE_SIZE - 1) write_byte_idx_t; + typedef uvalue_t(PAGE_COUNT - 1) page_idx_t; }; template diff --git a/Marlin/src/feature/e_parser.cpp b/Marlin/src/feature/e_parser.cpp index cfe0956aa789..b50a12d1af18 100644 --- a/Marlin/src/feature/e_parser.cpp +++ b/Marlin/src/feature/e_parser.cpp @@ -33,7 +33,7 @@ // Static data members bool EmergencyParser::killed_by_M112, // = false EmergencyParser::quickstop_by_M410, - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA EmergencyParser::sd_abort_by_M524, #endif EmergencyParser::enabled; diff --git a/Marlin/src/feature/e_parser.h b/Marlin/src/feature/e_parser.h index 3a15a7ffa0f9..df4456d8d3ca 100644 --- a/Marlin/src/feature/e_parser.h +++ b/Marlin/src/feature/e_parser.h @@ -58,7 +58,7 @@ class EmergencyParser { EP_M10, EP_M108, EP_M11, EP_M112, EP_M4, EP_M41, EP_M410, - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA EP_M5, EP_M52, EP_M524, #endif #if ENABLED(HOST_PROMPT_SUPPORT) @@ -79,7 +79,7 @@ class EmergencyParser { static bool killed_by_M112; static bool quickstop_by_M410; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA static bool sd_abort_by_M524; #endif @@ -152,7 +152,7 @@ class EmergencyParser { case ' ': break; case '1': state = EP_M1; break; case '4': state = EP_M4; break; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA case '5': state = EP_M5; break; #endif #if ENABLED(HOST_PROMPT_SUPPORT) @@ -175,7 +175,7 @@ class EmergencyParser { case EP_M4: state = (c == '1') ? EP_M41 : EP_IGNORE; break; case EP_M41: state = (c == '0') ? EP_M410 : EP_IGNORE; break; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA case EP_M5: state = (c == '2') ? EP_M52 : EP_IGNORE; break; case EP_M52: state = (c == '4') ? EP_M524 : EP_IGNORE; break; #endif @@ -215,7 +215,7 @@ class EmergencyParser { case EP_M108: wait_for_user = wait_for_heatup = false; break; case EP_M112: killed_by_M112 = true; break; case EP_M410: quickstop_by_M410 = true; break; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA case EP_M524: sd_abort_by_M524 = true; break; #endif #if ENABLED(HOST_PROMPT_SUPPORT) diff --git a/Marlin/src/feature/easythreed_ui.cpp b/Marlin/src/feature/easythreed_ui.cpp index b15daffc09be..40969e3949c9 100644 --- a/Marlin/src/feature/easythreed_ui.cpp +++ b/Marlin/src/feature/easythreed_ui.cpp @@ -190,31 +190,28 @@ void EasythreedUI::printButton() { 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 + 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 + const int16_t filecnt = card.get_num_items(); // 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.selectFileByIndex(filecnt); // Select the last file (without sort) card.openAndPrintFile(card.filename); // Start printing it - break; - } + } 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; - } + } 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; - } + } break; } } else { // Register a longer press diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index 092ce0f8b852..0386b5ccdb35 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -27,7 +27,6 @@ //todo: try faster I2C speed; tweak TWI_FREQ (400000L, or faster?); or just TWBR = ((CPU_FREQ / 400000L) - 16) / 2; //todo: consider Marlin-optimized Wire library; i.e. MarlinWire, like MarlinSerial - #include "../inc/MarlinConfig.h" #if ENABLED(I2C_POSITION_ENCODERS) @@ -49,7 +48,7 @@ void I2CPositionEncoder::init(const uint8_t address, const AxisEnum axis) { initialized = true; - SERIAL_ECHOLNPGM("Setting up encoder on ", AS_CHAR(AXIS_CHAR(encoderAxis)), " axis, addr = ", address); + SERIAL_ECHOLNPGM("Setting up encoder on ", C(AXIS_CHAR(encoderAxis)), " axis, addr = ", address); position = get_position(); } @@ -67,7 +66,7 @@ void I2CPositionEncoder::update() { /* if (trusted) { //commented out as part of the note below trusted = false; - SERIAL_ECHOLNPGM("Fault detected on ", AS_CHAR(AXIS_CHAR(encoderAxis)), " axis encoder. Disengaging error correction until module is trusted again."); + SERIAL_ECHOLNPGM("Fault detected on ", C(AXIS_CHAR(encoderAxis)), " axis encoder. Disengaging error correction until module is trusted again."); } */ return; @@ -92,7 +91,7 @@ void I2CPositionEncoder::update() { if (millis() - lastErrorTime > I2CPE_TIME_TRUSTED) { trusted = true; - SERIAL_ECHOLNPGM("Untrusted encoder module on ", AS_CHAR(AXIS_CHAR(encoderAxis)), " axis has been fault-free for set duration, reinstating error correction."); + SERIAL_ECHOLNPGM("Untrusted encoder module on ", C(AXIS_CHAR(encoderAxis)), " axis has been fault-free for set duration, reinstating error correction."); //the encoder likely lost its place when the error occurred, so we'll reset and use the printer's //idea of where it the axis is to re-initialize @@ -138,7 +137,7 @@ void I2CPositionEncoder::update() { errIdx = (errIdx >= I2CPE_ERR_ARRAY_SIZE - 1) ? 0 : errIdx + 1; err[errIdx] = get_axis_error_steps(false); - LOOP_L_N(i, I2CPE_ERR_ARRAY_SIZE) { + for (uint8_t i = 0; i < I2CPE_ERR_ARRAY_SIZE; ++i) { sum += err[i]; if (i) diffSum += ABS(err[i-1] - err[i]); } @@ -170,7 +169,7 @@ void I2CPositionEncoder::update() { errPrst[errPrstIdx++] = error; // Error must persist for I2CPE_ERR_PRST_ARRAY_SIZE error cycles. This also serves to improve the average accuracy if (errPrstIdx >= I2CPE_ERR_PRST_ARRAY_SIZE) { float sumP = 0; - LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i]; + for (uint8_t i = 0; i < I2CPE_ERR_PRST_ARRAY_SIZE; ++i) sumP += errPrst[i]; const int32_t errorP = int32_t(sumP * RECIPROCAL(I2CPE_ERR_PRST_ARRAY_SIZE)); SERIAL_CHAR(AXIS_CHAR(encoderAxis)); SERIAL_ECHOLNPGM(" : CORRECT ERR ", errorP * planner.mm_per_step[encoderAxis], "mm"); @@ -404,7 +403,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { planner.synchronize(); - LOOP_L_N(i, iter) { + for (uint8_t i = 0; i < iter; ++i) { TERN_(HAS_EXTRUDERS, startCoord.e = planner.get_axis_position_mm(E_AXIS)); planner.buffer_line(startCoord, fr_mm_s, 0); planner.synchronize(); @@ -425,22 +424,22 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { travelledDistance = mm_from_count(ABS(stopCount - startCount)); SERIAL_ECHOLNPGM("Attempted travel: ", travelDistance, "mm"); - SERIAL_ECHOLNPGM(" Actual travel: ", travelledDistance, "mm"); + SERIAL_ECHOLNPGM(" Actual travel: ", travelledDistance, "mm"); - //Calculate new axis steps per unit + // Calculate new axis steps per unit old_steps_mm = planner.settings.axis_steps_per_mm[encoderAxis]; new_steps_mm = (old_steps_mm * travelDistance) / travelledDistance; SERIAL_ECHOLNPGM("Old steps/mm: ", old_steps_mm); SERIAL_ECHOLNPGM("New steps/mm: ", new_steps_mm); - //Save new value + // Save new value planner.settings.axis_steps_per_mm[encoderAxis] = new_steps_mm; if (iter > 1) { total += new_steps_mm; - // swap start and end points so next loop runs from current position + // Swap start and end points so next loop runs from current position const float tempCoord = startCoord[encoderAxis]; startCoord[encoderAxis] = endCoord[encoderAxis]; endCoord[encoderAxis] = tempCoord; @@ -465,7 +464,6 @@ void I2CPositionEncoder::reset() { TERN_(I2CPE_ERR_ROLLING_AVERAGE, ZERO(err)); } - bool I2CPositionEncodersMgr::I2CPE_anyaxis; uint8_t I2CPositionEncodersMgr::I2CPE_addr, I2CPositionEncodersMgr::I2CPE_idx; diff --git a/Marlin/src/feature/encoder_i2c.h b/Marlin/src/feature/encoder_i2c.h index f25fe2ea6bc4..861a8e52d4d6 100644 --- a/Marlin/src/feature/encoder_i2c.h +++ b/Marlin/src/feature/encoder_i2c.h @@ -90,7 +90,7 @@ #define I2CPE_PARSE_ERR 1 #define I2CPE_PARSE_OK 0 -#define LOOP_PE(VAR) LOOP_L_N(VAR, I2CPE_ENCODER_CNT) +#define LOOP_PE(VAR) for (uint8_t VAR = 0; VAR < I2CPE_ENCODER_CNT; ++VAR) #define CHECK_IDX() do{ if (!WITHIN(idx, 0, I2CPE_ENCODER_CNT - 1)) return; }while(0) typedef union { @@ -261,32 +261,32 @@ class I2CPositionEncodersMgr { static void report_error_count(const int8_t idx, const AxisEnum axis) { CHECK_IDX(); - SERIAL_ECHOLNPGM("Error count on ", AS_CHAR(AXIS_CHAR(axis)), " axis is ", encoders[idx].get_error_count()); + SERIAL_ECHOLNPGM("Error count on ", C(AXIS_CHAR(axis)), " axis is ", encoders[idx].get_error_count()); } static void reset_error_count(const int8_t idx, const AxisEnum axis) { CHECK_IDX(); encoders[idx].set_error_count(0); - SERIAL_ECHOLNPGM("Error count on ", AS_CHAR(AXIS_CHAR(axis)), " axis has been reset."); + SERIAL_ECHOLNPGM("Error count on ", C(AXIS_CHAR(axis)), " axis has been reset."); } static void enable_ec(const int8_t idx, const bool enabled, const AxisEnum axis) { CHECK_IDX(); encoders[idx].set_ec_enabled(enabled); - SERIAL_ECHOPGM("Error correction on ", AS_CHAR(AXIS_CHAR(axis))); + SERIAL_ECHOPGM("Error correction on ", C(AXIS_CHAR(axis))); SERIAL_ECHO_TERNARY(encoders[idx].get_ec_enabled(), " axis is ", "en", "dis", "abled.\n"); } static void set_ec_threshold(const int8_t idx, const float newThreshold, const AxisEnum axis) { CHECK_IDX(); encoders[idx].set_ec_threshold(newThreshold); - SERIAL_ECHOLNPGM("Error correct threshold for ", AS_CHAR(AXIS_CHAR(axis)), " axis set to ", newThreshold, "mm."); + SERIAL_ECHOLNPGM("Error correct threshold for ", C(AXIS_CHAR(axis)), " axis set to ", newThreshold, "mm."); } static void get_ec_threshold(const int8_t idx, const AxisEnum axis) { CHECK_IDX(); const float threshold = encoders[idx].get_ec_threshold(); - SERIAL_ECHOLNPGM("Error correct threshold for ", AS_CHAR(AXIS_CHAR(axis)), " axis is ", threshold, "mm."); + SERIAL_ECHOLNPGM("Error correct threshold for ", C(AXIS_CHAR(axis)), " axis is ", threshold, "mm."); } static int8_t idx_from_axis(const AxisEnum axis) { diff --git a/Marlin/src/feature/fancheck.cpp b/Marlin/src/feature/fancheck.cpp index 126b79b0a409..844191e7e442 100644 --- a/Marlin/src/feature/fancheck.cpp +++ b/Marlin/src/feature/fancheck.cpp @@ -72,7 +72,7 @@ void FanCheck::update_tachometers() { bool status; #define _TACHO_CASE(N) case N: status = READ(E##N##_FAN_TACHO_PIN); break; - LOOP_L_N(f, TACHO_COUNT) { + for (uint8_t f = 0; f < TACHO_COUNT; ++f) { switch (f) { #if HAS_E0_FAN_TACHO _TACHO_CASE(0) @@ -113,7 +113,7 @@ void FanCheck::compute_speed(uint16_t elapsedTime) { static uint8_t fan_reported_errors_msk = 0; uint8_t fan_error_msk = 0; - LOOP_L_N(f, TACHO_COUNT) { + for (uint8_t f = 0; f < TACHO_COUNT; ++f) { switch (f) { TERN_(HAS_E0_FAN_TACHO, case 0:) TERN_(HAS_E1_FAN_TACHO, case 1:) @@ -150,7 +150,7 @@ void FanCheck::compute_speed(uint16_t elapsedTime) { if (fan_error_msk & ~fan_reported_errors_msk) { // Handle new faults only - LOOP_L_N(f, TACHO_COUNT) if (TEST(fan_error_msk, f)) report_speed_error(f); + for (uint8_t f = 0; f < TACHO_COUNT; ++f) if (TEST(fan_error_msk, f)) report_speed_error(f); } fan_reported_errors_msk = fan_error_msk; } @@ -176,8 +176,8 @@ void FanCheck::report_speed_error(uint8_t fan) { } void FanCheck::print_fan_states() { - LOOP_L_N(s, 2) { - LOOP_L_N(f, TACHO_COUNT) { + for (uint8_t s = 0; s < 2; ++s) { + for (uint8_t f = 0; f < TACHO_COUNT; ++f) { switch (f) { TERN_(HAS_E0_FAN_TACHO, case 0:) TERN_(HAS_E1_FAN_TACHO, case 1:) diff --git a/Marlin/src/feature/filwidth.cpp b/Marlin/src/feature/filwidth.cpp index 2bd9c789808e..3befd7752a6e 100644 --- a/Marlin/src/feature/filwidth.cpp +++ b/Marlin/src/feature/filwidth.cpp @@ -42,7 +42,7 @@ int8_t FilamentWidthSensor::ratios[MAX_MEASUREMENT_DELAY + 1], // Ring void FilamentWidthSensor::init() { const int8_t ratio = sample_to_size_ratio(); - LOOP_L_N(i, COUNT(ratios)) ratios[i] = ratio; + for (uint8_t i = 0; i < COUNT(ratios); ++i) ratios[i] = ratio; index_r = index_w = 0; } diff --git a/Marlin/src/feature/filwidth.h b/Marlin/src/feature/filwidth.h index 9eb1e77762ff..ab50fe0af3f9 100644 --- a/Marlin/src/feature/filwidth.h +++ b/Marlin/src/feature/filwidth.h @@ -67,7 +67,7 @@ class FilamentWidthSensor { } // Convert raw measurement to mm - static float raw_to_mm(const uint16_t v) { return v * float(ADC_VREF) * RECIPROCAL(float(MAX_RAW_THERMISTOR_VALUE)); } + static float raw_to_mm(const uint16_t v) { return v * (float(ADC_VREF_MV) / 1000.0f) * RECIPROCAL(float(MAX_RAW_THERMISTOR_VALUE)); } static float raw_to_mm() { return raw_to_mm(raw); } // A scaled reading is ready diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index 28355640d223..8f2edad158dd 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -195,8 +195,6 @@ void FWRetract::retract(const bool retracting E_OPTARG(bool swapping/*=false*/)) //*/ } -//extern const char SP_Z_STR[]; - /** * M207: Set firmware retraction values * @@ -265,5 +263,4 @@ void FWRetract::M208_report() { #endif // FWRETRACT_AUTORETRACT - #endif // FWRETRACT diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index 773b6ebc61a4..235253b5a345 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -187,13 +187,13 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { switch (response) { case 0: // "Purge More" button - #if BOTH(M600_PURGE_MORE_RESUMABLE, ADVANCED_PAUSE_FEATURE) + #if ALL(M600_PURGE_MORE_RESUMABLE, ADVANCED_PAUSE_FEATURE) pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; // Simulate menu selection (menu exits, doesn't extrude more) #endif break; case 1: // "Continue" / "Disable Runout" button - #if BOTH(M600_PURGE_MORE_RESUMABLE, ADVANCED_PAUSE_FEATURE) + #if ALL(M600_PURGE_MORE_RESUMABLE, ADVANCED_PAUSE_FEATURE) pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; // Simulate menu selection #endif #if HAS_FILAMENT_SENSOR @@ -209,7 +209,7 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); break; case PROMPT_PAUSE_RESUME: - #if BOTH(ADVANCED_PAUSE_FEATURE, SDSUPPORT) + #if ALL(ADVANCED_PAUSE_FEATURE, HAS_MEDIA) extern const char M24_STR[]; queue.inject_P(M24_STR); #endif diff --git a/Marlin/src/feature/hotend_idle.cpp b/Marlin/src/feature/hotend_idle.cpp index 4b137f42da7b..b79cb568a2a4 100644 --- a/Marlin/src/feature/hotend_idle.cpp +++ b/Marlin/src/feature/hotend_idle.cpp @@ -37,7 +37,7 @@ #include "../module/planner.h" #include "../lcd/marlinui.h" -extern HotendIdleProtection hotend_idle; +HotendIdleProtection hotend_idle; millis_t HotendIdleProtection::next_protect_ms = 0; diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 3753235ab5e7..ac7f1815162b 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -30,7 +30,7 @@ #include "leds.h" -#if EITHER(CASE_LIGHT_USE_RGB_LED, CASE_LIGHT_USE_NEOPIXEL) +#if ANY(CASE_LIGHT_USE_RGB_LED, CASE_LIGHT_USE_NEOPIXEL) #include "../../feature/caselight.h" #endif @@ -50,7 +50,7 @@ LEDLights leds; void LEDLights::setup() { - #if EITHER(RGB_LED, RGBW_LED) + #if ANY(RGB_LED, RGBW_LED) if (PWM_PIN(RGB_LED_R_PIN)) SET_PWM(RGB_LED_R_PIN); else SET_OUTPUT(RGB_LED_R_PIN); if (PWM_PIN(RGB_LED_G_PIN)) SET_PWM(RGB_LED_G_PIN); else SET_OUTPUT(RGB_LED_G_PIN); if (PWM_PIN(RGB_LED_B_PIN)) SET_PWM(RGB_LED_B_PIN); else SET_OUTPUT(RGB_LED_B_PIN); @@ -76,8 +76,8 @@ void LEDLights::setup() { #endif delay(200); - LOOP_L_N(i, led_pin_count) { - LOOP_LE_N(b, 200) { + for (uint8_t i = 0; i < led_pin_count; ++i) { + for (uint8_t b = 0; b <= 200; ++b) { const uint16_t led_pwm = b <= 100 ? b : 200 - b; if (i == 0 && PWM_PIN(RGB_LED_R_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_R_PIN), led_pwm); else WRITE(RGB_LED_R_PIN, b < 100 ? HIGH : LOW); if (i == 1 && PWM_PIN(RGB_LED_G_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_G_PIN), led_pwm); else WRITE(RGB_LED_G_PIN, b < 100 ? HIGH : LOW); @@ -95,7 +95,62 @@ void LEDLights::setup() { delay(500); } #endif // RGB_STARTUP_TEST - #endif + + #elif ALL(PCA9632, RGB_STARTUP_TEST) // PCA9632 RGB_STARTUP_TEST + + constexpr int8_t led_pin_count = TERN(HAS_WHITE_LED, 4, 3); + + // Startup animation + LEDColor curColor = LEDColorOff(); + PCA9632_set_led_color(curColor); // blackout + delay(200); + + /** + * LED Pin Counter steps -> events + * | 0-100 | 100-200 | 200-300 | 300-400 | + * fade in steady | fade out + * start next pin fade in + */ + + uint16_t led_pin_counters[led_pin_count] = { 1, 0, 0 }; + + bool canEnd = false; + while (led_pin_counters[0] != 99 || !canEnd) { + if (led_pin_counters[0] == 99) // End loop next time pin0 counter is 99 + canEnd = true; + for (uint8_t i = 0; i < led_pin_count; ++i) { + if (led_pin_counters[i] > 0) { + if (++led_pin_counters[i] == 400) // turn off current pin counter in led_pin_counters + led_pin_counters[i] = 0; + else if (led_pin_counters[i] == 201) { // start next pin pwm + led_pin_counters[i + 1 == led_pin_count ? 0 : i + 1] = 1; + i++; // skip next pin in this loop so it doesn't increment twice + } + } + } + uint16_t r, g, b; + r = led_pin_counters[0]; curColor.r = r <= 100 ? r : r <= 300 ? 100 : 400 - r; + g = led_pin_counters[1]; curColor.g = g <= 100 ? g : g <= 300 ? 100 : 400 - g; + b = led_pin_counters[2]; curColor.b = b <= 100 ? b : b <= 300 ? 100 : 400 - b; + #if HAS_WHITE_LED + const uint16_t w = led_pin_counters[3]; curColor.w = w <= 100 ? w : w <= 300 ? 100 : 400 - w; + #endif + PCA9632_set_led_color(curColor); + delay(RGB_STARTUP_TEST_INNER_MS); + } + + // Fade to white + for (uint8_t led_pwm = 0; led_pwm <= 100; ++led_pwm) { + NOLESS(curColor.r, led_pwm); + NOLESS(curColor.g, led_pwm); + NOLESS(curColor.b, led_pwm); + TERN_(HAS_WHITE_LED, NOLESS(curColor.w, led_pwm)); + PCA9632_set_led_color(curColor); + delay(RGB_STARTUP_TEST_INNER_MS); + } + + #endif // PCA9632 && RGB_STARTUP_TEST + TERN_(NEOPIXEL_LED, neo.init()); TERN_(PCA9533, PCA9533_init()); TERN_(LED_USER_PRESET_STARTUP, set_default()); @@ -121,7 +176,7 @@ void LEDLights::set_color(const LEDColor &incol #endif #endif - #if BOTH(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) + #if ALL(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) // Update brightness only if caselight is ON or switching leds off if (caselight.on || incol.is_off()) #endif @@ -136,7 +191,7 @@ void LEDLights::set_color(const LEDColor &incol } #endif - #if BOTH(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) + #if ALL(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) // Update color only if caselight is ON or switching leds off if (caselight.on || incol.is_off()) #endif @@ -151,7 +206,7 @@ void LEDLights::set_color(const LEDColor &incol #endif - #if EITHER(RGB_LED, RGBW_LED) + #if ANY(RGB_LED, RGBW_LED) // This variant uses 3-4 separate pins for the RGB(W) components. // If the pins can do PWM then their intensity will be set. @@ -173,7 +228,7 @@ void LEDLights::set_color(const LEDColor &incol TERN_(PCA9632, PCA9632_set_led_color(incol)); TERN_(PCA9533, PCA9533_set_rgb(incol.r, incol.g, incol.b)); - #if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS) + #if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS) // Don't update the color when OFF lights_on = !incol.is_off(); if (lights_on) color = incol; diff --git a/Marlin/src/feature/leds/leds.h b/Marlin/src/feature/leds/leds.h index c6137b45c355..7a31ca685d49 100644 --- a/Marlin/src/feature/leds/leds.h +++ b/Marlin/src/feature/leds/leds.h @@ -30,7 +30,7 @@ #include // A white component can be passed -#if EITHER(RGBW_LED, PCA9632_RGBW) +#if ANY(RGBW_LED, PCA9632_RGBW) #define HAS_WHITE_LED 1 #endif @@ -164,7 +164,7 @@ class LEDLights { #if ENABLED(LED_CONTROL_MENU) static void toggle(); // swap "off" with color #endif - #if EITHER(LED_CONTROL_MENU, CASE_LIGHT_USE_RGB_LED) || LED_POWEROFF_TIMEOUT > 0 + #if ANY(LED_CONTROL_MENU, CASE_LIGHT_USE_RGB_LED) || LED_POWEROFF_TIMEOUT > 0 static void update() { set_color(color); } #endif diff --git a/Marlin/src/feature/leds/neopixel.cpp b/Marlin/src/feature/leds/neopixel.cpp index ab7ffe217796..d157ba73d316 100644 --- a/Marlin/src/feature/leds/neopixel.cpp +++ b/Marlin/src/feature/leds/neopixel.cpp @@ -30,7 +30,7 @@ #include "leds.h" -#if EITHER(NEOPIXEL_STARTUP_TEST, NEOPIXEL2_STARTUP_TEST) +#if ANY(NEOPIXEL_STARTUP_TEST, NEOPIXEL2_STARTUP_TEST) #include "../../core/utility.h" #endif @@ -54,7 +54,7 @@ Adafruit_NeoPixel Marlin_NeoPixel::adaneo1(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEOPIX set_background_color(background_color); } -#endif +#endif // NEOPIXEL_BKGD_INDEX_FIRST void Marlin_NeoPixel::set_color(const uint32_t color) { if (neoindex >= 0) { diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h index 2048e2c2eebf..a724083f1761 100644 --- a/Marlin/src/feature/leds/neopixel.h +++ b/Marlin/src/feature/leds/neopixel.h @@ -58,7 +58,7 @@ #define MULTIPLE_NEOPIXEL_TYPES 1 #endif -#if EITHER(MULTIPLE_NEOPIXEL_TYPES, NEOPIXEL2_INSERIES) +#if ANY(MULTIPLE_NEOPIXEL_TYPES, NEOPIXEL2_INSERIES) #define CONJOINED_NEOPIXEL 1 #endif @@ -66,7 +66,7 @@ // Types // ------------------------ -typedef IF<(TERN0(NEOPIXEL_LED, NEOPIXEL_PIXELS > 127)), int16_t, int8_t>::type pixel_index_t; +typedef value_t(TERN0(NEOPIXEL_LED, NEOPIXEL_PIXELS)) pixel_index_t; // ------------------------ // Classes diff --git a/Marlin/src/feature/leds/pca9533.cpp b/Marlin/src/feature/leds/pca9533.cpp index 914db21ba31c..d71760e2cb63 100644 --- a/Marlin/src/feature/leds/pca9533.cpp +++ b/Marlin/src/feature/leds/pca9533.cpp @@ -1,4 +1,4 @@ -/* +/** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * diff --git a/Marlin/src/feature/leds/pca9533.h b/Marlin/src/feature/leds/pca9533.h index 431058c49136..3a18e96b245d 100644 --- a/Marlin/src/feature/leds/pca9533.h +++ b/Marlin/src/feature/leds/pca9533.h @@ -1,4 +1,4 @@ -/* +/** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * @@ -21,7 +21,7 @@ */ #pragma once -/* +/** * Driver for the PCA9533 LED controller found on the MightyBoard * used by FlashForge Creator Pro, MakerBot, etc. * Written 2020 APR 01 by grauerfuchs diff --git a/Marlin/src/feature/leds/printer_event_leds.h b/Marlin/src/feature/leds/printer_event_leds.h index 2a4342e8f55c..3a037eba96e5 100644 --- a/Marlin/src/feature/leds/printer_event_leds.h +++ b/Marlin/src/feature/leds/printer_event_leds.h @@ -59,7 +59,7 @@ class PrinterEventLEDs { static void onPidTuningDone(LEDColor c) { leds.set_color(c); } #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA static void onPrintCompleted() { leds.set_green(); @@ -80,7 +80,7 @@ class PrinterEventLEDs { #endif } - #endif // SDSUPPORT + #endif // HAS_MEDIA }; extern PrinterEventLEDs printerEventLEDs; diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index 2fdfcba32d21..ac2881c0b5f9 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -39,7 +39,7 @@ #if ENABLED(MAX7219_DEBUG) -#define MAX7219_ERRORS // Disable to save 406 bytes of Program Memory +#define MAX7219_ERRORS // Requires ~400 bytes of flash #include "max7219.h" @@ -136,7 +136,7 @@ uint8_t Max7219::suspended; // = 0; void Max7219::error(FSTR_P const func, const int32_t v1, const int32_t v2/*=-1*/) { #if ENABLED(MAX7219_ERRORS) SERIAL_ECHOPGM("??? Max7219::"); - SERIAL_ECHOF(func, AS_CHAR('(')); + SERIAL_ECHOF(func, C('(')); SERIAL_ECHO(v1); if (v2 > 0) SERIAL_ECHOPGM(", ", v2); SERIAL_CHAR(')'); @@ -155,7 +155,7 @@ void Max7219::error(FSTR_P const func, const int32_t v1, const int32_t v2/*=-1*/ */ inline uint32_t flipped(const uint32_t bits, const uint8_t n_bytes) { uint32_t mask = 1, outbits = 0; - LOOP_L_N(b, n_bytes * 8) { + for (uint8_t b = 0; b < n_bytes * 8; ++b) { outbits <<= 1; if (bits & mask) outbits |= 1; mask <<= 1; @@ -338,13 +338,13 @@ void Max7219::fill() { void Max7219::clear_row(const uint8_t row) { if (row >= MAX7219_Y_LEDS) return error(F("clear_row"), row); - LOOP_L_N(x, MAX7219_X_LEDS) CLR_7219(x, row); + for (uint8_t x = 0; x < MAX7219_X_LEDS; ++x) CLR_7219(x, row); send_row(row); } void Max7219::clear_column(const uint8_t col) { if (col >= MAX7219_X_LEDS) return error(F("set_column"), col); - LOOP_L_N(y, MAX7219_Y_LEDS) CLR_7219(col, y); + for (uint8_t y = 0; y < MAX7219_Y_LEDS; ++y) CLR_7219(col, y); send_column(col); } @@ -356,7 +356,7 @@ void Max7219::clear_column(const uint8_t col) { void Max7219::set_row(const uint8_t row, const uint32_t val) { if (row >= MAX7219_Y_LEDS) return error(F("set_row"), row); uint32_t mask = _BV32(MAX7219_X_LEDS - 1); - LOOP_L_N(x, MAX7219_X_LEDS) { + for (uint8_t x = 0; x < MAX7219_X_LEDS; ++x) { if (val & mask) SET_7219(x, row); else CLR_7219(x, row); mask >>= 1; } @@ -371,7 +371,7 @@ void Max7219::set_row(const uint8_t row, const uint32_t val) { void Max7219::set_column(const uint8_t col, const uint32_t val) { if (col >= MAX7219_X_LEDS) return error(F("set_column"), col); uint32_t mask = _BV32(MAX7219_Y_LEDS - 1); - LOOP_L_N(y, MAX7219_Y_LEDS) { + for (uint8_t y = 0; y < MAX7219_Y_LEDS; ++y) { if (val & mask) SET_7219(col, y); else CLR_7219(col, y); mask >>= 1; } @@ -436,23 +436,23 @@ void Max7219::set_columns_32bits(const uint8_t x, uint32_t val) { // Initialize the Max7219 void Max7219::register_setup() { - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_scanLimit, 0x07); pulse_load(); // Tell the chips to load the clocked out data - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_decodeMode, 0x00); // Using an led matrix (not digits) pulse_load(); // Tell the chips to load the clocked out data - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_shutdown, 0x01); // Not in shutdown mode pulse_load(); // Tell the chips to load the clocked out data - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_displayTest, 0x00); // No display test pulse_load(); // Tell the chips to load the clocked out data - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_intensity, 0x01 & 0x0F); // The first 0x0F is the value you can set // Range: 0x00 to 0x0F pulse_load(); // Tell the chips to load the clocked out data @@ -471,7 +471,7 @@ void Max7219::register_setup() { constexpr millis_t pattern_delay = 4; int8_t spiralx, spiraly, spiral_dir; - IF<(MAX7219_LEDS > 255), uint16_t, uint8_t>::type spiral_count; + uvalue_t(MAX7219_LEDS) spiral_count; void Max7219::test_pattern() { constexpr int8_t way[][2] = { { 1, 0 }, { 0, 1 }, { -1, 0 }, { 0, -1 } }; @@ -707,7 +707,7 @@ void Max7219::idle_tasks() { #ifdef MAX7219_DEBUG_PLANNER_QUEUE static int16_t last_depth = 0; - const int16_t current_depth = (head - tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1) & 0xF; + const int16_t current_depth = BLOCK_MOD(head - tail + (BLOCK_BUFFER_SIZE)) & 0xF; if (current_depth != last_depth) { quantity16(MAX7219_DEBUG_PLANNER_QUEUE, last_depth, current_depth, &row_change_mask); last_depth = current_depth; @@ -726,7 +726,7 @@ void Max7219::idle_tasks() { // batch line updates suspended--; if (!suspended) - LOOP_L_N(i, 8) if (row_change_mask & _BV(i)) + for (uint8_t i = 0; i < 8; ++i) if (row_change_mask & _BV(i)) refresh_line(i); // After resume() automatically do a refresh() diff --git a/Marlin/src/feature/meatpack.cpp b/Marlin/src/feature/meatpack.cpp index 07ff41e5be22..6db250052d28 100644 --- a/Marlin/src/feature/meatpack.cpp +++ b/Marlin/src/feature/meatpack.cpp @@ -140,7 +140,7 @@ void MeatPack::handle_output_char(const uint8_t c) { #if ENABLED(MP_DEBUG) if (chars_decoded < 1024) { ++chars_decoded; - DEBUG_ECHOLNPGM("RB: ", AS_CHAR(c)); + DEBUG_ECHOLNPGM("RB: ", C(c)); } #endif } diff --git a/Marlin/src/feature/meatpack.h b/Marlin/src/feature/meatpack.h index 98a535e5923f..0de1f792c139 100644 --- a/Marlin/src/feature/meatpack.h +++ b/Marlin/src/feature/meatpack.h @@ -20,7 +20,7 @@ * */ -/* +/** * MeatPack G-code Compression * * Algorithm & Implementation: Scott Mudge - mail@scottmudge.com @@ -144,7 +144,6 @@ struct MeatpackSerial : public SerialBase > { void flushTX() { CALL_IF_EXISTS(void, &out, flushTX); } SerialFeature features(serial_index_t index) const { return SerialFeature::MeatPack | CALL_IF_EXISTS(SerialFeature, &out, features, index); } - int available(serial_index_t index) { if (charCount) return charCount; // The buffer still has data if (out.available(index) <= 0) return 0; // No data to read diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index cf88b806f542..1ce489224813 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -42,7 +42,7 @@ int_fast8_t Mixer::runner = 0; mixer_comp_t Mixer::s_color[MIXING_STEPPERS]; mixer_accu_t Mixer::accu[MIXING_STEPPERS] = { 0 }; -#if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) +#if ANY(HAS_DUAL_MIXING, GRADIENT_MIX) mixer_perc_t Mixer::mix[MIXING_STEPPERS]; #endif @@ -94,13 +94,13 @@ void Mixer::normalize(const uint8_t tool_index) { void Mixer::reset_vtools() { // Virtual Tools 0, 1, 2, 3 = Filament 1, 2, 3, 4, etc. // Every virtual tool gets a pure filament - LOOP_L_N(t, _MIN(MIXING_VIRTUAL_TOOLS, MIXING_STEPPERS)) + for (uint8_t t = 0; t < _MIN(MIXING_VIRTUAL_TOOLS, MIXING_STEPPERS); ++t) MIXER_STEPPER_LOOP(i) color[t][i] = (t == i) ? COLOR_A_MASK : 0; // Remaining virtual tools are 100% filament 1 #if MIXING_VIRTUAL_TOOLS > MIXING_STEPPERS - LOOP_S_L_N(t, MIXING_STEPPERS, MIXING_VIRTUAL_TOOLS) + for (uint8_t t = MIXING_STEPPERS; t < MIXING_VIRTUAL_TOOLS; ++t) MIXER_STEPPER_LOOP(i) color[t][i] = (i == 0) ? COLOR_A_MASK : 0; #endif @@ -138,7 +138,7 @@ void Mixer::init() { color[MIXER_AUTORETRACT_TOOL][i] = COLOR_A_MASK; #endif - #if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) + #if ANY(HAS_DUAL_MIXING, GRADIENT_MIX) update_mix_from_vtool(); #endif diff --git a/Marlin/src/feature/mixing.h b/Marlin/src/feature/mixing.h index 3a14fdad5975..bc3ca794ad04 100644 --- a/Marlin/src/feature/mixing.h +++ b/Marlin/src/feature/mixing.h @@ -108,7 +108,7 @@ class Mixer { } // Used when dealing with blocks - FORCE_INLINE static void populate_block(mixer_comp_t b_color[MIXING_STEPPERS]) { + FORCE_INLINE static void populate_block(mixer_comp_t (&b_color)[MIXING_STEPPERS]) { #if ENABLED(GRADIENT_MIX) if (gradient.enabled) { MIXER_STEPPER_LOOP(i) b_color[i] = gradient.color[i]; @@ -118,11 +118,11 @@ class Mixer { MIXER_STEPPER_LOOP(i) b_color[i] = color[selected_vtool][i]; } - FORCE_INLINE static void stepper_setup(mixer_comp_t b_color[MIXING_STEPPERS]) { + FORCE_INLINE static void stepper_setup(mixer_comp_t (&b_color)[MIXING_STEPPERS]) { MIXER_STEPPER_LOOP(i) s_color[i] = b_color[i]; } - #if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) + #if ANY(HAS_DUAL_MIXING, GRADIENT_MIX) static mixer_perc_t mix[MIXING_STEPPERS]; // Scratch array for the Mix in proportion to 100 @@ -233,13 +233,7 @@ class Mixer { for (;;) { if (--runner < 0) runner = MIXING_STEPPERS - 1; accu[runner] += s_color[runner]; - if ( - #ifdef MIXER_ACCU_SIGNED - accu[runner] < 0 - #else - accu[runner] & COLOR_A_MASK - #endif - ) { + if (TERN(MIXER_ACCU_SIGNED, accu[runner] < 0, accu[runner] & COLOR_A_MASK)) { accu[runner] &= COLOR_MASK; return runner; } diff --git a/Marlin/src/feature/mmu/mmu2-serial-protocol.md b/Marlin/src/feature/mmu/mmu2-serial-protocol.md index 93135e406f36..088d41b44693 100644 --- a/Marlin/src/feature/mmu/mmu2-serial-protocol.md +++ b/Marlin/src/feature/mmu/mmu2-serial-protocol.md @@ -28,11 +28,8 @@ Now we are sure MMU is available and ready. If there was a timeout or other comm - *Build number* is an integer value and has to be >=126, or =>132 if 12V mode is enabled - *FINDA status* is 1 if the filament is loaded to the extruder, 0 otherwise - *Build number* is checked against the required value, if it does not match, printer is halted. - - Toolchange ========== @@ -54,7 +51,6 @@ When done, the MMU sends We don't wait for a response here but immediately continue with the next G-code which should be one or more extruder moves to feed the filament into the hotend. - FINDA status ============ @@ -63,8 +59,6 @@ FINDA status *FINDA status* is 1 if the is filament loaded to the extruder, 0 otherwise. This could be used as filament runout sensor if probed regularly. - - Load filament ============= @@ -74,7 +68,6 @@ MMU will feed filament down to the extruder, when done - MMU => 'ok\n' - Unload filament ============= @@ -84,11 +77,8 @@ MMU will retract current filament from the extruder, when done - MMU => 'ok\n' - - Eject filament ============== - MMU <= 'E*Filament index*\n' - MMU => 'ok\n' - diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index 7747a8b1157c..4e65cd431b73 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -136,12 +136,12 @@ void MMU2::reset() { #endif } -uint8_t MMU2::get_current_tool() { - return extruder == MMU2_NO_TOOL ? -1 : extruder; -} +int8_t MMU2::get_current_tool() { return extruder == MMU2_NO_TOOL ? -1 : extruder; } -#if EITHER(HAS_PRUSA_MMU2S, MMU_EXTRUDER_SENSOR) +#if ANY(HAS_PRUSA_MMU2S, MMU_EXTRUDER_SENSOR) #define FILAMENT_PRESENT() (READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE) +#else + #define FILAMENT_PRESENT() true #endif void mmu2_attn_buzz(const bool two=false) { @@ -149,6 +149,7 @@ void mmu2_attn_buzz(const bool two=false) { if (two) { BUZZ(10, 0); BUZZ(200, 404); } } +// Avoiding sscanf significantly reduces build size void MMU2::mmu_loop() { switch (state) { @@ -190,7 +191,6 @@ void MMU2::mmu_loop() { DEBUG_ECHOLNPGM("MMU <= 'M1'"); MMU2_SEND("M1"); // Stealth Mode state = -5; - #else DEBUG_ECHOLNPGM("MMU <= 'P0'"); MMU2_SEND("P0"); // Read FINDA @@ -200,15 +200,15 @@ void MMU2::mmu_loop() { break; #if ENABLED(MMU2_MODE_12V) - case -5: - // response to M1 - if (rx_ok()) { - DEBUG_ECHOLNPGM("MMU => ok"); - DEBUG_ECHOLNPGM("MMU <= 'P0'"); - MMU2_SEND("P0"); // Read FINDA - state = -4; - } - break; + case -5: + // response to M1 + if (rx_ok()) { + DEBUG_ECHOLNPGM("MMU => ok"); + DEBUG_ECHOLNPGM("MMU <= 'P0'"); + MMU2_SEND("P0"); // Read FINDA + state = -4; + } + break; #endif case -4: @@ -406,7 +406,7 @@ void MMU2::tx_str(FSTR_P fstr) { void MMU2::tx_printf(FSTR_P format, int argument = -1) { clear_rx_buffer(); const uint8_t len = sprintf_P(tx_buffer, FTOP(format), argument); - LOOP_L_N(i, len) MMU2_SERIAL.write(tx_buffer[i]); + for (uint8_t i = 0; i < len; ++i) MMU2_SERIAL.write(tx_buffer[i]); prev_request = millis(); } @@ -416,7 +416,7 @@ void MMU2::tx_printf(FSTR_P format, int argument = -1) { void MMU2::tx_printf(FSTR_P format, int argument1, int argument2) { clear_rx_buffer(); const uint8_t len = sprintf_P(tx_buffer, FTOP(format), argument1, argument2); - LOOP_L_N(i, len) MMU2_SERIAL.write(tx_buffer[i]); + for (uint8_t i = 0; i < len; ++i) MMU2_SERIAL.write(tx_buffer[i]); prev_request = millis(); } @@ -460,10 +460,15 @@ static void mmu2_not_responding() { #if HAS_PRUSA_MMU2S + /** + * Load filament until the sensor at the gears is triggered + * and give up after a number of attempts set with MMU2_C0_RETRY. + * Each try has a timeout before returning a fail state. + */ bool MMU2::load_to_gears() { command(MMU_CMD_C0); manage_response(true, true); - LOOP_L_N(i, MMU2_C0_RETRY) { // Keep loading until filament reaches gears + for (uint8_t i = 0; i < MMU2_C0_RETRY; ++i) { // Keep loading until filament reaches gears if (mmu2s_triggered) break; command(MMU_CMD_C0); manage_response(true, true); @@ -824,13 +829,12 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { } } else if (mmu_print_saved) { - SERIAL_ECHOLNPGM("MMU starts responding\n"); + SERIAL_ECHOLNPGM("\nMMU starts responding"); if (turn_off_nozzle && resume_hotend_temp) { thermalManager.setTargetHotend(resume_hotend_temp, active_extruder); LCD_MESSAGE(MSG_HEATING); ERR_BUZZ(); - while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(1000); } @@ -843,7 +847,6 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { if (move_axes && all_axes_homed()) { // Move XY to starting position, then Z do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); - // Move Z_AXIS to saved position do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); } @@ -893,7 +896,7 @@ void MMU2::filament_runout() { int filament_detected_count = 0; const int steps = (MMU2_CAN_LOAD_RETRACT) / (MMU2_CAN_LOAD_INCREMENT); DEBUG_ECHOLNPGM("MMU can_load:"); - LOOP_L_N(i, steps) { + for (uint8_t i = 0; i < steps; ++i) { execute_extruder_sequence((const E_Step *)can_load_increment_sequence, COUNT(can_load_increment_sequence)); check_filament(); // Don't trust the idle function DEBUG_CHAR(mmu2s_triggered ? 'O' : 'o'); @@ -1038,9 +1041,9 @@ void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) { planner.synchronize(); stepper.enable_extruder(); - const E_Step* step = sequence; + const E_Step *step = sequence; - LOOP_L_N(i, steps) { + for (uint8_t i = 0; i < steps; ++i) { const float es = pgm_read_float(&(step->extrude)); const feedRate_t fr_mm_m = pgm_read_float(&(step->feedRate)); diff --git a/Marlin/src/feature/mmu/mmu2.h b/Marlin/src/feature/mmu/mmu2.h index 18d6d38a359d..515f400b4ce3 100644 --- a/Marlin/src/feature/mmu/mmu2.h +++ b/Marlin/src/feature/mmu/mmu2.h @@ -47,7 +47,7 @@ class MMU2 { static void mmu_loop(); static void tool_change(const uint8_t index); static void tool_change(const char *special); - static uint8_t get_current_tool(); + static int8_t get_current_tool(); static void set_filament_type(const uint8_t index, const uint8_t type); static bool unload(); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 04d206ff931d..36088e4e2abd 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -91,7 +91,7 @@ static xyze_pos_t resume_position; fil_change_settings_t fc_settings[EXTRUDERS]; -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../sd/cardreader.h" #endif @@ -210,7 +210,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load while (wait_for_user) { impatient_beep(max_beep_count); - #if BOTH(FILAMENT_CHANGE_RESUME_ON_INSERT, FILAMENT_RUNOUT_SENSOR) + #if ALL(FILAMENT_CHANGE_RESUME_ON_INSERT, FILAMENT_RUNOUT_SENSOR) #if MULTI_FILAMENT_SENSOR #define _CASE_INSERTED(N) case N-1: if (READ(FIL_RUNOUT##N##_PIN) != FIL_RUNOUT##N##_STATE) wait_for_user = false; break; switch (active_extruder) { @@ -284,7 +284,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load // Show "Purge More" / "Resume" menu and wait for reply KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = false; - #if EITHER(HAS_MARLINUI_MENU, DWIN_LCD_PROUI) + #if ANY(HAS_MARLINUI_MENU, DWIN_LCD_PROUI) ui.pause_show_message(PAUSE_MESSAGE_OPTION); // Also sets PAUSE_RESPONSE_WAIT_FOR #else pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; @@ -326,18 +326,18 @@ inline void disable_active_extruder() { */ bool unload_filament(const_float_t unload_length, const bool show_lcd/*=false*/, const PauseMode mode/*=PAUSE_MODE_PAUSE_PRINT*/ - #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + #if ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) , const_float_t mix_multiplier/*=1.0*/ #endif ) { DEBUG_SECTION(uf, "unload_filament", true); DEBUG_ECHOLNPGM("... unloadlen:", unload_length, " showlcd:", show_lcd, " mode:", mode - #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + #if ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) , " mixmult:", mix_multiplier #endif ); - #if !BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + #if !ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) constexpr float mix_multiplier = 1.0f; #endif @@ -415,7 +415,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool ++did_pause_print; // Pause the print job and timer - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA const bool was_sd_printing = IS_SD_PRINTING(); if (was_sd_printing) { card.pauseSDPrint(); @@ -440,7 +440,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool // Wait for buffered blocks to complete planner.synchronize(); - #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && HAS_FAN + #if ALL(ADVANCED_PAUSE_FANS_PAUSE, HAS_FAN) thermalManager.set_fans_paused(true); #endif @@ -696,7 +696,7 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ // Resume the print job timer if it was running if (print_job_timer.isPaused()) print_job_timer.start(); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (did_pause_print) { --did_pause_print; card.startOrResumeFilePrinting(); diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index 134b1d1b3294..45f62dc31029 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -48,15 +48,15 @@ enum PauseMessage : char { PAUSE_MESSAGE_PARKING, PAUSE_MESSAGE_CHANGING, PAUSE_MESSAGE_WAITING, - PAUSE_MESSAGE_UNLOAD, PAUSE_MESSAGE_INSERT, PAUSE_MESSAGE_LOAD, + PAUSE_MESSAGE_UNLOAD, PAUSE_MESSAGE_PURGE, PAUSE_MESSAGE_OPTION, PAUSE_MESSAGE_RESUME, - PAUSE_MESSAGE_STATUS, PAUSE_MESSAGE_HEAT, - PAUSE_MESSAGE_HEATING + PAUSE_MESSAGE_HEATING, + PAUSE_MESSAGE_STATUS }; #if M600_PURGE_MORE_RESUMABLE @@ -117,7 +117,7 @@ bool unload_filament( const_float_t unload_length, // (mm) Filament Unload Length - 0 to skip const bool show_lcd=false, // Set LCD status messages? const PauseMode mode=PAUSE_MODE_PAUSE_PRINT // Pause Mode to apply - #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + #if ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) , const_float_t mix_multiplier=1.0f // Extrusion multiplier (for a Mixing Extruder) #endif ); diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 8a16628bac45..3774a8cbae5d 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -26,7 +26,7 @@ #include "../inc/MarlinConfigPre.h" -#if EITHER(PSU_CONTROL, AUTO_POWER_CONTROL) +#if ANY(PSU_CONTROL, AUTO_POWER_CONTROL) #include "power.h" #include "../module/planner.h" @@ -49,7 +49,7 @@ bool Power::psu_on; #include "../module/stepper.h" #include "../module/temperature.h" - #if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) + #if ALL(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) #include "controllerfan.h" #endif @@ -78,7 +78,7 @@ void Power::power_on() { if (psu_on) return; - #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) cancelAutoPowerOff(); #endif @@ -98,12 +98,12 @@ void Power::power_on() { * Processes any PSU_POWEROFF_GCODE and makes a PS_OFF_SOUND if enabled. */ void Power::power_off() { - SERIAL_ECHOLNPGM(STR_POWEROFF); - TERN_(HAS_SUICIDE, suicide()); if (!psu_on) return; + SERIAL_ECHOLNPGM(STR_POWEROFF); + #ifdef PSU_POWEROFF_GCODE gcode.process_subcommands_now(F(PSU_POWEROFF_GCODE)); #endif @@ -115,12 +115,12 @@ void Power::power_off() { OUT_WRITE(PS_ON_PIN, !PSU_ACTIVE_STATE); psu_on = false; - #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) cancelAutoPowerOff(); #endif } -#if EITHER(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) +#if ANY(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) bool Power::is_cooling_needed() { #if HAS_HOTEND && AUTO_POWER_E_TEMP @@ -140,7 +140,7 @@ void Power::power_off() { #endif -#if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) +#if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) #if ENABLED(POWER_OFF_TIMER) millis_t Power::power_off_time = 0; @@ -192,7 +192,7 @@ void Power::power_off() { HOTEND_LOOP() if (thermalManager.autofan_speed[e]) return true; #endif - #if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) + #if ALL(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) if (controllerFan.state()) return true; #endif diff --git a/Marlin/src/feature/power.h b/Marlin/src/feature/power.h index 839366ca602b..fdbb7126ceae 100644 --- a/Marlin/src/feature/power.h +++ b/Marlin/src/feature/power.h @@ -25,7 +25,7 @@ * power.h - power control */ -#if EITHER(AUTO_POWER_CONTROL, POWER_OFF_TIMER) +#if ANY(AUTO_POWER_CONTROL, POWER_OFF_TIMER) #include "../core/millis_t.h" #endif @@ -37,7 +37,7 @@ class Power { static void power_on(); static void power_off(); - #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) #if ENABLED(POWER_OFF_TIMER) static millis_t power_off_time; static void setPowerOffTimer(const millis_t delay_ms); diff --git a/Marlin/src/feature/power_monitor.h b/Marlin/src/feature/power_monitor.h index fa0690905333..d57ef6fa67e1 100644 --- a/Marlin/src/feature/power_monitor.h +++ b/Marlin/src/feature/power_monitor.h @@ -46,11 +46,11 @@ struct pm_lpf_t { class PowerMonitor { private: #if ENABLED(POWER_MONITOR_CURRENT) - static constexpr float amps_adc_scale = float(ADC_VREF) / (POWER_MONITOR_VOLTS_PER_AMP * PM_SAMPLE_RANGE); + static constexpr float amps_adc_scale = (float(ADC_VREF_MV) / 1000.0f) / (POWER_MONITOR_VOLTS_PER_AMP * PM_SAMPLE_RANGE); static pm_lpf_t amps; #endif #if ENABLED(POWER_MONITOR_VOLTAGE) - static constexpr float volts_adc_scale = float(ADC_VREF) / (POWER_MONITOR_VOLTS_PER_VOLT * PM_SAMPLE_RANGE); + static constexpr float volts_adc_scale = (float(ADC_VREF_MV) / 1000.0f) / (POWER_MONITOR_VOLTS_PER_VOLT * PM_SAMPLE_RANGE); static pm_lpf_t volts; #endif @@ -119,7 +119,7 @@ class PowerMonitor { volts.reset(); #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA display_item_ms = 0; display_item = 0; #endif diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 1037f823f644..86e6b780bddc 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -67,16 +67,15 @@ uint32_t PrintJobRecovery::cmd_sdpos, // = 0 PrintJobRecovery recovery; -#ifndef POWER_LOSS_PURGE_LEN - #define POWER_LOSS_PURGE_LEN 0 -#endif - #if DISABLED(BACKUP_POWER_SUPPLY) #undef POWER_LOSS_RETRACT_LEN // No retract at outage without backup power #endif #ifndef POWER_LOSS_RETRACT_LEN #define POWER_LOSS_RETRACT_LEN 0 #endif +#ifndef POWER_LOSS_PURGE_LEN + #define POWER_LOSS_PURGE_LEN 0 +#endif // Allow power-loss recovery to be aborted #define PLR_CAN_ABORT @@ -109,6 +108,7 @@ void PrintJobRecovery::changed() { purge(); else if (IS_SD_PRINTING()) save(true); + TERN_(EXTENSIBLE_UI, ExtUI::onSetPowerLoss(enabled)); } /** @@ -215,15 +215,13 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW #endif #endif - #if HAS_EXTRUDERS + #if HAS_HOTEND HOTEND_LOOP() info.target_temperature[e] = thermalManager.degTargetHotend(e); #endif TERN_(HAS_HEATED_BED, info.target_temperature_bed = thermalManager.degTargetBed()); - #if HAS_FAN - COPY(info.fan_speed, thermalManager.fan_speed); - #endif + TERN_(HAS_FAN, COPY(info.fan_speed, thermalManager.fan_speed)); #if HAS_LEVELING info.flag.leveling = planner.leveling_active; @@ -313,6 +311,9 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW // and a flag whether the raise was already done here. if (IS_SD_PRINTING()) save(true, zraise, ENABLED(BACKUP_POWER_SUPPLY)); + // Tell the LCD about the outage, even though it is about to die + TERN_(EXTENSIBLE_UI, ExtUI::onPowerLoss()); + // Disable all heaters to reduce power loss thermalManager.disable_all_heaters(); @@ -622,7 +623,7 @@ void PrintJobRecovery::resume() { #if ENABLED(GCODE_REPEAT_MARKERS) DEBUG_ECHOLNPGM("repeat index: ", info.stored_repeat.index); - LOOP_L_N(i, info.stored_repeat.index) + for (uint8_t i = 0; i < info.stored_repeat.index; ++i) DEBUG_ECHOLNPGM("..... sdpos: ", info.stored_repeat.marker.sdpos, " count: ", info.stored_repeat.marker.counter); #endif @@ -691,7 +692,7 @@ void PrintJobRecovery::resume() { #endif // Mixing extruder and gradient - #if BOTH(MIXING_EXTRUDER, GRADIENT_MIX) + #if ALL(MIXING_EXTRUDER, GRADIENT_MIX) DEBUG_ECHOLNPGM("gradient: ", info.gradient.enabled ? "ON" : "OFF"); #endif @@ -710,7 +711,9 @@ void PrintJobRecovery::resume() { DEBUG_ECHOLNPGM("flag.dryrun: ", AS_DIGIT(info.flag.dryrun)); DEBUG_ECHOLNPGM("flag.allow_cold_extrusion: ", AS_DIGIT(info.flag.allow_cold_extrusion)); - DEBUG_ECHOLNPGM("flag.volumetric_enabled: ", AS_DIGIT(info.flag.volumetric_enabled)); + #if DISABLED(NO_VOLUMETRICS) + DEBUG_ECHOLNPGM("flag.volumetric_enabled: ", AS_DIGIT(info.flag.volumetric_enabled)); + #endif } else DEBUG_ECHOLNPGM("INVALID DATA"); diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index d241fdb74c8e..09ceab5c7ee4 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -43,7 +43,7 @@ #endif #ifndef POWER_LOSS_ZRAISE - #define POWER_LOSS_ZRAISE 2 + #define POWER_LOSS_ZRAISE 2 // Default Z-raise on outage or resume #endif //#define DEBUG_POWER_LOSS_RECOVERY @@ -113,7 +113,7 @@ typedef struct { millis_t print_job_elapsed; // Relative axis modes - uint8_t axis_relative; + relative_t axis_relative; // Misc. Marlin flags struct { diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index b5f636e698c9..2b362a2186b6 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -66,13 +66,13 @@ float ProbeTempComp::init_measurement; // = 0.0 bool ProbeTempComp::enabled = true; void ProbeTempComp::reset() { - TERN_(PTC_PROBE, LOOP_L_N(i, PTC_PROBE_COUNT) z_offsets_probe[i] = z_offsets_probe_default[i]); - TERN_(PTC_BED, LOOP_L_N(i, PTC_BED_COUNT) z_offsets_bed[i] = z_offsets_bed_default[i]); - TERN_(PTC_HOTEND, LOOP_L_N(i, PTC_HOTEND_COUNT) z_offsets_hotend[i] = z_offsets_hotend_default[i]); + TERN_(PTC_PROBE, for (uint8_t i = 0; i < PTC_PROBE_COUNT; ++i) z_offsets_probe[i] = z_offsets_probe_default[i]); + TERN_(PTC_BED, for (uint8_t i = 0; i < PTC_BED_COUNT; ++i) z_offsets_bed[i] = z_offsets_bed_default[i]); + TERN_(PTC_HOTEND, for (uint8_t i = 0; i < PTC_HOTEND_COUNT; ++i) z_offsets_hotend[i] = z_offsets_hotend_default[i]); } void ProbeTempComp::clear_offsets(const TempSensorID tsi) { - LOOP_L_N(i, cali_info[tsi].measurements) + for (uint8_t i = 0; i < cali_info[tsi].measurements; ++i) sensor_z_offsets[tsi][i] = 0; calib_idx = 0; } @@ -84,7 +84,7 @@ bool ProbeTempComp::set_offset(const TempSensorID tsi, const uint8_t idx, const } void ProbeTempComp::print_offsets() { - LOOP_L_N(s, TSI_COUNT) { + for (uint8_t s = 0; s < TSI_COUNT; ++s) { celsius_t temp = cali_info[s].start_temp; for (int16_t i = -1; i < cali_info[s].measurements; ++i) { SERIAL_ECHOF( @@ -232,7 +232,7 @@ bool ProbeTempComp::linear_regression(const TempSensorID tsi, float &k, float &d sum_xy = 0, sum_y = 0; float xi = static_cast(start_temp); - LOOP_L_N(i, calib_idx) { + for (uint8_t i = 0; i < calib_idx; ++i) { const float yi = static_cast(data[i]); xi += res_temp; sum_x += xi; diff --git a/Marlin/src/feature/repeat.cpp b/Marlin/src/feature/repeat.cpp index fed7ac0908a0..4484dab95b39 100644 --- a/Marlin/src/feature/repeat.cpp +++ b/Marlin/src/feature/repeat.cpp @@ -66,7 +66,7 @@ void Repeat::loop() { } } -void Repeat::cancel() { LOOP_L_N(i, index) marker[i].counter = 0; } +void Repeat::cancel() { for (uint8_t i = 0; i < index; ++i) marker[i].counter = 0; } void Repeat::early_parse_M808(char * const cmd) { if (is_command_M808(cmd)) { diff --git a/Marlin/src/feature/repeat.h b/Marlin/src/feature/repeat.h index fc11e4a9e2cf..ce309f6470c1 100644 --- a/Marlin/src/feature/repeat.h +++ b/Marlin/src/feature/repeat.h @@ -40,7 +40,7 @@ class Repeat { public: static void reset() { index = 0; } static bool is_active() { - LOOP_L_N(i, index) if (marker[i].counter) return true; + for (uint8_t i = 0; i < index; ++i) if (marker[i].counter) return true; return false; } static bool is_command_M808(char * const cmd) { return cmd[0] == 'M' && cmd[1] == '8' && cmd[2] == '0' && cmd[3] == '8' && !NUMERIC(cmd[4]); } @@ -48,6 +48,9 @@ class Repeat { static void add_marker(const uint32_t sdpos, const uint16_t count); static void loop(); static void cancel(); + static uint8_t count() { return index; } + static int16_t get_marker_counter(const uint8_t i) { return marker[i].counter; } + static uint32_t get_marker_sdpos(const uint8_t i) { return marker[i].sdpos; } }; extern Repeat repeat; diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index e74d857a79ed..252f11a45915 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -144,7 +144,7 @@ class TFilamentMonitor : public FilamentMonitorBase { #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) if (runout_flags) { SERIAL_ECHOPGM("Runout Sensors: "); - LOOP_L_N(i, 8) SERIAL_ECHO('0' + TEST(runout_flags, i)); + for (uint8_t i = 0; i < 8; ++i) SERIAL_CHAR('0' + TEST(runout_flags, i)); SERIAL_ECHOPGM(" -> ", extruder); if (ran_out) SERIAL_ECHOPGM(" RUN OUT"); SERIAL_EOL(); @@ -263,7 +263,7 @@ class FilamentSensorBase { #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) if (change) { SERIAL_ECHOPGM("Motion detected:"); - LOOP_L_N(e, NUM_RUNOUT_SENSORS) + for (uint8_t e = 0; e < NUM_RUNOUT_SENSORS; ++e) if (TEST(change, e)) SERIAL_CHAR(' ', '0' + e); SERIAL_EOL(); } @@ -310,7 +310,7 @@ class FilamentSensorBase { static void block_completed(const block_t * const) {} static void run() { - LOOP_L_N(s, NUM_RUNOUT_SENSORS) { + for (uint8_t s = 0; s < NUM_RUNOUT_SENSORS; ++s) { const bool out = poll_runout_state(s); if (!out) filament_present(s); #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) @@ -324,7 +324,6 @@ class FilamentSensorBase { } }; - #endif // !FILAMENT_MOTION_SENSOR /********************************* RESPONSE TYPE *********************************/ @@ -342,7 +341,7 @@ class FilamentSensorBase { static float runout_distance_mm; static void reset() { - LOOP_L_N(i, NUM_RUNOUT_SENSORS) filament_present(i); + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) filament_present(i); } static void run() { @@ -351,7 +350,7 @@ class FilamentSensorBase { const millis_t ms = millis(); if (ELAPSED(ms, t)) { t = millis() + 1000UL; - LOOP_L_N(i, NUM_RUNOUT_SENSORS) + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) SERIAL_ECHOF(i ? F(", ") : F("Remaining mm: "), runout_mm_countdown[i]); SERIAL_EOL(); } @@ -360,7 +359,7 @@ class FilamentSensorBase { 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); + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) if (runout_mm_countdown[i] < 0) SBI(runout_flags, i); return runout_flags; } @@ -390,16 +389,16 @@ class FilamentSensorBase { public: static void reset() { - LOOP_L_N(i, NUM_RUNOUT_SENSORS) filament_present(i); + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) filament_present(i); } static void run() { - LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (runout_count[i] >= 0) runout_count[i]--; + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) if (runout_count[i] >= 0) runout_count[i]--; } static uint8_t has_run_out() { uint8_t runout_flags = 0; - LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (runout_count[i] < 0) SBI(runout_flags, i); + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) if (runout_count[i] < 0) SBI(runout_flags, i); return runout_flags; } diff --git a/Marlin/src/feature/solenoid.cpp b/Marlin/src/feature/solenoid.cpp index 861e44ed05de..cc4522e30a62 100644 --- a/Marlin/src/feature/solenoid.cpp +++ b/Marlin/src/feature/solenoid.cpp @@ -22,12 +22,12 @@ #include "../inc/MarlinConfig.h" -#if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) +#if ANY(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) #include "solenoid.h" #include "../module/motion.h" // for active_extruder -#include "../module/tool_change.h" +#include "../module/tool_change.h" // for parking_extruder_set_parked // Used primarily with MANUAL_SOLENOID_CONTROL static void set_solenoid(const uint8_t num, const uint8_t state) { diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 8908ae6df524..681df2f081e7 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -38,7 +38,6 @@ #define PCT_TO_PWM(X) ((X) * 255 / 100) #define PCT_TO_SERVO(X) ((X) * 180 / 100) - // Laser/Cutter operation mode enum CutterMode : int8_t { CUTTER_MODE_ERROR = -1, diff --git a/Marlin/src/feature/spindle_laser_types.h b/Marlin/src/feature/spindle_laser_types.h index 2f36a68a1a32..4e5e4d06f67d 100644 --- a/Marlin/src/feature/spindle_laser_types.h +++ b/Marlin/src/feature/spindle_laser_types.h @@ -57,7 +57,7 @@ #endif #endif -typedef IF<(SPEED_POWER_MAX > 255), uint16_t, uint8_t>::type cutter_cpower_t; +typedef uvalue_t(SPEED_POWER_MAX) cutter_cpower_t; #if CUTTER_UNIT_IS(RPM) && SPEED_POWER_MAX > 255 typedef uint16_t cutter_power_t; diff --git a/Marlin/src/feature/stepper_driver_safety.h b/Marlin/src/feature/stepper_driver_safety.h index 46edf3390d77..ac3d8b64f9f4 100644 --- a/Marlin/src/feature/stepper_driver_safety.h +++ b/Marlin/src/feature/stepper_driver_safety.h @@ -21,7 +21,6 @@ */ #pragma once - #include "../inc/MarlinConfigPre.h" void stepper_driver_backward_check(); diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 2e5a5c55850b..095e14fe1558 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -773,8 +773,8 @@ } } - static void tmc_debug_loop(const TMC_debug_enum n, LOGICAL_AXIS_ARGS(const bool)) { - if (x) { + static void tmc_debug_loop(const TMC_debug_enum n OPTARGS_LOGICAL(const bool)) { + if (TERN0(HAS_X_AXIS, x)) { #if AXIS_IS_TMC(X) tmc_status(stepperX, n); #endif @@ -856,8 +856,8 @@ SERIAL_EOL(); } - static void drv_status_loop(const TMC_drv_status_enum n, LOGICAL_AXIS_ARGS(const bool)) { - if (x) { + static void drv_status_loop(const TMC_drv_status_enum n OPTARGS_LOGICAL(const bool)) { + if (TERN0(HAS_X_AXIS, x)) { #if AXIS_IS_TMC(X) tmc_parse_drv_status(stepperX, n); #endif @@ -944,8 +944,8 @@ */ void tmc_report_all(LOGICAL_AXIS_ARGS(const bool)) { - #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, LOGICAL_AXIS_ARGS()); }while(0) - #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, LOGICAL_AXIS_ARGS()); }while(0) + #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM OPTARGS_LOGICAL()); }while(0) + #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM OPTARGS_LOGICAL()); }while(0) TMC_REPORT("\t", TMC_CODES); #if HAS_DRIVER(TMC2209) @@ -1070,8 +1070,8 @@ } #endif - static void tmc_get_registers(TMC_get_registers_enum n, LOGICAL_AXIS_ARGS(const bool)) { - if (x) { + static void tmc_get_registers(TMC_get_registers_enum n OPTARGS_LOGICAL(const bool)) { + if (TERN0(HAS_X_AXIS, x)) { #if AXIS_IS_TMC(X) tmc_get_registers(stepperX, n); #endif @@ -1154,7 +1154,7 @@ } void tmc_get_registers(LOGICAL_AXIS_ARGS(bool)) { - #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, LOGICAL_AXIS_ARGS()); }while(0) + #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM OPTARGS_LOGICAL()); }while(0) #define TMC_GET_REG(NAME, TABS) _TMC_GET_REG(STRINGIFY(NAME) TABS, TMC_GET_##NAME) _TMC_GET_REG("\t", TMC_AXIS_CODES); TMC_GET_REG(GCONF, "\t\t"); @@ -1236,7 +1236,7 @@ static bool test_connection(TMC &st) { void test_tmc_connection(LOGICAL_AXIS_ARGS(const bool)) { uint8_t axis_connection = 0; - if (x) { + if (TERN0(HAS_X_AXIS, x)) { #if AXIS_IS_TMC(X) axis_connection += test_connection(stepperX); #endif diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index c10bab62749d..4ba38359069a 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -348,7 +348,7 @@ void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); #if USE_SENSORLESS // Track enabled status of stealthChop and only re-enable where applicable - struct sensorless_t { bool NUM_AXIS_ARGS(), x2, y2, z2, z3, z4; }; + struct sensorless_t { bool NUM_AXIS_ARGS_() x2, y2, z2, z3, z4; }; #if ENABLED(IMPROVE_HOMING_RELIABILITY) extern millis_t sg_guard_period; @@ -378,6 +378,7 @@ void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); return drv_status.stallGuard; } + #endif // SPI_ENDSTOPS #endif // USE_SENSORLESS diff --git a/Marlin/src/feature/tramming.cpp b/Marlin/src/feature/tramming.cpp index d03f0cf53bd7..3721c5eb811a 100644 --- a/Marlin/src/feature/tramming.cpp +++ b/Marlin/src/feature/tramming.cpp @@ -29,31 +29,11 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" -PGMSTR(point_name_1, TRAMMING_POINT_NAME_1); -PGMSTR(point_name_2, TRAMMING_POINT_NAME_2); -PGMSTR(point_name_3, TRAMMING_POINT_NAME_3); -#ifdef TRAMMING_POINT_NAME_4 - PGMSTR(point_name_4, TRAMMING_POINT_NAME_4); - #ifdef TRAMMING_POINT_NAME_5 - PGMSTR(point_name_5, TRAMMING_POINT_NAME_5); - #ifdef TRAMMING_POINT_NAME_6 - PGMSTR(point_name_6, TRAMMING_POINT_NAME_6); - #endif - #endif -#endif +#define _TRAM_NAME_DEF(N) PGMSTR(point_name_##N, TRAMMING_POINT_NAME_##N); +#define _TRAM_NAME_ITEM(N) point_name_##N +REPEAT_1(_NR_TRAM_NAMES, _TRAM_NAME_DEF) -PGM_P const tramming_point_name[] PROGMEM = { - point_name_1, point_name_2, point_name_3 - #ifdef TRAMMING_POINT_NAME_4 - , point_name_4 - #ifdef TRAMMING_POINT_NAME_5 - , point_name_5 - #ifdef TRAMMING_POINT_NAME_6 - , point_name_6 - #endif - #endif - #endif -}; +PGM_P const tramming_point_name[] PROGMEM = { REPLIST_1(_NR_TRAM_NAMES, _TRAM_NAME_ITEM) }; #ifdef ASSISTED_TRAMMING_WAIT_POSITION diff --git a/Marlin/src/feature/tramming.h b/Marlin/src/feature/tramming.h index 925659e29db2..c8f20f001081 100644 --- a/Marlin/src/feature/tramming.h +++ b/Marlin/src/feature/tramming.h @@ -31,43 +31,34 @@ constexpr xy_pos_t tramming_points[] = TRAMMING_POINT_XY; #define G35_PROBE_COUNT COUNT(tramming_points) -static_assert(WITHIN(G35_PROBE_COUNT, 3, 6), "TRAMMING_POINT_XY requires between 3 and 6 XY positions."); +static_assert(WITHIN(G35_PROBE_COUNT, 3, 9), "TRAMMING_POINT_XY requires between 3 and 9 XY positions."); -#define VALIDATE_TRAMMING_POINT(N) static_assert(N >= G35_PROBE_COUNT || Probe::build_time::can_reach(tramming_points[N]), \ - "TRAMMING_POINT_XY point " STRINGIFY(N) " is not reachable with the default NOZZLE_TO_PROBE offset and PROBING_MARGIN.") -VALIDATE_TRAMMING_POINT(0); VALIDATE_TRAMMING_POINT(1); VALIDATE_TRAMMING_POINT(2); VALIDATE_TRAMMING_POINT(3); VALIDATE_TRAMMING_POINT(4); VALIDATE_TRAMMING_POINT(5); - -extern const char point_name_1[], point_name_2[], point_name_3[] - #ifdef TRAMMING_POINT_NAME_4 - , point_name_4[] - #ifdef TRAMMING_POINT_NAME_5 - , point_name_5[] - #ifdef TRAMMING_POINT_NAME_6 - , point_name_6[] - #endif - #endif - #endif -; - -#define _NR_TRAM_NAMES 2 -#ifdef TRAMMING_POINT_NAME_3 - #undef _NR_TRAM_NAMES +#ifdef TRAMMING_POINT_NAME_9 + #define _NR_TRAM_NAMES 9 +#elif defined(TRAMMING_POINT_NAME_8) + #define _NR_TRAM_NAMES 8 +#elif defined(TRAMMING_POINT_NAME_7) + #define _NR_TRAM_NAMES 7 +#elif defined(TRAMMING_POINT_NAME_6) + #define _NR_TRAM_NAMES 6 +#elif defined(TRAMMING_POINT_NAME_5) + #define _NR_TRAM_NAMES 5 +#elif defined(TRAMMING_POINT_NAME_4) + #define _NR_TRAM_NAMES 4 +#elif defined(TRAMMING_POINT_NAME_3) #define _NR_TRAM_NAMES 3 - #ifdef TRAMMING_POINT_NAME_4 - #undef _NR_TRAM_NAMES - #define _NR_TRAM_NAMES 4 - #ifdef TRAMMING_POINT_NAME_5 - #undef _NR_TRAM_NAMES - #define _NR_TRAM_NAMES 5 - #ifdef TRAMMING_POINT_NAME_6 - #undef _NR_TRAM_NAMES - #define _NR_TRAM_NAMES 6 - #endif - #endif - #endif +#else + #define _NR_TRAM_NAMES 0 #endif + static_assert(_NR_TRAM_NAMES >= G35_PROBE_COUNT, "Define enough TRAMMING_POINT_NAME_s for all TRAMMING_POINT_XY entries."); -#undef _NR_TRAM_NAMES + +#define _TRAM_NAME_PTR(N) point_name_##N[] +extern const char REPLIST_1(_NR_TRAM_NAMES, _TRAM_NAME_PTR); + +#define _CHECK_TRAM_POINT(N) static_assert(Probe::build_time::can_reach(tramming_points[N]), "TRAMMING_POINT_XY point " STRINGIFY(N) " is not reachable with the default NOZZLE_TO_PROBE offset and PROBING_MARGIN."); +REPEAT(_NR_TRAM_NAMES, _CHECK_TRAM_POINT) +#undef _CHECK_TRAM_POINT extern PGM_P const tramming_point_name[]; diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index 9aec6b030537..4aedb4b5f3c5 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -145,7 +145,7 @@ void TWIBus::echodata(uint8_t bytes, FSTR_P const pref, uint8_t adr, const uint8 void TWIBus::echobuffer(FSTR_P const prefix, uint8_t adr) { echoprefix(buffer_s, prefix, adr); - LOOP_L_N(i, buffer_s) SERIAL_CHAR(buffer[i]); + for (uint8_t i = 0; i < buffer_s; ++i) SERIAL_CHAR(buffer[i]); SERIAL_EOL(); } diff --git a/Marlin/src/feature/twibus.h b/Marlin/src/feature/twibus.h index 806e2a147a7d..de23abbed53c 100644 --- a/Marlin/src/feature/twibus.h +++ b/Marlin/src/feature/twibus.h @@ -74,7 +74,6 @@ class TWIBus { */ uint8_t buffer[TWIBUS_BUFFER_SIZE]; - public: /** * @brief Target device address diff --git a/Marlin/src/feature/x_twist.cpp b/Marlin/src/feature/x_twist.cpp index b5ad25cba87d..b8f7e52ab6d5 100644 --- a/Marlin/src/feature/x_twist.cpp +++ b/Marlin/src/feature/x_twist.cpp @@ -43,12 +43,12 @@ void XATC::reset() { void XATC::print_points() { SERIAL_ECHOLNPGM(" X-Twist Correction:"); - LOOP_L_N(x, XATC_MAX_POINTS) { + for (uint8_t x = 0; x < XATC_MAX_POINTS; ++x) { SERIAL_CHAR(' '); if (!isnan(z_offset[x])) serial_offset(z_offset[x]); else - LOOP_L_N(i, 6) SERIAL_CHAR(i ? '=' : ' '); + for (uint8_t i = 0; i < 6; ++i) SERIAL_CHAR(i ? '=' : ' '); } SERIAL_EOL(); } diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index fe20423b8d8b..30643cb84e9b 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -628,7 +628,7 @@ void GcodeSuite::G26() { } // Get repeat from 'R', otherwise do one full circuit - int16_t g26_repeats; + grid_count_t g26_repeats; #if HAS_MARLINUI_MENU g26_repeats = parser.intval('R', GRID_MAX_POINTS + 1); #else @@ -707,7 +707,7 @@ void GcodeSuite::G26() { #error "A_CNT must be a positive value. Please change A_INT." #endif float trig_table[A_CNT]; - LOOP_L_N(i, A_CNT) + for (uint8_t i = 0; i < A_CNT; ++i) trig_table[i] = INTERSECTION_CIRCLE_RADIUS * cos(RADIANS(i * A_INT)); #endif // !ARC_SUPPORT diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index dd828bf0c873..aa4ded00078b 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -57,8 +57,9 @@ * 41 - Counter-Clockwise M4 * 50 - Clockwise M5 * 51 - Counter-Clockwise M5 - **/ + */ void GcodeSuite::G35() { + DEBUG_SECTION(log_G35, "G35", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) log_machine_info(); @@ -82,9 +83,7 @@ void GcodeSuite::G35() { set_bed_leveling_enabled(false); #endif - #if ENABLED(CNC_WORKSPACE_PLANES) - workspace_plane = PLANE_XY; - #endif + TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); // Always home with tool 0 active #if HAS_MULTI_HOTEND @@ -101,7 +100,7 @@ void GcodeSuite::G35() { bool err_break = false; // Probe all positions - LOOP_L_N(i, G35_PROBE_COUNT) { + for (uint8_t i = 0; i < G35_PROBE_COUNT; ++i) { // 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 @@ -134,7 +133,7 @@ void GcodeSuite::G35() { const float threads_factor[] = { 0.5, 0.7, 0.8 }; // Calculate adjusts - LOOP_S_L_N(i, 1, G35_PROBE_COUNT) { + for (uint8_t i = 1; i < G35_PROBE_COUNT; ++i) { const float diff = z_measured[0] - z_measured[i], adjust = ABS(diff) < 0.001f ? 0 : diff / threads_factor[(screw_thread - 30) / 10]; @@ -158,7 +157,7 @@ void GcodeSuite::G35() { if (old_tool_index != 0) tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER)); // Fetch previous toolhead if not PARKING_EXTRUDER #endif - #if BOTH(HAS_LEVELING, RESTORE_LEVELING_AFTER_G35) + #if ALL(HAS_LEVELING, RESTORE_LEVELING_AFTER_G35) set_bed_leveling_enabled(leveling_was_active); #endif diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 79f92f7482a2..2d0ef57b26ee 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -101,16 +101,16 @@ class G29_State { uint8_t tool_index; #endif - #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) + #if ANY(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) int abl_probe_index; #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) - int abl_points; + grid_count_t abl_points; #elif ENABLED(AUTO_BED_LEVELING_3POINT) - static constexpr int abl_points = 3; + static constexpr grid_count_t abl_points = 3; #elif ABL_USES_GRID - static constexpr int abl_points = GRID_MAX_POINTS; + static constexpr grid_count_t abl_points = GRID_MAX_POINTS; #endif #if ABL_USES_GRID @@ -136,16 +136,16 @@ class G29_State { #if ENABLED(AUTO_BED_LEVELING_LINEAR) int indexIntoAB[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; - float eqnAMatrix[(GRID_MAX_POINTS) * 3], // "A" matrix of the linear system of equations - eqnBVector[GRID_MAX_POINTS], // "B" vector of Z points + float eqnAMatrix[GRID_MAX_POINTS * 3], // "A" matrix of the linear system of equations + eqnBVector[GRID_MAX_POINTS], // "B" vector of Z points mean; #endif #endif }; -#if ABL_USES_GRID && EITHER(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR) +#if ABL_USES_GRID && ANY(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR) constexpr xy_uint8_t G29_State::grid_points; - constexpr int G29_State::abl_points; + constexpr grid_count_t G29_State::abl_points; #endif /** @@ -226,6 +226,7 @@ class G29_State { * There's no extra effect if you have a fixed Z probe. */ G29_TYPE GcodeSuite::G29() { + DEBUG_SECTION(log_G29, "G29", DEBUGGING(LEVELING)); // Leveling state is persistent when done manually with multiple G29 commands @@ -235,7 +236,7 @@ G29_TYPE GcodeSuite::G29() { reset_stepper_timeout(); // Q = Query leveling and G29 state - const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen_test('Q'); + const bool seenQ = ANY(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen_test('Q'); // G29 Q is also available if debugging #if ENABLED(DEBUG_LEVELING_FEATURE) @@ -286,7 +287,7 @@ G29_TYPE GcodeSuite::G29() { if (active_extruder != 0) tool_change(0, true); #endif - #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) + #if ANY(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) abl.abl_probe_index = -1; #endif @@ -443,7 +444,7 @@ G29_TYPE GcodeSuite::G29() { #if ENABLED(PREHEAT_BEFORE_LEVELING) if (!abl.dryrun) probe.preheat_for_probing(LEVELING_NOZZLE_TEMP, - #if BOTH(DWIN_LCD_PROUI, HAS_HEATED_BED) + #if ALL(DWIN_LCD_PROUI, HAS_HEATED_BED) HMI_data.BedLevT #else LEVELING_BED_TEMP @@ -501,20 +502,13 @@ G29_TYPE GcodeSuite::G29() { #endif #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (!abl.dryrun - && (abl.gridSpacing != bedlevel.grid_spacing || abl.probe_position_lf != bedlevel.grid_start) - ) { - // Reset grid to 0.0 or "not probed". (Also disables ABL) - reset_bed_level(); - - // Can't re-enable (on error) until the new grid is written - abl.reenable = false; + if (!abl.dryrun && (abl.gridSpacing != bedlevel.grid_spacing || abl.probe_position_lf != bedlevel.grid_start)) { + reset_bed_level(); // Reset grid to 0.0 or "not probed". (Also disables ABL) + abl.reenable = false; // Can't re-enable (on error) until the new grid is written } - // Pre-populate local Z values from the stored mesh TERN_(IS_KINEMATIC, COPY(abl.z_values, bedlevel.z_values)); - - #endif // AUTO_BED_LEVELING_BILINEAR + #endif } // !g29_in_progress @@ -556,7 +550,7 @@ G29_TYPE GcodeSuite::G29() { } else { - #if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) + #if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) const uint16_t index = abl.abl_probe_index - 1; #endif @@ -691,7 +685,7 @@ G29_TYPE GcodeSuite::G29() { zig ^= true; // zag // An index to print current state - uint8_t pt_index = (PR_OUTER_VAR) * (PR_INNER_SIZE) + 1; + grid_count_t pt_index = (PR_OUTER_VAR) * (PR_INNER_SIZE) + 1; // Inner loop is Y with PROBE_Y_FIRST enabled // Inner loop is X with PROBE_Y_FIRST disabled @@ -742,7 +736,7 @@ G29_TYPE GcodeSuite::G29() { // Probe at 3 arbitrary points - LOOP_L_N(i, 3) { + for (uint8_t i = 0; i < 3; ++i) { if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing point ", i + 1, "/3."); TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_POINT), int(i + 1))); @@ -853,7 +847,7 @@ G29_TYPE GcodeSuite::G29() { auto print_topo_map = [&](FSTR_P const title, const bool get_min) { SERIAL_ECHOF(title); for (int8_t yy = abl.grid_points.y - 1; yy >= 0; yy--) { - LOOP_L_N(xx, abl.grid_points.x) { + for (uint8_t xx = 0; xx < abl.grid_points.x; ++xx) { const int ind = abl.indexIntoAB[xx][yy]; xyz_float_t tmp = { abl.eqnAMatrix[ind + 0 * abl.abl_points], abl.eqnAMatrix[ind + 1 * abl.abl_points], 0 }; diff --git a/Marlin/src/gcode/bedlevel/abl/M421.cpp b/Marlin/src/gcode/bedlevel/abl/M421.cpp index 3272ea1bd227..f66d0231901e 100644 --- a/Marlin/src/gcode/bedlevel/abl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/abl/M421.cpp @@ -56,8 +56,8 @@ void GcodeSuite::M421() { const float zval = parser.value_linear_units(); uint8_t sx = ix >= 0 ? ix : 0, ex = ix >= 0 ? ix : GRID_MAX_POINTS_X - 1, sy = iy >= 0 ? iy : 0, ey = iy >= 0 ? iy : GRID_MAX_POINTS_Y - 1; - LOOP_S_LE_N(x, sx, ex) { - LOOP_S_LE_N(y, sy, ey) { + for (uint8_t x = sx; x <= ex; ++x) { + for (uint8_t y = sy; y <= ey; ++y) { bedlevel.z_values[x][y] = zval + (hasQ ? bedlevel.z_values[x][y] : 0); TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, bedlevel.z_values[x][y])); } diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index e3e96a7960c2..f30f8c8b9c65 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -64,6 +64,7 @@ inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM(" * S5 Reset and disable mesh */ void GcodeSuite::G29() { + DEBUG_SECTION(log_G29, "G29", true); // G29 Q is also available if debugging @@ -103,9 +104,8 @@ void GcodeSuite::G29() { bedlevel.reset(); mbl_probe_index = 0; if (!ui.wait_for_move) { - queue.inject(parser.seen_test('N') ? F("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : F("G29S2")); - TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart()); - TERN_(DWIN_LCD_PROUI, DWIN_LevelingStart()); + if (parser.seen_test('N')) + queue.inject(F("G28" TERN_(CAN_SET_LEVELING_AFTER_G28, "L0"))); // Position bed horizontally and Z probe vertically. #if HAS_SAFE_BED_LEVELING @@ -141,6 +141,11 @@ void GcodeSuite::G29() { do_blocking_move_to(safe_position); #endif // HAS_SAFE_BED_LEVELING + queue.inject(F("G29S2")); + + TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart()); + TERN_(DWIN_LCD_PROUI, DWIN_LevelingStart()); + return; } state = MeshNext; @@ -169,7 +174,7 @@ void GcodeSuite::G29() { SET_SOFT_ENDSTOP_LOOSE(false); } // If there's another point to sample, move there with optional lift. - if (mbl_probe_index < (GRID_MAX_POINTS)) { + if (mbl_probe_index < GRID_MAX_POINTS) { // Disable software endstops to allow manual adjustment // If G29 is left hanging without completion they won't be re-enabled! SET_SOFT_ENDSTOP_LOOSE(true); diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp index ff74f4c6f744..f1fd40010a45 100644 --- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp @@ -66,7 +66,7 @@ void GcodeSuite::M421() { else if (!WITHIN(ij.x, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(ij.y, 0, GRID_MAX_POINTS_Y - 1)) SERIAL_ERROR_MSG(STR_ERR_MESH_XY); else { - float &zval = bedlevel.z_values[ij.x][ij.y]; // Altering this Mesh Point + float &zval = bedlevel.z_values[ij.x][ij.y]; // Altering this Mesh Point zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); // N=NAN, Z=NEWVAL, or Q=ADDVAL TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); // Ping ExtUI in case it's showing the mesh TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(ij.x, ij.y, zval)); diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index a9f378adfc90..fe1f87409afb 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -86,7 +86,7 @@ NUM_AXIS_LIST( TERN0(X_SENSORLESS, tmc_enable_stallguard(stepperX)), TERN0(Y_SENSORLESS, tmc_enable_stallguard(stepperY)), - false, false, false, false + false, false, false, false, false, false, false ) , TERN0(X2_SENSORLESS, tmc_enable_stallguard(stepperX2)) , TERN0(Y2_SENSORLESS, tmc_enable_stallguard(stepperY2)) @@ -468,7 +468,7 @@ void GcodeSuite::G28() { #endif } - #if BOTH(FOAMCUTTER_XYUV, HAS_I_AXIS) + #if ALL(FOAMCUTTER_XYUV, HAS_I_AXIS) // Home I (after X) if (doI) homeaxis(I_AXIS); #endif @@ -479,7 +479,7 @@ void GcodeSuite::G28() { homeaxis(Y_AXIS); #endif - #if BOTH(FOAMCUTTER_XYUV, HAS_J_AXIS) + #if ALL(FOAMCUTTER_XYUV, HAS_J_AXIS) // Home J (after Y) if (doJ) homeaxis(J_AXIS); #endif @@ -493,7 +493,7 @@ void GcodeSuite::G28() { // Home Z last if homing towards the bed #if HAS_Z_AXIS && DISABLED(HOME_Z_FIRST) if (doZ) { - #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) + #if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) stepper.set_all_z_lock(false); stepper.set_separate_multi_axis(false); #endif diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 656c23cb78ff..4673cc9832be 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -97,12 +97,12 @@ void ac_cleanup(TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index)) { void print_signed_float(FSTR_P const prefix, const_float_t f) { SERIAL_ECHOPGM(" "); - SERIAL_ECHOF(prefix, AS_CHAR(':')); + SERIAL_ECHOF(prefix, C(':')); serial_offset(f); } /** - * - Print the delta settings + * - Print the delta settings */ static void print_calibration_settings(const bool end_stops, const bool tower_angles) { SERIAL_ECHOPGM(".Height:", delta_height); @@ -128,7 +128,7 @@ static void print_calibration_settings(const bool end_stops, const bool tower_an } /** - * - Print the probe results + * - Print the probe results */ static void print_calibration_results(const float z_pt[NPP + 1], const bool tower_points, const bool opposite_points) { SERIAL_ECHOPGM(". "); @@ -152,7 +152,7 @@ static void print_calibration_results(const float z_pt[NPP + 1], const bool towe } /** - * - Calculate the standard deviation from the zero plane + * - Calculate the standard deviation from the zero plane */ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool _1p_cal, const bool _4p_cal, const bool _4p_opp) { if (!_0p_cal) { @@ -170,7 +170,7 @@ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool } /** - * - Probe a point + * - Probe a point */ static float calibration_probe(const xy_pos_t &xy, const bool stow, const bool probe_at_offset) { #if HAS_BED_PROBE @@ -182,7 +182,7 @@ static float calibration_probe(const xy_pos_t &xy, const bool stow, const bool p } /** - * - Probe a grid + * - Probe a grid */ 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, @@ -464,8 +464,8 @@ void GcodeSuite::G33() { SERIAL_ECHOLNPGM("G33 Auto Calibrate"); // Report settings - PGM_P const checkingac = PSTR("Checking... AC"); - SERIAL_ECHOPGM_P(checkingac); + FSTR_P const checkingac = F("Checking... AC"); + SERIAL_ECHOF(checkingac); SERIAL_ECHOPGM(" at radius:", dcr); if (verbose_level == 0) SERIAL_ECHOPGM(" (DRY-RUN)"); SERIAL_EOL(); diff --git a/Marlin/src/gcode/calibrate/G34.cpp b/Marlin/src/gcode/calibrate/G34.cpp index 7ae1e7765caa..9a0cb0054b72 100644 --- a/Marlin/src/gcode/calibrate/G34.cpp +++ b/Marlin/src/gcode/calibrate/G34.cpp @@ -39,6 +39,23 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" +/** + * G34 - Align the ends of the X gantry. See https://youtu.be/3jAFQdTk8iw + * + * - The carriage moves to GANTRY_CALIBRATION_SAFE_POSITION, also called the “pounce” position. + * - If possible, the Z stepper current is reduced to the value specified by 'S' + * (or GANTRY_CALIBRATION_CURRENT) to prevent damage to steppers and other parts. + * The reduced current should be just high enough to move the Z axis when not blocked. + * - The Z axis is jogged past the Z limit, only as far as the specified Z distance + * (or GANTRY_CALIBRATION_EXTRA_HEIGHT) at the GANTRY_CALIBRATION_FEEDRATE. + * - The Z axis is moved back to the working area (also at GANTRY_CALIBRATION_FEEDRATE). + * - Stepper current is restored back to normal. + * - The machine is re-homed, according to GANTRY_CALIBRATION_COMMANDS_POST. + * + * Parameters: + * [S] - Current value to use for the raise move. (Default: GANTRY_CALIBRATION_CURRENT) + * [Z] - Extra distance past Z_MAX_POS to move the Z axis. (Default: GANTRY_CALIBRATION_EXTRA_HEIGHT) + */ void GcodeSuite::G34() { // Home before the alignment procedure diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 8cf652cd8411..c137e07a4834 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfigPre.h" -#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) +#if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) #include "../../feature/z_stepper_align.h" @@ -79,6 +79,7 @@ * R Flag to recalculate points based on current probe offsets */ void GcodeSuite::G34() { + DEBUG_SECTION(log_G34, "G34", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) log_machine_info(); @@ -108,6 +109,7 @@ void GcodeSuite::G34() { } #if ENABLED(Z_STEPPER_AUTO_ALIGN) + do { // break out on error const int8_t z_auto_align_iterations = parser.intval('I', Z_STEPPER_ALIGN_ITERATIONS); @@ -217,7 +219,7 @@ void GcodeSuite::G34() { float z_measured_max = -100000.0f; // Probe all positions (one per Z-Stepper) - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { // iteration odd/even --> downward / upward stepper sequence const uint8_t iprobe = (iteration & 1) ? NUM_Z_STEPPERS - 1 - i : i; @@ -242,7 +244,7 @@ void GcodeSuite::G34() { // Add height to each value, to provide a more useful target height for // the next iteration of probing. This allows adjustments to be made away from the bed. - z_measured[iprobe] = z_probed_height + Z_CLEARANCE_BETWEEN_PROBES; + z_measured[iprobe] = z_probed_height + (Z_CLEARANCE_BETWEEN_PROBES); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Z", iprobe + 1, " measured position is ", z_measured[iprobe]); @@ -272,14 +274,14 @@ void GcodeSuite::G34() { // This allows the actual adjustment logic to be shared by both algorithms. linear_fit_data lfd; incremental_LSF_reset(&lfd); - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { SERIAL_ECHOLNPGM("PROBEPT_", i, ": ", z_measured[i]); incremental_LSF(&lfd, z_stepper_align.xy[i], z_measured[i]); } finish_incremental_LSF(&lfd); z_measured_min = 100000.0f; - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { z_measured[i] = -(lfd.A * z_stepper_align.stepper_xy[i].x + lfd.B * z_stepper_align.stepper_xy[i].y + lfd.D); z_measured_min = _MIN(z_measured_min, z_measured[i]); } @@ -347,12 +349,12 @@ void GcodeSuite::G34() { // Calculate mean value as a reference float z_measured_mean = 0.0f; - LOOP_L_N(zstepper, NUM_Z_STEPPERS) z_measured_mean += z_measured[zstepper]; + for (uint8_t zstepper = 0; zstepper < NUM_Z_STEPPERS; ++zstepper) z_measured_mean += z_measured[zstepper]; z_measured_mean /= NUM_Z_STEPPERS; // Calculate the sum of the absolute deviations from the mean value float z_align_level_indicator = 0.0f; - LOOP_L_N(zstepper, NUM_Z_STEPPERS) + for (uint8_t zstepper = 0; zstepper < NUM_Z_STEPPERS; ++zstepper) z_align_level_indicator += ABS(z_measured[zstepper] - z_measured_mean); // If it's getting worse, stop and throw an error @@ -367,7 +369,7 @@ void GcodeSuite::G34() { bool success_break = true; // Correct the individual stepper offsets - LOOP_L_N(zstepper, NUM_Z_STEPPERS) { + for (uint8_t zstepper = 0; zstepper < NUM_Z_STEPPERS; ++zstepper) { // Calculate current stepper move float z_align_move = z_measured[zstepper] - z_measured_min; const float z_align_abs = ABS(z_align_move); @@ -444,14 +446,14 @@ void GcodeSuite::G34() { // Use the probed height from the last iteration to determine the Z height. // z_measured_min is used, because all steppers are aligned to z_measured_min. // Ideally, this would be equal to the 'z_probe * 0.5f' which was added earlier. - current_position.z -= z_measured_min - (float)Z_CLEARANCE_BETWEEN_PROBES; + current_position.z -= z_measured_min - float(Z_CLEARANCE_BETWEEN_PROBES); sync_plan_position(); #endif // Restore the active tool after homing TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER))); // Fetch previous tool for parking extruder - #if BOTH(HAS_LEVELING, RESTORE_LEVELING_AFTER_G34) + #if ALL(HAS_LEVELING, RESTORE_LEVELING_AFTER_G34) set_bed_leveling_enabled(leveling_was_active); #endif @@ -546,7 +548,7 @@ void GcodeSuite::M422() { void GcodeSuite::M422_report(const bool forReplay/*=true*/) { report_heading(forReplay, F(STR_Z_AUTO_ALIGN)); - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M422 S"), i + 1, @@ -555,7 +557,7 @@ void GcodeSuite::M422_report(const bool forReplay/*=true*/) { ); } #if HAS_Z_STEPPER_ALIGN_STEPPER_XY - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M422 W"), i + 1, diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index a22608f5b42b..992d7c38e621 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -33,10 +33,13 @@ #include "../../lcd/marlinui.h" #include "../../module/motion.h" #include "../../module/planner.h" -#include "../../module/tool_change.h" #include "../../module/endstops.h" #include "../../feature/bedlevel/bedlevel.h" +#if HAS_MULTI_HOTEND + #include "../../module/tool_change.h" +#endif + #if !AXIS_CAN_CALIBRATE(X) #undef CALIBRATION_MEASURE_LEFT #undef CALIBRATION_MEASURE_RIGHT @@ -70,7 +73,7 @@ #define CALIBRATION_MEASUREMENT_CERTAIN 0.5 // mm #endif -#if BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT) +#if ALL(HAS_X_AXIS, CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT) #define HAS_X_CENTER 1 #endif #if ALL(HAS_Y_AXIS, CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK) @@ -171,7 +174,7 @@ inline void park_above_object(measurements_t &m, const float uncertainty) { #if HAS_HOTEND_OFFSET inline void normalize_hotend_offsets() { - LOOP_S_L_N(e, 1, HOTENDS) + for (uint8_t e = 1; e < HOTENDS; ++e) hotend_offset[e] -= hotend_offset[0]; hotend_offset[0].reset(); } @@ -271,10 +274,10 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t #if AXIS_CAN_CALIBRATE(X) _ACASE(X, RIGHT, LEFT); #endif - #if HAS_Y_AXIS && AXIS_CAN_CALIBRATE(Y) + #if AXIS_CAN_CALIBRATE(Y) _ACASE(Y, BACK, FRONT); #endif - #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) + #if AXIS_CAN_CALIBRATE(Z) case TOP: { const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); m.obj_center.z = measurement - dimensions.z / 2; @@ -282,22 +285,22 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t return; } #endif - #if HAS_I_AXIS && AXIS_CAN_CALIBRATE(I) + #if AXIS_CAN_CALIBRATE(I) _PCASE(I); #endif - #if HAS_J_AXIS && AXIS_CAN_CALIBRATE(J) + #if AXIS_CAN_CALIBRATE(J) _PCASE(J); #endif - #if HAS_K_AXIS && AXIS_CAN_CALIBRATE(K) + #if AXIS_CAN_CALIBRATE(K) _PCASE(K); #endif - #if HAS_U_AXIS && AXIS_CAN_CALIBRATE(U) + #if AXIS_CAN_CALIBRATE(U) _PCASE(U); #endif - #if HAS_V_AXIS && AXIS_CAN_CALIBRATE(V) + #if AXIS_CAN_CALIBRATE(V) _PCASE(V); #endif - #if HAS_W_AXIS && AXIS_CAN_CALIBRATE(W) + #if AXIS_CAN_CALIBRATE(W) _PCASE(W); #endif default: return; @@ -395,14 +398,16 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if ENABLED(CALIBRATION_REPORTING) inline void report_measured_faces(const measurements_t &m) { SERIAL_ECHOLNPGM("Sides:"); - #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) + #if AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPGM(" Top: ", m.obj_side[TOP]); #endif - #if ENABLED(CALIBRATION_MEASURE_LEFT) - SERIAL_ECHOLNPGM(" Left: ", m.obj_side[LEFT]); - #endif - #if ENABLED(CALIBRATION_MEASURE_RIGHT) - SERIAL_ECHOLNPGM(" Right: ", m.obj_side[RIGHT]); + #if HAS_X_AXIS + #if ENABLED(CALIBRATION_MEASURE_LEFT) + SERIAL_ECHOLNPGM(" Left: ", m.obj_side[LEFT]); + #endif + #if ENABLED(CALIBRATION_MEASURE_RIGHT) + SERIAL_ECHOLNPGM(" Right: ", m.obj_side[RIGHT]); + #endif #endif #if HAS_Y_AXIS #if ENABLED(CALIBRATION_MEASURE_FRONT) @@ -503,7 +508,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM(" Right: ", m.backlash[RIGHT]); #endif #endif - #if HAS_Y_AXIS && AXIS_CAN_CALIBRATE(Y) + #if AXIS_CAN_CALIBRATE(Y) #if ENABLED(CALIBRATION_MEASURE_FRONT) SERIAL_ECHOLNPGM(" Front: ", m.backlash[FRONT]); #endif @@ -511,10 +516,10 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM(" Back: ", m.backlash[BACK]); #endif #endif - #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) + #if AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPGM(" Top: ", m.backlash[TOP]); #endif - #if HAS_I_AXIS && AXIS_CAN_CALIBRATE(I) + #if AXIS_CAN_CALIBRATE(I) #if ENABLED(CALIBRATION_MEASURE_IMIN) SERIAL_ECHOLNPGM(" " STR_I_MIN ": ", m.backlash[IMINIMUM]); #endif @@ -522,7 +527,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM(" " STR_I_MAX ": ", m.backlash[IMAXIMUM]); #endif #endif - #if HAS_J_AXIS && AXIS_CAN_CALIBRATE(J) + #if AXIS_CAN_CALIBRATE(J) #if ENABLED(CALIBRATION_MEASURE_JMIN) SERIAL_ECHOLNPGM(" " STR_J_MIN ": ", m.backlash[JMINIMUM]); #endif @@ -530,7 +535,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM(" " STR_J_MAX ": ", m.backlash[JMAXIMUM]); #endif #endif - #if HAS_K_AXIS && AXIS_CAN_CALIBRATE(K) + #if AXIS_CAN_CALIBRATE(K) #if ENABLED(CALIBRATION_MEASURE_KMIN) SERIAL_ECHOLNPGM(" " STR_K_MIN ": ", m.backlash[KMINIMUM]); #endif @@ -538,7 +543,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM(" " STR_K_MAX ": ", m.backlash[KMAXIMUM]); #endif #endif - #if HAS_U_AXIS && AXIS_CAN_CALIBRATE(U) + #if AXIS_CAN_CALIBRATE(U) #if ENABLED(CALIBRATION_MEASURE_UMIN) SERIAL_ECHOLNPGM(" " STR_U_MIN ": ", m.backlash[UMINIMUM]); #endif @@ -546,7 +551,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM(" " STR_U_MAX ": ", m.backlash[UMAXIMUM]); #endif #endif - #if HAS_V_AXIS && AXIS_CAN_CALIBRATE(V) + #if AXIS_CAN_CALIBRATE(V) #if ENABLED(CALIBRATION_MEASURE_VMIN) SERIAL_ECHOLNPGM(" " STR_V_MIN ": ", m.backlash[VMINIMUM]); #endif @@ -554,7 +559,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM(" " STR_V_MAX ": ", m.backlash[VMAXIMUM]); #endif #endif - #if HAS_W_AXIS && AXIS_CAN_CALIBRATE(W) + #if AXIS_CAN_CALIBRATE(W) #if ENABLED(CALIBRATION_MEASURE_WMIN) SERIAL_ECHOLNPGM(" " STR_W_MIN ": ", m.backlash[WMINIMUM]); #endif @@ -575,7 +580,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if HAS_Y_CENTER && AXIS_CAN_CALIBRATE(Y) SERIAL_ECHOLNPGM_P(SP_Y_STR, m.pos_error.y); #endif - #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) + #if AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPGM_P(SP_Z_STR, m.pos_error.z); #endif #if HAS_I_CENTER && AXIS_CAN_CALIBRATE(I) @@ -616,7 +621,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // This function requires normalize_hotend_offsets() to be called // inline void report_hotend_offsets() { - LOOP_S_L_N(e, 1, HOTENDS) + for (uint8_t e = 1; e < HOTENDS; ++e) SERIAL_ECHOLNPGM_P(PSTR("T"), e, PSTR(" Hotend Offset X"), hotend_offset[e].x, SP_Y_STR, hotend_offset[e].y, SP_Z_STR, hotend_offset[e].z); } #endif diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index c484d4f1b770..be125b148551 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -34,7 +34,6 @@ #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" @@ -82,7 +81,7 @@ * - `P` - Run probe temperature calibration. */ -#if BOTH(PTC_PROBE, PTC_BED) +#if ALL(PTC_PROBE, PTC_BED) static void say_waiting_for() { SERIAL_ECHOPGM("Waiting for "); } static void say_waiting_for_probe_heating() { say_waiting_for(); SERIAL_ECHOLNPGM("probe heating."); } @@ -108,7 +107,6 @@ }; auto g76_probe = [](const TempSensorID sid, celsius_t &targ, const xy_pos_t &nozpos) { - do_z_clearance(5.0); // Raise nozzle before probing ptc.set_enabled(false); const float measured_z = probe.probe_at_point(nozpos, PROBE_PT_STOW, 0, false); // verbose=0, probe_relative=false ptc.set_enabled(true); @@ -258,7 +256,7 @@ say_waiting_for_probe_heating(); SERIAL_ECHOLNPGM(" Bed:", target_bed, " Probe:", target_probe); - const millis_t probe_timeout_ms = millis() + SEC_TO_MS(900UL); + const millis_t probe_timeout_ms = millis() + MIN_TO_MS(15); while (thermalManager.degProbe() < target_probe) { if (report_temps(next_temp_report, probe_timeout_ms)) { SERIAL_ECHOLNPGM("!Probe heating timed out."); diff --git a/Marlin/src/gcode/calibrate/M100.cpp b/Marlin/src/gcode/calibrate/M100.cpp index 338392b59746..3791c69f88bd 100644 --- a/Marlin/src/gcode/calibrate/M100.cpp +++ b/Marlin/src/gcode/calibrate/M100.cpp @@ -60,7 +60,7 @@ #define TEST_BYTE ((char) 0xE5) -#if EITHER(__AVR__, IS_32BIT_TEENSY) +#if ANY(__AVR__, IS_32BIT_TEENSY) extern char __bss_end; char *end_bss = &__bss_end, @@ -163,14 +163,14 @@ inline int32_t count_test_bytes(const char * const start_free_memory) { while (start_free_memory < end_free_memory) { print_hex_address(start_free_memory); // Print the address SERIAL_CHAR(':'); - LOOP_L_N(i, 16) { // and 16 data bytes + for (uint8_t i = 0; i < 16; ++i) { // and 16 data bytes if (i == 8) SERIAL_CHAR('-'); print_hex_byte(start_free_memory[i]); SERIAL_CHAR(' '); } serial_delay(25); SERIAL_CHAR('|'); // Point out non test bytes - LOOP_L_N(i, 16) { + for (uint8_t i = 0; i < 16; ++i) { char ccc = (char)start_free_memory[i]; // cast to char before automatically casting to char on assignment, in case the compiler is broken ccc = (ccc == TEST_BYTE) ? ' ' : '?'; SERIAL_CHAR(ccc); diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index a6c6ff9dae3e..cd206ca48927 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -46,12 +46,13 @@ void GcodeSuite::M425() { bool noArgs = true; - auto axis_can_calibrate = [](const uint8_t a) { - #define _CAN_CASE(N) case N##_AXIS: return AXIS_CAN_CALIBRATE(N); + auto axis_can_calibrate = [](const uint8_t a) -> bool { + #define _CAN_CASE(N) case N##_AXIS: return bool(AXIS_CAN_CALIBRATE(N)); switch (a) { - default: return false; MAIN_AXIS_MAP(_CAN_CASE) + default: break; } + return false; }; LOOP_NUM_AXES(a) { @@ -111,17 +112,19 @@ void GcodeSuite::M425_report(const bool forReplay/*=true*/) { #ifdef BACKLASH_SMOOTHING_MM , PSTR(" S"), LINEAR_UNIT(backlash.get_smoothing_mm()) #endif - , LIST_N(DOUBLE(NUM_AXES), - SP_X_STR, LINEAR_UNIT(backlash.get_distance_mm(X_AXIS)), - SP_Y_STR, LINEAR_UNIT(backlash.get_distance_mm(Y_AXIS)), - SP_Z_STR, LINEAR_UNIT(backlash.get_distance_mm(Z_AXIS)), - SP_I_STR, I_AXIS_UNIT(backlash.get_distance_mm(I_AXIS)), - SP_J_STR, J_AXIS_UNIT(backlash.get_distance_mm(J_AXIS)), - SP_K_STR, K_AXIS_UNIT(backlash.get_distance_mm(K_AXIS)), - SP_U_STR, U_AXIS_UNIT(backlash.get_distance_mm(U_AXIS)), - SP_V_STR, V_AXIS_UNIT(backlash.get_distance_mm(V_AXIS)), - SP_W_STR, W_AXIS_UNIT(backlash.get_distance_mm(W_AXIS)) - ) + #if NUM_AXES + , LIST_N(DOUBLE(NUM_AXES), + SP_X_STR, LINEAR_UNIT(backlash.get_distance_mm(X_AXIS)), + SP_Y_STR, LINEAR_UNIT(backlash.get_distance_mm(Y_AXIS)), + SP_Z_STR, LINEAR_UNIT(backlash.get_distance_mm(Z_AXIS)), + SP_I_STR, I_AXIS_UNIT(backlash.get_distance_mm(I_AXIS)), + SP_J_STR, J_AXIS_UNIT(backlash.get_distance_mm(J_AXIS)), + SP_K_STR, K_AXIS_UNIT(backlash.get_distance_mm(K_AXIS)), + SP_U_STR, U_AXIS_UNIT(backlash.get_distance_mm(U_AXIS)), + SP_V_STR, V_AXIS_UNIT(backlash.get_distance_mm(V_AXIS)), + SP_W_STR, W_AXIS_UNIT(backlash.get_distance_mm(W_AXIS)) + ) + #endif ); } diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index 6d4117b6b806..8bee3fd88ced 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -66,9 +66,6 @@ void GcodeSuite::M48() { return; } - if (verbose_level > 0) - SERIAL_ECHOLNPGM("M48 Z-Probe Repeatability Test"); - const int8_t n_samples = parser.byteval('P', 10); if (!WITHIN(n_samples, 4, 50)) { SERIAL_ECHOLNPGM("?Sample size not plausible (4-50)."); @@ -102,6 +99,9 @@ void GcodeSuite::M48() { const bool schizoid_flag = parser.boolval('S'); if (schizoid_flag && !seen_L) n_legs = 7; + if (verbose_level > 0) + SERIAL_ECHOLNPGM("M48 Z-Probe Repeatability Test"); + if (verbose_level > 2) SERIAL_ECHOLNPGM("Positioning the probe..."); @@ -148,7 +148,7 @@ void GcodeSuite::M48() { float sample_sum = 0.0; - LOOP_L_N(n, n_samples) { + for (uint8_t n = 0; n < n_samples; ++n) { #if HAS_STATUS_MESSAGE // Display M48 progress in the status bar ui.status_printf(0, F(S_FMT ": %d/%d"), GET_TEXT(MSG_M48_POINT), int(n + 1), int(n_samples)); @@ -175,7 +175,7 @@ void GcodeSuite::M48() { } // Move from leg to leg in rapid succession - LOOP_L_N(l, n_legs - 1) { + for (uint8_t l = 0; l < n_legs - 1; ++l) { // Move some distance around the perimeter float delta_angle; @@ -223,7 +223,7 @@ void GcodeSuite::M48() { } // n_legs // Probe a single point - const float pz = probe.probe_at_point(test_position, raise_after, 0); + const float pz = probe.probe_at_point(test_position, raise_after); // Break the loop if the probe fails probing_good = !isnan(pz); @@ -243,7 +243,7 @@ void GcodeSuite::M48() { // Calculate the standard deviation so far. // The value after the last sample will be the final output. float dev_sum = 0.0; - LOOP_LE_N(j, n) dev_sum += sq(sample_set[j] - mean); + for (uint8_t j = 0; j <= n; ++j) dev_sum += sq(sample_set[j] - mean); sigma = SQRT(dev_sum / (n + 1)); if (verbose_level > 1) { diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index 90fad1811c8c..143b6f249a4e 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS +#if ANY(DELTA, HAS_EXTRA_ENDSTOPS) #include "../gcode.h" @@ -52,7 +52,7 @@ is_err = true; else { delta_endstop_adj[i] = v; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("delta_endstop_adj[", AS_CHAR(AXIS_CHAR(i)), "] = ", v); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("delta_endstop_adj[", C(AXIS_CHAR(i)), "] = ", v); } } } diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index cda3177d93eb..96bfb78352f6 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -143,24 +143,32 @@ void GcodeSuite::M201() { void GcodeSuite::M201_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, F(STR_MAX_ACCELERATION)); - SERIAL_ECHOLNPGM_P( - LIST_N(DOUBLE(NUM_AXES), - PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]), - SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]), - SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]), - SP_I_STR, I_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]), - SP_J_STR, J_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]), - SP_K_STR, K_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS]), - SP_U_STR, U_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[U_AXIS]), - SP_V_STR, V_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[V_AXIS]), - SP_W_STR, W_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[W_AXIS]) - ) - #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) - , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS]) - #endif - ); + #if NUM_AXES + SERIAL_ECHOPGM_P( + LIST_N(DOUBLE(NUM_AXES), + PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]), + SP_I_STR, I_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]), + SP_J_STR, J_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]), + SP_K_STR, K_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS]), + SP_U_STR, U_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[U_AXIS]), + SP_V_STR, V_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[V_AXIS]), + SP_W_STR, W_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[W_AXIS]) + ) + ); + #endif + + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) + SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS])); + #endif + + #if NUM_AXES || (HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)) + SERIAL_EOL(); + #endif + #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(i, E_STEPPERS) { + for (uint8_t i = 0; i < E_STEPPERS; ++i) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M201 T"), i @@ -191,24 +199,32 @@ void GcodeSuite::M203() { void GcodeSuite::M203_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, F(STR_MAX_FEEDRATES)); - SERIAL_ECHOLNPGM_P( - LIST_N(DOUBLE(NUM_AXES), - PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]), - SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]), - SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]), - SP_I_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[I_AXIS]), - SP_J_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[J_AXIS]), - SP_K_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[K_AXIS]), - SP_U_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[U_AXIS]), - SP_V_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[V_AXIS]), - SP_W_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[W_AXIS]) - ) - #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) - , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS]) - #endif - ); + #if NUM_AXES + SERIAL_ECHOPGM_P( + LIST_N(DOUBLE(NUM_AXES), + PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]), + SP_I_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[I_AXIS]), + SP_J_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[J_AXIS]), + SP_K_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[K_AXIS]), + SP_U_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[U_AXIS]), + SP_V_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[V_AXIS]), + SP_W_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[W_AXIS]) + ) + ); + #endif + + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) + SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS])); + #endif + + #if NUM_AXES || (HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)) + SERIAL_EOL(); + #endif + #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(i, E_STEPPERS) { + for (uint8_t i = 0; i < E_STEPPERS; ++i) { if (!forReplay) SERIAL_ECHO_START(); SERIAL_ECHOLNPGM_P( PSTR(" M203 T"), i @@ -281,9 +297,6 @@ 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 && AXIS_COLLISION('J') - #error "Can't set_max_jerk for 'J' axis because 'J' is used for Junction Deviation." - #endif if (parser.seenval('J')) { const float junc_dev = parser.value_linear_units(); if (WITHIN(junc_dev, 0.01f, 0.3f)) { diff --git a/Marlin/src/gcode/config/M217.cpp b/Marlin/src/gcode/config/M217.cpp index b360739e210a..908a19fae711 100644 --- a/Marlin/src/gcode/config/M217.cpp +++ b/Marlin/src/gcode/config/M217.cpp @@ -95,7 +95,9 @@ void GcodeSuite::M217() { #if ENABLED(TOOLCHANGE_PARK) if (parser.seenval('W')) { toolchange_settings.enable_park = parser.value_linear_units(); } - if (parser.seenval('X')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.x = constrain(v, X_MIN_POS, X_MAX_POS); } + #if HAS_X_AXIS + if (parser.seenval('X')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.x = constrain(v, X_MIN_POS, X_MAX_POS); } + #endif #if HAS_Y_AXIS if (parser.seenval('Y')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.y = constrain(v, Y_MIN_POS, Y_MAX_POS); } #endif @@ -183,25 +185,27 @@ void GcodeSuite::M217_report(const bool forReplay/*=true*/) { #endif #if ENABLED(TOOLCHANGE_PARK) - { SERIAL_ECHOPGM(" W", LINEAR_UNIT(toolchange_settings.enable_park)); - SERIAL_ECHOPGM_P( - SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x) - #if HAS_Y_AXIS - , SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y) - #endif - #if SECONDARY_AXES >= 1 - , LIST_N(DOUBLE(SECONDARY_AXES) - , SP_I_STR, I_AXIS_UNIT(toolchange_settings.change_point.i) - , SP_J_STR, J_AXIS_UNIT(toolchange_settings.change_point.j) - , SP_K_STR, K_AXIS_UNIT(toolchange_settings.change_point.k) - , SP_C_STR, U_AXIS_UNIT(toolchange_settings.change_point.u) - , PSTR(" H"), V_AXIS_UNIT(toolchange_settings.change_point.v) - , PSTR(" O"), W_AXIS_UNIT(toolchange_settings.change_point.w) - ) - #endif - ); - } + #if NUM_AXES + { + SERIAL_ECHOPGM_P( + SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x) + #if HAS_Y_AXIS + , SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y) + #endif + #if SECONDARY_AXES >= 1 + , LIST_N(DOUBLE(SECONDARY_AXES) + , SP_I_STR, I_AXIS_UNIT(toolchange_settings.change_point.i) + , SP_J_STR, J_AXIS_UNIT(toolchange_settings.change_point.j) + , SP_K_STR, K_AXIS_UNIT(toolchange_settings.change_point.k) + , SP_C_STR, U_AXIS_UNIT(toolchange_settings.change_point.u) + , PSTR(" H"), V_AXIS_UNIT(toolchange_settings.change_point.v) + , PSTR(" O"), W_AXIS_UNIT(toolchange_settings.change_point.w) + ) + #endif + ); + } + #endif #endif #if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED) diff --git a/Marlin/src/gcode/config/M218.cpp b/Marlin/src/gcode/config/M218.cpp index c39447a28d38..d645685701ec 100644 --- a/Marlin/src/gcode/config/M218.cpp +++ b/Marlin/src/gcode/config/M218.cpp @@ -46,9 +46,15 @@ void GcodeSuite::M218() { const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; - if (parser.seenval('X')) hotend_offset[target_extruder].x = parser.value_linear_units(); - if (parser.seenval('Y')) hotend_offset[target_extruder].y = parser.value_linear_units(); - if (parser.seenval('Z')) hotend_offset[target_extruder].z = parser.value_linear_units(); + #if HAS_X_AXIS + if (parser.seenval('X')) hotend_offset[target_extruder].x = parser.value_linear_units(); + #endif + #if HAS_Y_AXIS + if (parser.seenval('Y')) hotend_offset[target_extruder].y = parser.value_linear_units(); + #endif + #if HAS_Z_AXIS + if (parser.seenval('Z')) hotend_offset[target_extruder].z = parser.value_linear_units(); + #endif #if ENABLED(DELTA) if (target_extruder == active_extruder) @@ -58,7 +64,7 @@ void GcodeSuite::M218() { void GcodeSuite::M218_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, F(STR_HOTEND_OFFSETS)); - LOOP_S_L_N(e, 1, HOTENDS) { + for (uint8_t e = 1; e < HOTENDS; ++e) { report_echo_start(forReplay); SERIAL_ECHOPGM_P( PSTR(" M218 T"), e, diff --git a/Marlin/src/gcode/config/M281.cpp b/Marlin/src/gcode/config/M281.cpp index e4ef3ab40b8c..038a5d615ada 100644 --- a/Marlin/src/gcode/config/M281.cpp +++ b/Marlin/src/gcode/config/M281.cpp @@ -56,7 +56,7 @@ void GcodeSuite::M281() { void GcodeSuite::M281_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, F(STR_SERVO_ANGLES)); - LOOP_L_N(i, NUM_SERVOS) { + for (uint8_t i = 0; i < NUM_SERVOS; ++i) { switch (i) { default: break; #if ENABLED(SWITCHING_EXTRUDER) @@ -66,6 +66,9 @@ void GcodeSuite::M281_report(const bool forReplay/*=true*/) { #endif #elif ENABLED(SWITCHING_NOZZLE) case SWITCHING_NOZZLE_SERVO_NR: + #if ENABLED(SWITCHING_NOZZLE_TWO_SERVOS) + case SWITCHING_NOZZLE_E1_SERVO_NR: + #endif #elif ENABLED(BLTOUCH) || (HAS_Z_SERVO_PROBE && defined(Z_SERVO_ANGLES)) case Z_PROBE_SERVO_NR: #endif diff --git a/Marlin/src/gcode/config/M305.cpp b/Marlin/src/gcode/config/M305.cpp index e7746923b318..48d7cf18820a 100644 --- a/Marlin/src/gcode/config/M305.cpp +++ b/Marlin/src/gcode/config/M305.cpp @@ -69,7 +69,7 @@ void GcodeSuite::M305() { SERIAL_ECHO_MSG("!Invalid Steinhart-Hart C coeff. (-0.01 < C < +0.01)"); } // If not setting then report parameters else if (t_index < 0) { // ...all user thermistors - LOOP_L_N(i, USER_THERMISTORS) + for (uint8_t i = 0; i < USER_THERMISTORS; ++i) thermalManager.M305_report(i); } else // ...one user thermistor diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 460e25dde272..de511d9e0e50 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -25,7 +25,7 @@ #if ENABLED(PINS_DEBUGGING) #include "../gcode.h" -#include "../../MarlinCore.h" // for pin_is_protected +#include "../../MarlinCore.h" // for pin_is_protected, wait_for_user #include "../../pins/pinsDebug.h" #include "../../module/endstops.h" @@ -61,7 +61,7 @@ inline void toggle_pins() { end = PARSED_PIN_INDEX('L', NUM_DIGITAL_PINS - 1), wait = parser.intval('W', 500); - LOOP_S_LE_N(i, start, end) { + for (uint8_t i = start; i <= end; ++i) { pin_t pin = GET_PIN_MAP_PIN_M43(i); if (!VALID_PIN(pin)) continue; if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) { @@ -195,31 +195,30 @@ inline void servo_probe_test() { if (!blt) { // DEPLOY and STOW 4 times and see if the signal follows // Then it is a mechanical switch - uint8_t i = 0; SERIAL_ECHOLNPGM(". Deploy & stow 4 times"); - do { + for (uint8_t i = 0; i < 4; ++i) { servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy safe_delay(500); deploy_state = READ(PROBE_TEST_PIN); servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][1]); // Stow safe_delay(500); stow_state = READ(PROBE_TEST_PIN); - } while (++i < 4); + } if (probe_inverting != deploy_state) SERIAL_ECHOLNPGM("WARNING: INVERTING setting probably backwards."); if (deploy_state != stow_state) { SERIAL_ECHOLNPGM("= Mechanical Switch detected"); if (deploy_state) { - SERIAL_ECHOLNPGM(" DEPLOYED state: HIGH (logic 1)", - " STOWED (triggered) state: LOW (logic 0)"); + SERIAL_ECHOLNPGM(". DEPLOYED state: HIGH (logic 1)\n" + ". STOWED (triggered) state: LOW (logic 0)"); } else { - SERIAL_ECHOLNPGM(" DEPLOYED state: LOW (logic 0)", - " STOWED (triggered) state: HIGH (logic 1)"); + SERIAL_ECHOLNPGM(". DEPLOYED state: LOW (logic 0)\n" + ". STOWED (triggered) state: HIGH (logic 1)"); } #if ENABLED(BLTOUCH) - SERIAL_ECHOLNPGM("FAIL: BLTOUCH enabled - Set up this device as a Servo Probe with INVERTING set to 'true'."); + SERIAL_ECHOLNPGM("FAIL: Can't enable BLTOUCH. Check your settings."); #endif return; } @@ -336,7 +335,7 @@ void GcodeSuite::M43() { const uint8_t pin_count = last_pin - first_pin + 1; uint8_t pin_state[pin_count]; bool can_watch = false; - LOOP_S_LE_N(i, first_pin, last_pin) { + for (uint8_t i = first_pin; i <= last_pin; ++i) { pin_t pin = GET_PIN_MAP_PIN_M43(i); if (!VALID_PIN(pin)) continue; if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue; @@ -379,7 +378,7 @@ void GcodeSuite::M43() { #endif for (;;) { - LOOP_S_LE_N(i, first_pin, last_pin) { + for (uint8_t i = first_pin; i <= last_pin; ++i) { const pin_t pin = GET_PIN_MAP_PIN_M43(i); if (!VALID_PIN(pin)) continue; if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue; @@ -408,7 +407,7 @@ void GcodeSuite::M43() { } else { // Report current state of selected pin(s) - LOOP_S_LE_N(i, first_pin, last_pin) { + for (uint8_t i = first_pin; i <= last_pin; ++i) { const pin_t pin = GET_PIN_MAP_PIN_M43(i); if (VALID_PIN(pin)) report_pin_state_extended(pin, ignore_protection, true); } diff --git a/Marlin/src/gcode/config/M672.cpp b/Marlin/src/gcode/config/M672.cpp index 257b49471f61..064d05d0b639 100644 --- a/Marlin/src/gcode/config/M672.cpp +++ b/Marlin/src/gcode/config/M672.cpp @@ -54,7 +54,7 @@ // b3 b2 b1 b0 ~b0 ... lo bits, NOT last bit // void M672_send(uint8_t b) { // bit rate requirement: 1kHz +/- 30% - LOOP_L_N(bits, 14) { + for (uint8_t bits = 0; bits < 14; ++bits) { switch (bits) { default: { OUT_WRITE(SMART_EFFECTOR_MOD_PIN, !!(b & 0x80)); b <<= 1; break; } // send bit, shift next into place case 7: diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index c7610b83a9b9..b5bdd784055e 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -37,6 +37,7 @@ * H - Specify micro-steps to use. Best guess if not supplied. * L - Desired layer height in current units. Nearest good heights are shown. */ + void GcodeSuite::M92() { const int8_t target_extruder = get_target_extruder_from_command(); @@ -92,24 +93,30 @@ void GcodeSuite::M92() { void GcodeSuite::M92_report(const bool forReplay/*=true*/, const int8_t e/*=-1*/) { report_heading_etc(forReplay, F(STR_STEPS_PER_UNIT)); - SERIAL_ECHOPGM_P(LIST_N(DOUBLE(NUM_AXES), - PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), - SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), - SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]), - SP_I_STR, I_AXIS_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]), - SP_J_STR, J_AXIS_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]), - SP_K_STR, K_AXIS_UNIT(planner.settings.axis_steps_per_mm[K_AXIS]), - SP_U_STR, U_AXIS_UNIT(planner.settings.axis_steps_per_mm[U_AXIS]), - SP_V_STR, V_AXIS_UNIT(planner.settings.axis_steps_per_mm[V_AXIS]), - SP_W_STR, W_AXIS_UNIT(planner.settings.axis_steps_per_mm[W_AXIS]) - )); + #if NUM_AXES + #define PRINT_EOL + SERIAL_ECHOPGM_P(LIST_N(DOUBLE(NUM_AXES), + PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]), + SP_I_STR, I_AXIS_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]), + SP_J_STR, J_AXIS_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]), + SP_K_STR, K_AXIS_UNIT(planner.settings.axis_steps_per_mm[K_AXIS]), + SP_U_STR, U_AXIS_UNIT(planner.settings.axis_steps_per_mm[U_AXIS]), + SP_V_STR, V_AXIS_UNIT(planner.settings.axis_steps_per_mm[V_AXIS]), + SP_W_STR, W_AXIS_UNIT(planner.settings.axis_steps_per_mm[W_AXIS]) + )); + #endif + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) + #define PRINT_EOL SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS])); #endif - SERIAL_EOL(); + + if (ENABLED(PRINT_EOL)) SERIAL_EOL(); #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(i, E_STEPPERS) { + for (uint8_t i = 0; i < E_STEPPERS; ++i) { if (e >= 0 && i != e) continue; report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( diff --git a/Marlin/src/gcode/control/M111.cpp b/Marlin/src/gcode/control/M111.cpp index a92d334ae9d3..39fce1e536b2 100644 --- a/Marlin/src/gcode/control/M111.cpp +++ b/Marlin/src/gcode/control/M111.cpp @@ -46,7 +46,7 @@ void GcodeSuite::M111() { SERIAL_ECHOPGM(STR_DEBUG_PREFIX); if (marlin_debug_flags) { uint8_t comma = 0; - LOOP_L_N(i, COUNT(debug_strings)) { + for (uint8_t i = 0; i < COUNT(debug_strings); ++i) { if (TEST(marlin_debug_flags, i)) { if (comma++) SERIAL_CHAR(','); SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&debug_strings[i])); @@ -55,23 +55,20 @@ void GcodeSuite::M111() { } else { SERIAL_ECHOPGM(STR_DEBUG_OFF); - #if !defined(__AVR__) || !defined(USBCON) + #if !(defined(__AVR__) && defined(USBCON)) #if ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS) SERIAL_ECHOPGM("\nBuffer Overruns: ", MYSERIAL1.buffer_overruns()); #endif - #if ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS) SERIAL_ECHOPGM("\nFraming Errors: ", MYSERIAL1.framing_errors()); #endif - #if ENABLED(SERIAL_STATS_DROPPED_RX) SERIAL_ECHOPGM("\nDropped bytes: ", MYSERIAL1.dropped()); #endif - #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) SERIAL_ECHOPGM("\nMax RX Queue Size: ", MYSERIAL1.rxMaxEnqueued()); #endif - #endif // !__AVR__ || !USBCON + #endif // !(__AVR__ && USBCON) } SERIAL_EOL(); } diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index 4ff48568faea..1742d288b3f5 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -48,17 +48,19 @@ inline stepper_flags_t selected_axis_bits() { selected.bits = e_axis_mask; } #endif - selected.bits |= NUM_AXIS_GANG( - (parser.seen_test('X') << X_AXIS), - | (parser.seen_test('Y') << Y_AXIS), - | (parser.seen_test('Z') << Z_AXIS), - | (parser.seen_test(AXIS4_NAME) << I_AXIS), - | (parser.seen_test(AXIS5_NAME) << J_AXIS), - | (parser.seen_test(AXIS6_NAME) << K_AXIS), - | (parser.seen_test(AXIS7_NAME) << U_AXIS), - | (parser.seen_test(AXIS8_NAME) << V_AXIS), - | (parser.seen_test(AXIS9_NAME) << W_AXIS) - ); + #if NUM_AXES + selected.bits |= NUM_AXIS_GANG( + (parser.seen_test('X') << X_AXIS), + | (parser.seen_test('Y') << Y_AXIS), + | (parser.seen_test('Z') << Z_AXIS), + | (parser.seen_test(AXIS4_NAME) << I_AXIS), + | (parser.seen_test(AXIS5_NAME) << J_AXIS), + | (parser.seen_test(AXIS6_NAME) << K_AXIS), + | (parser.seen_test(AXIS7_NAME) << U_AXIS), + | (parser.seen_test(AXIS8_NAME) << V_AXIS), + | (parser.seen_test(AXIS9_NAME) << W_AXIS) + ); + #endif return selected; } @@ -71,7 +73,7 @@ void do_enable(const stepper_flags_t to_enable) { if (!shall_enable) return; // All specified axes already enabled? - ena_mask_t also_enabled = 0; // Track steppers enabled due to overlap + ena_mask_t also_enabled = 0; // Track steppers enabled due to overlap // Enable all flagged axes LOOP_NUM_AXES(a) { @@ -212,7 +214,7 @@ void try_to_disable(const stepper_flags_t to_disable) { void GcodeSuite::M18_M84() { if (parser.seenval('S')) { reset_stepper_timeout(); - #if HAS_DISABLE_INACTIVE_AXIS + #if HAS_DISABLE_IDLE_AXES const millis_t ms = parser.value_millis_from_seconds(); #if LASER_SAFETY_TIMEOUT_MS > 0 if (ms && ms <= LASER_SAFETY_TIMEOUT_MS) { diff --git a/Marlin/src/gcode/control/M3-M5.cpp b/Marlin/src/gcode/control/M3-M5.cpp index 5d5d44e8bfe8..ec24cf8a6585 100644 --- a/Marlin/src/gcode/control/M3-M5.cpp +++ b/Marlin/src/gcode/control/M3-M5.cpp @@ -32,21 +32,18 @@ * Laser: * M3 - Laser ON/Power (Ramped power) * M4 - Laser ON/Power (Ramped power) - * M5 - Set power output to 0 (leaving inline mode unchanged). * * M3I - Enable continuous inline power to be processed by the planner, with power * calculated and set in the planner blocks, processed inline during stepping. - * Within inline mode M3 S-Values will set the power for the next moves e.g. G1 X10 Y10 powers on with the last S-Value. + * In inline mode M3 S-Values will set the power for the next moves. + * (e.g., G1 X10 Y10 powers on with the last S-Value.) * M3I must be set before using planner-synced M3 inline S-Values (LASER_POWER_SYNC). * * M4I - Set dynamic mode which calculates laser power OCR based on the current feedrate. * - * M5I - Clear inline mode and set power to 0. - * * Spindle: * M3 - Spindle ON (Clockwise) * M4 - Spindle ON (Counter-clockwise) - * M5 - Spindle OFF * * Parameters: * S - Set power. S0 will turn the spindle/laser off. @@ -92,19 +89,15 @@ void GcodeSuite::M3_M4(const bool is_M4) { #endif auto get_s_power = [] { - float u; if (parser.seenval('S')) { const float v = parser.value_float(); - u = TERN(LASER_POWER_TRAP, v, cutter.power_to_range(v)); + cutter.menuPower = cutter.unitPower = TERN(LASER_POWER_TRAP, v, cutter.power_to_range(v)); } else if (cutter.cutter_mode == CUTTER_MODE_STANDARD) - u = cutter.cpwr_to_upwr(SPEED_POWER_STARTUP); - - cutter.menuPower = cutter.unitPower = u; + cutter.menuPower = cutter.unitPower = cutter.cpwr_to_upwr(SPEED_POWER_STARTUP); // PWM not implied, power converted to OCR from unit definition and on/off if not PWM. - cutter.power = TERN(SPINDLE_LASER_USE_PWM, cutter.upower_to_ocr(u), u > 0 ? 255 : 0); - return u; + cutter.power = TERN(SPINDLE_LASER_USE_PWM, cutter.upower_to_ocr(cutter.unitPower), cutter.unitPower > 0 ? 255 : 0); }; if (cutter.cutter_mode == CUTTER_MODE_CONTINUOUS || cutter.cutter_mode == CUTTER_MODE_DYNAMIC) { // Laser power in inline mode @@ -138,6 +131,13 @@ void GcodeSuite::M3_M4(const bool is_M4) { /** * M5 - Cutter OFF (when moves are complete) + * + * Laser: + * M5 - Set power output to 0 (leaving inline mode unchanged). + * M5I - Clear inline mode and set power to 0. + * + * Spindle: + * M5 - Spindle OFF */ void GcodeSuite::M5() { planner.synchronize(); diff --git a/Marlin/src/gcode/control/M380_M381.cpp b/Marlin/src/gcode/control/M380_M381.cpp index 6bcec891e281..20d24484ed0f 100644 --- a/Marlin/src/gcode/control/M380_M381.cpp +++ b/Marlin/src/gcode/control/M380_M381.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) +#if ANY(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) #include "../gcode.h" #include "../../feature/solenoid.h" diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 1b3a29d10056..13965cb72c22 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -25,7 +25,6 @@ #if ENABLED(DIRECT_PIN_CONTROL) #include "../gcode.h" -#include "../../MarlinCore.h" // for pin_is_protected #if HAS_FAN #include "../../module/temperature.h" @@ -38,12 +37,14 @@ #define OUTPUT_OPEN_DRAIN OUTPUT_OPEN_DRAIN #endif +bool pin_is_protected(const pin_t pin); + void protected_pin_err() { SERIAL_ERROR_MSG(STR_ERR_PROTECTED_PIN); } /** - * M42: Change pin status via GCode + * M42: Change pin status via G-Code * * P Pin number (LED if omitted) * For LPC1768 specify pin P1_02 as M42 P102, @@ -53,6 +54,7 @@ void protected_pin_err() { * I Flag to ignore Marlin's pin protection * * T Pin mode: 0=INPUT 1=OUTPUT 2=INPUT_PULLUP 3=INPUT_PULLDOWN + * 4=INPUT_ANALOG 5=OUTPUT_OPEN_DRAIN */ void GcodeSuite::M42() { const int pin_index = PARSED_PIN_INDEX('P', GET_PIN_MAP_INDEX(LED_PIN)); @@ -86,30 +88,8 @@ void GcodeSuite::M42() { #if HAS_FAN switch (pin) { - #if HAS_FAN0 - case FAN0_PIN: thermalManager.fan_speed[0] = pin_status; return; - #endif - #if HAS_FAN1 - case FAN1_PIN: thermalManager.fan_speed[1] = pin_status; return; - #endif - #if HAS_FAN2 - case FAN2_PIN: thermalManager.fan_speed[2] = pin_status; return; - #endif - #if HAS_FAN3 - case FAN3_PIN: thermalManager.fan_speed[3] = pin_status; return; - #endif - #if HAS_FAN4 - case FAN4_PIN: thermalManager.fan_speed[4] = pin_status; return; - #endif - #if HAS_FAN5 - case FAN5_PIN: thermalManager.fan_speed[5] = pin_status; return; - #endif - #if HAS_FAN6 - case FAN6_PIN: thermalManager.fan_speed[6] = pin_status; return; - #endif - #if HAS_FAN7 - case FAN7_PIN: thermalManager.fan_speed[7] = pin_status; return; - #endif + #define _CASE(N) case FAN##N##_PIN: thermalManager.fan_speed[N] = pin_status; return; + REPEAT(FAN_COUNT, _CASE) } #endif @@ -119,7 +99,7 @@ void GcodeSuite::M42() { } // An OUTPUT_OPEN_DRAIN should not be changed to normal OUTPUT (STM32) - // Use M42 Px M1/5 S0/1 to set the output type and then set value + // Use M42 Px T1/5 S0/1 to set the output type and then set value #ifndef OUTPUT_OPEN_DRAIN pinMode(pin, OUTPUT); #endif diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index a52c706fa6b5..167cdae4a931 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/Marlin/src/gcode/control/M605.cpp @@ -127,25 +127,24 @@ case DXC_MIRRORED_MODE: DEBUG_ECHOPGM("MIRRORED"); break; } DEBUG_ECHOPGM("\nActive Ext: ", active_extruder); - if (!active_extruder_parked) DEBUG_ECHOPGM(" NOT "); - DEBUG_ECHOPGM(" parked."); - DEBUG_ECHOPGM("\nactive_extruder_x_pos: ", current_position.x); - DEBUG_ECHOPGM("\ninactive_extruder_x: ", inactive_extruder_x); - DEBUG_ECHOPGM("\nextruder_duplication_enabled: ", extruder_duplication_enabled); - DEBUG_ECHOPGM("\nduplicate_extruder_x_offset: ", duplicate_extruder_x_offset); - DEBUG_ECHOPGM("\nduplicate_extruder_temp_offset: ", duplicate_extruder_temp_offset); - DEBUG_ECHOPGM("\ndelayed_move_time: ", delayed_move_time); - DEBUG_ECHOPGM("\nX1 Home X: ", x_home_pos(0), "\nX1_MIN_POS=", X1_MIN_POS, "\nX1_MAX_POS=", X1_MAX_POS); - DEBUG_ECHOPGM("\nX2 Home X: ", x_home_pos(1), "\nX2_MIN_POS=", X2_MIN_POS, "\nX2_MAX_POS=", X2_MAX_POS); - DEBUG_ECHOPGM("\nX2_HOME_DIR=", X2_HOME_DIR, "\nX2_HOME_POS=", X2_HOME_POS); - DEBUG_ECHOPGM("\nDEFAULT_DUAL_X_CARRIAGE_MODE=", STRINGIFY(DEFAULT_DUAL_X_CARRIAGE_MODE)); - DEBUG_ECHOPGM("\toolchange_settings.z_raise=", toolchange_settings.z_raise); - DEBUG_ECHOPGM("\nDEFAULT_DUPLICATION_X_OFFSET=", DEFAULT_DUPLICATION_X_OFFSET); - DEBUG_EOL(); + if (!active_extruder_parked) DEBUG_ECHOPGM(" NOT ", F(" parked.")); + DEBUG_ECHOLNPGM( + "\nactive_extruder_x_pos: ", current_position.x, + "\ninactive_extruder_x: ", inactive_extruder_x, + "\nextruder_duplication_enabled: ", extruder_duplication_enabled, + "\nduplicate_extruder_x_offset: ", duplicate_extruder_x_offset, + "\nduplicate_extruder_temp_offset: ", duplicate_extruder_temp_offset, + "\ndelayed_move_time: ", delayed_move_time, + "\nX1 Home: ", x_home_pos(0), " X1_MIN_POS=", X1_MIN_POS, " X1_MAX_POS=", X1_MAX_POS, + "\nX2 Home: ", x_home_pos(1), " X2_MIN_POS=", X2_MIN_POS, " X2_MAX_POS=", X2_MAX_POS, + "\nDEFAULT_DUAL_X_CARRIAGE_MODE=", STRINGIFY(DEFAULT_DUAL_X_CARRIAGE_MODE), + "\toolchange_settings.z_raise=", toolchange_settings.z_raise, + "\nDEFAULT_DUPLICATION_X_OFFSET=", DEFAULT_DUPLICATION_X_OFFSET + ); HOTEND_LOOP() { DEBUG_ECHOPGM_P(SP_T_STR, e); - LOOP_NUM_AXES(a) DEBUG_ECHOPGM(" hotend_offset[", e, "].", AS_CHAR(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]); + LOOP_NUM_AXES(a) DEBUG_ECHOPGM(" hotend_offset[", e, "].", C(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]); DEBUG_EOL(); } DEBUG_EOL(); diff --git a/Marlin/src/gcode/control/M7-M9.cpp b/Marlin/src/gcode/control/M7-M9.cpp index ccde4f552cb9..837bb114b299 100644 --- a/Marlin/src/gcode/control/M7-M9.cpp +++ b/Marlin/src/gcode/control/M7-M9.cpp @@ -37,7 +37,7 @@ } #endif -#if EITHER(COOLANT_FLOOD, AIR_ASSIST) +#if ANY(COOLANT_FLOOD, AIR_ASSIST) #if ENABLED(AIR_ASSIST) #include "../../feature/spindle_laser.h" diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index 90b25e7ed34d..94dd5e3dd93f 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -79,7 +79,7 @@ void GcodeSuite::M81() { print_job_timer.stop(); - #if BOTH(HAS_FAN, PROBING_FANS_OFF) + #if ALL(HAS_FAN, PROBING_FANS_OFF) thermalManager.fans_paused = false; ZERO(thermalManager.saved_fan_speed); #endif diff --git a/Marlin/src/gcode/control/M993_M994.cpp b/Marlin/src/gcode/control/M993_M994.cpp index 598a73fab756..bc634ae13c0d 100644 --- a/Marlin/src/gcode/control/M993_M994.cpp +++ b/Marlin/src/gcode/control/M993_M994.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ALL(SPI_FLASH, SDSUPPORT, MARLIN_DEV_MODE) +#if SPI_FLASH_BACKUP #include "../gcode.h" #include "../../sd/cardreader.h" @@ -85,4 +85,4 @@ void GcodeSuite::M994() { card.closefile(); } -#endif // SPI_FLASH && SDSUPPORT && MARLIN_DEV_MODE +#endif // SPI_FLASH_BACKUP diff --git a/Marlin/src/gcode/control/T.cpp b/Marlin/src/gcode/control/T.cpp index 5e8f6b5436d4..cbe4d26fac15 100644 --- a/Marlin/src/gcode/control/T.cpp +++ b/Marlin/src/gcode/control/T.cpp @@ -23,7 +23,7 @@ #include "../gcode.h" #include "../../module/tool_change.h" -#if EITHER(HAS_MULTI_EXTRUDER, DEBUG_LEVELING_FEATURE) +#if ANY(HAS_MULTI_EXTRUDER, DEBUG_LEVELING_FEATURE) #include "../../module/motion.h" #endif @@ -41,13 +41,21 @@ * S1 Don't move the tool in XY after change * * For PRUSA_MMU2(S) and EXTENDABLE_EMU_MMU2(S) - * T[n] Gcode to extrude at least 38.10 mm at feedrate 19.02 mm/s must follow immediately to load to extruder wheels. - * T? Gcode to extrude shouldn't have to follow. Load to extruder wheels is done automatically. + * T[n] G-code to extrude at least 38.10 mm at feedrate 19.02 mm/s must follow immediately to load to extruder wheels. + * T? G-code to extrude shouldn't have to follow. Load to extruder wheels is done automatically. * Tx Same as T?, but nozzle doesn't have to be preheated. Tc requires a preheated nozzle to finish filament load. * Tc Load to nozzle after filament was prepared by Tc and nozzle is already heated. */ void GcodeSuite::T(const int8_t tool_index) { + #if HAS_MULTI_EXTRUDER + // For 'T' with no parameter report the current tool. + if (parser.string_arg && *parser.string_arg == '*') { + SERIAL_ECHOLNPGM(STR_ACTIVE_EXTRUDER, active_extruder); + return; + } + #endif + DEBUG_SECTION(log_T, "T", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("...(", tool_index, ")"); @@ -63,8 +71,8 @@ void GcodeSuite::T(const int8_t tool_index) { tool_change(tool_index #if HAS_MULTI_EXTRUDER - , TERN(PARKING_EXTRUDER, false, tool_index == active_extruder) // For PARKING_EXTRUDER motion is decided in tool_change() - || parser.boolval('S') + , parser.boolval('S') + || TERN(PARKING_EXTRUDER, false, tool_index == active_extruder) // For PARKING_EXTRUDER motion is decided in tool_change() #endif ); } diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index 8c0da41801cc..ec295f4139cc 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -120,8 +120,7 @@ void GcodeSuite::M900() { EXTRUDER_LOOP() { const bool slot = TEST(lin_adv_slot, e); SERIAL_ECHOLNPGM("Advance T", e, " S", slot, " K", planner.extruder_advance_K[e], - "(S", !slot, " K", other_extruder_advance_K[e], ")"); - SERIAL_EOL(); + "(S", !slot, " K", other_extruder_advance_K[e], ")"); } #endif diff --git a/Marlin/src/gcode/feature/camera/M240.cpp b/Marlin/src/gcode/feature/camera/M240.cpp index cf2e47ef6d2f..bb1d3f9eee31 100644 --- a/Marlin/src/gcode/feature/camera/M240.cpp +++ b/Marlin/src/gcode/feature/camera/M240.cpp @@ -84,7 +84,7 @@ inline void spin_photo_pin() { static constexpr uint32_t sequence[] = PHOTO_PULSES_US; - LOOP_L_N(i, COUNT(sequence)) + for (uint8_t i = 0; i < COUNT(sequence); ++i) pulse_photo_pin(sequence[i], !(i & 1)); } @@ -111,7 +111,7 @@ * B - Y offset to the return position * F - Override the XY movement feedrate * R - Retract/recover length (current units) - * S - Retract/recover feedrate (mm/m) + * S - Retract/recover feedrate (mm/min) * X - Move to X before triggering the shutter * Y - Move to Y before triggering the shutter * Z - Raise Z by a distance before triggering the shutter diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index 9ebe713cde46..8869f8d49462 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -51,7 +51,7 @@ void GcodeSuite::M907() { if (!parser.seen("BS" STR_AXES_LOGICAL)) return M907_report(); - if (parser.seenval('S')) LOOP_L_N(i, MOTOR_CURRENT_COUNT) stepper.set_digipot_current(i, parser.value_int()); + if (parser.seenval('S')) for (uint8_t i = 0; i < MOTOR_CURRENT_COUNT; ++i) stepper.set_digipot_current(i, parser.value_int()); LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) stepper.set_digipot_current(i, parser.value_int()); // X Y Z (I J K U V W) E (map to drivers according to DIGIPOT_CHANNELS. Default with NUM_AXES 3: map X Y Z E to X Y Z E0) // Additional extruders use B,C. // TODO: Change these parameters because 'E' is used and D should be reserved for debugging. B? @@ -82,7 +82,7 @@ void GcodeSuite::M907() { #endif )) return M907_report(); - if (parser.seenval('S')) LOOP_L_N(a, MOTOR_CURRENT_COUNT) stepper.set_digipot_current(a, parser.value_int()); + if (parser.seenval('S')) for (uint8_t a = 0; a < MOTOR_CURRENT_COUNT; ++a) stepper.set_digipot_current(a, parser.value_int()); #if HAS_X_Y_XY_I_J_K_U_V_W if (NUM_AXIS_GANG( @@ -104,7 +104,7 @@ void GcodeSuite::M907() { #if HAS_MOTOR_CURRENT_I2C // this one uses actual amps in floating point - if (parser.seenval('S')) LOOP_L_N(q, DIGIPOT_I2C_NUM_CHANNELS) digipot_i2c.set_current(q, parser.value_float()); + if (parser.seenval('S')) for (uint8_t q = 0; q < DIGIPOT_I2C_NUM_CHANNELS; ++q) digipot_i2c.set_current(q, parser.value_float()); LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) digipot_i2c.set_current(i, parser.value_float()); // X Y Z (I J K U V W) E (map to drivers according to pots adresses. Default with NUM_AXES 3 X Y Z E: map to X Y Z E0) // Additional extruders use B,C,D. // TODO: Change these parameters because 'E' is used and because 'D' should be reserved for debugging. B? diff --git a/Marlin/src/gcode/feature/input_shaping/M593.cpp b/Marlin/src/gcode/feature/input_shaping/M593.cpp index a4b3cd3fee97..1b6a43f9ddb7 100644 --- a/Marlin/src/gcode/feature/input_shaping/M593.cpp +++ b/Marlin/src/gcode/feature/input_shaping/M593.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfig.h" -#if HAS_SHAPING +#if HAS_ZV_SHAPING #include "../../gcode.h" #include "../../../module/stepper.h" diff --git a/Marlin/src/gcode/feature/leds/M150.cpp b/Marlin/src/gcode/feature/leds/M150.cpp index 43062c3f752a..dd5752ee4ceb 100644 --- a/Marlin/src/gcode/feature/leds/M150.cpp +++ b/Marlin/src/gcode/feature/leds/M150.cpp @@ -60,6 +60,7 @@ void GcodeSuite::M150() { #if ENABLED(NEOPIXEL_LED) const pixel_index_t index = parser.intval('I', -1); + const bool seenK = parser.seen_test('K'); #if ENABLED(NEOPIXEL2_SEPARATE) #ifndef NEOPIXEL_M150_DEFAULT #define NEOPIXEL_M150_DEFAULT -1 @@ -69,12 +70,13 @@ void GcodeSuite::M150() { int8_t brightness = neo.brightness(), unit = parser.intval('S', NEOPIXEL_M150_DEFAULT); switch (unit) { case -1: neo2.neoindex = index; // fall-thru - case 0: neo.neoindex = index; old_color = parser.seen('K') ? neo.pixel_color(index >= 0 ? index : 0) : 0; break; - case 1: neo2.neoindex = index; brightness = neo2.brightness(); old_color = parser.seen('K') ? neo2.pixel_color(index >= 0 ? index : 0) : 0; break; + case 0: neo.neoindex = index; old_color = seenK ? neo.pixel_color(_MAX(index, 0)) : 0; break; + case 1: neo2.neoindex = index; brightness = neo2.brightness(); old_color = seenK ? neo2.pixel_color(_MAX(index, 0)) : 0; break; } #else const uint8_t brightness = neo.brightness(); neo.neoindex = index; + old_color = seenK ? neo.pixel_color(_MAX(index, 0)) : 0; #endif #endif diff --git a/Marlin/src/gcode/feature/leds/M7219.cpp b/Marlin/src/gcode/feature/leds/M7219.cpp index 40d3554dfe6e..1f74217be3cb 100644 --- a/Marlin/src/gcode/feature/leds/M7219.cpp +++ b/Marlin/src/gcode/feature/leds/M7219.cpp @@ -79,7 +79,7 @@ void GcodeSuite::M7219() { } if (parser.seen('P')) { - LOOP_L_N(r, MAX7219_LINES) { + for (uint8_t r = 0; r < MAX7219_LINES; ++r) { SERIAL_ECHOPGM("led_line["); if (r < 10) SERIAL_CHAR(' '); SERIAL_ECHO(r); diff --git a/Marlin/src/gcode/feature/mixing/M163-M165.cpp b/Marlin/src/gcode/feature/mixing/M163-M165.cpp index a4cb64e7d62c..f4ea52df0a47 100644 --- a/Marlin/src/gcode/feature/mixing/M163-M165.cpp +++ b/Marlin/src/gcode/feature/mixing/M163-M165.cpp @@ -76,7 +76,7 @@ void GcodeSuite::M164() { * I[factor] Mix factor for extruder stepper 6 */ void GcodeSuite::M165() { - // Get mixing parameters from the GCode + // Get mixing parameters from the G-Code // The total "must" be 1.0 (but it will be normalized) // If no mix factors are given, the old mix is preserved const char mixing_codes[] = { LIST_N(MIXING_STEPPERS, 'A', 'B', 'C', 'D', 'H', 'I') }; diff --git a/Marlin/src/gcode/feature/network/M552-M554.cpp b/Marlin/src/gcode/feature/network/M552-M554.cpp index 0973fb87bf1a..ca7ddd0d360f 100644 --- a/Marlin/src/gcode/feature/network/M552-M554.cpp +++ b/Marlin/src/gcode/feature/network/M552-M554.cpp @@ -46,7 +46,7 @@ void MAC_report() { if (ethernet.hardware_enabled) { Ethernet.MACAddress(mac); SERIAL_ECHOPGM(" MAC: "); - LOOP_L_N(i, 6) { + for (uint8_t i = 0; i < 6; ++i) { if (mac[i] < 16) SERIAL_CHAR('0'); SERIAL_PRINT(mac[i], PrintBase::Hex); if (i < 5) SERIAL_CHAR(':'); @@ -59,7 +59,7 @@ void MAC_report() { // otherwise show the stored values void ip_report(const uint16_t cmd, FSTR_P const post, const IPAddress &ipo) { SERIAL_CHAR('M'); SERIAL_ECHO(cmd); SERIAL_CHAR(' '); - LOOP_L_N(i, 4) { + for (uint8_t i = 0; i < 4; ++i) { SERIAL_ECHO(ipo[i]); if (i < 3) SERIAL_CHAR('.'); } diff --git a/Marlin/src/gcode/feature/pause/G60.cpp b/Marlin/src/gcode/feature/pause/G60.cpp index b32935b341b9..aa74a57596d1 100644 --- a/Marlin/src/gcode/feature/pause/G60.cpp +++ b/Marlin/src/gcode/feature/pause/G60.cpp @@ -50,16 +50,19 @@ void GcodeSuite::G60() { { const xyze_pos_t &pos = stored_position[slot]; DEBUG_ECHOPGM(STR_SAVED_POS " S", slot, " :"); - DEBUG_ECHOLNPGM_P( - LIST_N(DOUBLE(NUM_AXES), - SP_X_LBL, pos.x, SP_Y_LBL, pos.y, SP_Z_LBL, pos.z, - SP_I_LBL, pos.i, SP_J_LBL, pos.j, SP_K_LBL, pos.k, - SP_U_LBL, pos.u, SP_V_LBL, pos.v, SP_W_LBL, pos.w - ) - #if HAS_EXTRUDERS - , SP_E_LBL, pos.e - #endif - ); + #if NUM_AXES + DEBUG_ECHOPGM_P( + LIST_N(DOUBLE(NUM_AXES), + SP_X_LBL, pos.x, SP_Y_LBL, pos.y, SP_Z_LBL, pos.z, + SP_I_LBL, pos.i, SP_J_LBL, pos.j, SP_K_LBL, pos.k, + SP_U_LBL, pos.u, SP_V_LBL, pos.v, SP_W_LBL, pos.w + ) + ); + #endif + #if HAS_EXTRUDERS + DEBUG_ECHOPGM_P(SP_E_LBL, pos.e); + #endif + DEBUG_EOL(); } #endif } diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index 889709c04531..0efcfbf208de 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -71,7 +71,7 @@ void GcodeSuite::G61() { if (!TEST(saved_slots[slot >> 3], slot & 0x07)) return; // Apply any given feedrate over 0.0 - feedRate_t saved_feedrate = feedrate_mm_s; + REMEMBER(saved, feedrate_mm_s); const float fr = parser.linearval('F'); if (fr > 0.0) feedrate_mm_s = MMM_TO_MMS(fr); @@ -101,8 +101,6 @@ void GcodeSuite::G61() { } #endif } - - feedrate_mm_s = saved_feedrate; } #endif // SAVED_POSITIONS diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index 9b18eda4fbae..b8d9d4811bc7 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -88,7 +88,7 @@ void GcodeSuite::M125() { park_point += hotend_offset[active_extruder]; #endif - const bool sd_printing = TERN0(SDSUPPORT, IS_SD_PRINTING()); + const bool sd_printing = TERN0(HAS_MEDIA, IS_SD_PRINTING()); ui.pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT); @@ -96,7 +96,7 @@ void GcodeSuite::M125() { const bool show_lcd = TERN0(HAS_MARLINUI_MENU, parser.boolval('P')); if (pause_print(retract, park_point, show_lcd, 0)) { - if (ENABLED(EXTENSIBLE_UI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) || !sd_printing || show_lcd) { + if (ENABLED(HAS_DISPLAY) || ALL(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) || !sd_printing || show_lcd) { wait_for_confirmation(false, 0); resume_print(0, 0, -retract, 0); } diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index 2afc5c36a09b..d1ebf254c16a 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -199,7 +199,7 @@ void GcodeSuite::M702() { #if HAS_PRUSA_MMU2 mmu2.unload(); #else - #if BOTH(HAS_MULTI_EXTRUDER, FILAMENT_UNLOAD_ALL_EXTRUDERS) + #if ALL(HAS_MULTI_EXTRUDER, FILAMENT_UNLOAD_ALL_EXTRUDERS) if (!parser.seenval('T')) { HOTEND_LOOP() { if (e != active_extruder) tool_change(e); diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index 61786d51ada1..a1765bfb43b4 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -30,6 +30,14 @@ /** * M122: Debug TMC drivers + * + * I - Flag to re-initialize stepper drivers with current settings. + * X, Y, Z, E - Flags to only report the specified axes. + * + * With TMC_DEBUG: + * V - Report raw register data. Refer to the datasheet to decipher the report. + * S - Flag to enable/disable continuous debug reporting. + * P - Interval between continuous debug reports, in milliseconds. */ void GcodeSuite::M122() { xyze_bool_t print_axis = ARRAY_N_1(LOGICAL_AXES, false); diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index e0aa182bf285..50ac5c746871 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -57,10 +57,12 @@ static void set_stealth_status(const bool enable, const int8_t eindex) { LOOP_LOGICAL_AXES(i) if (parser.seen(AXIS_CHAR(i))) { switch (i) { - case X_AXIS: - 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_X_AXIS + case X_AXIS: + 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; + #endif #if HAS_Y_AXIS case Y_AXIS: @@ -198,13 +200,13 @@ void GcodeSuite::M569_report(const bool forReplay/*=true*/) { if (chop_x2 || chop_y2 || chop_z2) { say_M569(forReplay, F("I1")); - if (chop_x2) SERIAL_ECHOPGM_P(SP_X_STR); - #if HAS_Y_AXIS - if (chop_y2) SERIAL_ECHOPGM_P(SP_Y_STR); - #endif - #if HAS_Z_AXIS - if (chop_z2) SERIAL_ECHOPGM_P(SP_Z_STR); - #endif + NUM_AXIS_CODE( + if (chop_x2) SERIAL_ECHOPGM_P(SP_X_STR), + if (chop_y2) SERIAL_ECHOPGM_P(SP_Y_STR), + if (chop_z2) SERIAL_ECHOPGM_P(SP_Z_STR), + NOOP, NOOP, NOOP, + NOOP, NOOP, NOOP + ); SERIAL_EOL(); } diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index b2cab135531c..b949200ad779 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -328,7 +328,6 @@ void GcodeSuite::M906_report(const bool forReplay/*=true*/) { say_M906(forReplay); SERIAL_ECHOLNPGM(" T7 E", stepperE7.getMilliamps()); #endif - SERIAL_EOL(); } #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 0fbf1def6777..fa1cc1227cc2 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -35,7 +35,7 @@ #define M91x_USE(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2208) || AXIS_DRIVER_TYPE(ST, TMC2209) || AXIS_DRIVER_TYPE(ST, TMC2660) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160)) #define M91x_USE_E(N) (E_STEPPERS > N && M91x_USE(E##N)) - #if M91x_USE(X) || M91x_USE(X2) + #if HAS_X_AXIS && (M91x_USE(X) || M91x_USE(X2)) #define M91x_SOME_X 1 #endif #if HAS_Y_AXIS && (M91x_USE(Y) || M91x_USE(Y2)) diff --git a/Marlin/src/gcode/feature/trinamic/M919.cpp b/Marlin/src/gcode/feature/trinamic/M919.cpp index 0e9343f6999d..4ee004291d85 100644 --- a/Marlin/src/gcode/feature/trinamic/M919.cpp +++ b/Marlin/src/gcode/feature/trinamic/M919.cpp @@ -118,7 +118,7 @@ void GcodeSuite::M919() { // 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_CHAR(i)), " has no TMC drivers."); + SERIAL_ECHOLNPGM("?Axis ", C(AXIS_CHAR(i)), " has no TMC drivers."); break; #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index bb859d802641..970707f61dae 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -75,13 +75,13 @@ GcodeSuite gcode; millis_t GcodeSuite::previous_move_ms = 0, GcodeSuite::max_inactive_time = 0; -#if HAS_DISABLE_INACTIVE_AXIS - millis_t GcodeSuite::stepper_inactive_time = SEC_TO_MS(DEFAULT_STEPPER_DEACTIVE_TIME); +#if HAS_DISABLE_IDLE_AXES + millis_t GcodeSuite::stepper_inactive_time = SEC_TO_MS(DEFAULT_STEPPER_TIMEOUT_SEC); #endif // Relative motion mode for each logical axis static constexpr xyze_bool_t ar_init = AXIS_RELATIVE_MODES; -axis_bits_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG( +relative_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG( | (ar_init.e << REL_E), | (ar_init.x << REL_X), | (ar_init.y << REL_Y), @@ -94,7 +94,7 @@ axis_bits_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG( | (ar_init.w << REL_W) ); -#if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) +#if ANY(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) bool GcodeSuite::autoreport_paused; // = false #endif @@ -166,7 +166,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command(const int8_t dval/*=-1*/) { } /** - * Set XYZ...E destination and feedrate from the current GCode command + * Set XYZ...E destination and feedrate from the current G-Code command * * - Set destination from included axis codes * - Set to current for missing axis codes @@ -216,13 +216,13 @@ void GcodeSuite::get_destination_from_command() { TERN_(LASER_FEATURE, cutter.feedrate_mm_m = MMS_TO_MMM(feedrate_mm_s)); } - #if BOTH(PRINTCOUNTER, HAS_EXTRUDERS) + #if ALL(PRINTCOUNTER, HAS_EXTRUDERS) if (!DEBUGGING(DRYRUN) && !skip_move) print_job_timer.incFilamentUsed(destination.e - current_position.e); #endif // Get ABCDHI mixing factors - #if BOTH(MIXING_EXTRUDER, DIRECT_MIXING_IN_G1) + #if ALL(MIXING_EXTRUDER, DIRECT_MIXING_IN_G1) M165(); #endif @@ -454,7 +454,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 61: G61(); break; // G61: Apply/restore saved coordinates. #endif - #if BOTH(PTC_PROBE, PTC_BED) + #if ALL(PTC_PROBE, PTC_BED) case 76: G76(); break; // G76: Calibrate first layer compensation values #endif @@ -472,7 +472,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif #if ENABLED(DEBUG_GCODE_PARSER) - case 800: parser.debug(); break; // G800: GCode Parser Test for G + case 800: parser.debug(); break; // G800: G-Code Parser Test for G #endif default: parser.unknown_command_warning(); break; @@ -496,11 +496,11 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 7: M7(); break; // M7: Coolant Mist ON #endif - #if EITHER(AIR_ASSIST, COOLANT_FLOOD) + #if ANY(AIR_ASSIST, COOLANT_FLOOD) case 8: M8(); break; // M8: Air Assist / Coolant Flood ON #endif - #if EITHER(AIR_ASSIST, COOLANT_CONTROL) + #if ANY(AIR_ASSIST, COOLANT_CONTROL) case 9: M9(); break; // M9: Air Assist / Coolant OFF #endif @@ -519,7 +519,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 17: M17(); break; // M17: Enable all stepper motors - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA case 20: M20(); break; // M20: List SD card case 21: M21(); break; // M21: Init SD card case 22: M22(); break; // M22: Release SD card @@ -540,12 +540,12 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 33: M33(); break; // M33: Get the long full path to a file or folder #endif - #if BOTH(SDCARD_SORT_ALPHA, SDSORT_GCODE) + #if ALL(SDCARD_SORT_ALPHA, SDSORT_GCODE) case 34: M34(); break; // M34: Set SD card sorting options #endif case 928: M928(); break; // M928: Start SD write - #endif // SDSUPPORT + #endif // HAS_MEDIA case 31: M31(); break; // M31: Report time since the start of SD print or last M109 @@ -581,7 +581,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 102: M102(); break; // M102: Configure Bed Distance Sensor #endif - #if HAS_EXTRUDERS + #if HAS_HOTEND case 104: M104(); break; // M104: Set hot end temperature case 109: M109(); break; // M109: Wait for hotend temperature to reach target #endif @@ -640,7 +640,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 154: M154(); break; // M154: Set position auto-report interval #endif - #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) + #if ALL(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) case 155: M155(); break; // M155: Set temperature auto-report interval #endif @@ -671,6 +671,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 82: M82(); break; // M82: Set E axis normal mode (same as other axes) case 83: M83(); break; // M83: Set E axis relative mode #endif + case 18: case 84: M18_M84(); break; // M18/M84: Disable Steppers / Set Timeout case 85: M85(); break; // M85: Set inactivity stepper shutdown timeout case 92: M92(); break; // M92: Set the steps-per-unit for one or more axes @@ -836,7 +837,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 364: if (M364()) return; break; // M364: SCARA Psi pos3 (90 deg to Theta) #endif - #if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) + #if ANY(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) case 380: M380(); break; // M380: Activate solenoid on active (or specified) extruder case 381: M381(); break; // M381: Disable all solenoids or, if MANUAL_SOLENOID_CONTROL, active (or specified) solenoid #endif @@ -915,7 +916,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA case 524: M524(); break; // M524: Abort the current SD print job #endif @@ -933,7 +934,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 575: M575(); break; // M575: Set serial baudrate #endif - #if HAS_SHAPING + #if HAS_ZV_SHAPING case 593: M593(); break; // M593: Set Input Shaping parameters #endif @@ -950,7 +951,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 665: M665(); break; // M665: Set Kinematics parameters #endif - #if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS + #if ANY(DELTA, HAS_EXTRA_ENDSTOPS) case 666: M666(); break; // M666: Set delta or multiple endstop adjustment #endif @@ -991,7 +992,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #if ANY(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_PWM, HAS_MOTOR_CURRENT_I2C, HAS_MOTOR_CURRENT_DAC) case 907: M907(); break; // M907: Set digital trimpot motor current using axis codes. - #if EITHER(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_DAC) + #if ANY(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_DAC) case 908: M908(); break; // M908: Control digital trimpot directly. #if HAS_MOTOR_CURRENT_DAC case 909: M909(); break; // M909: Print digipot/DAC current value @@ -1029,7 +1030,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif #if ENABLED(DEBUG_GCODE_PARSER) - case 800: parser.debug(); break; // M800: GCode Parser Test for M + case 800: parser.debug(); break; // M800: G-Code Parser Test for M #endif #if ENABLED(GCODE_REPEAT_MARKERS) @@ -1057,7 +1058,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 422: M422(); break; // M422: Set Z Stepper automatic alignment position using probe #endif - #if ALL(SPI_FLASH, SDSUPPORT, MARLIN_DEV_MODE) + #if SPI_FLASH_BACKUP case 993: M993(); break; // M993: Backup SPI Flash to SD case 994: M994(); break; // M994: Load a Backup from SD to SPI Flash #endif @@ -1077,7 +1078,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 1000: M1000(); break; // M1000: [INTERNAL] Resume from power-loss #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA case 1001: M1001(); break; // M1001: [INTERNAL] Handle SD completion #endif @@ -1120,7 +1121,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { if (!no_ok) queue.ok_to_send(); - SERIAL_OUT(msgDone); // Call the msgDone serial hook to signal command processing done + SERIAL_IMPL.msgDone(); // Call the msgDone serial hook to signal command processing done } #if ENABLED(M100_FREE_MEMORY_DUMPER) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 5d56e53dd5e0..c3e970ce09ed 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -300,6 +300,7 @@ * M913 - Set HYBRID_THRESHOLD speed. (Requires HYBRID_THRESHOLD) * M914 - Set StallGuard sensitivity. (Requires SENSORLESS_HOMING or SENSORLESS_PROBING) * 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) + * M936 - OTA update firmware. (Requires OTA_FIRMWARE_UPDATE) * 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) @@ -344,14 +345,20 @@ enum AxisRelative : uint8_t { #if HAS_EXTRUDERS , E_MODE_ABS, E_MODE_REL #endif + , NUM_REL_MODES }; +typedef bits_t(NUM_REL_MODES) relative_t; extern const char G28_STR[]; class GcodeSuite { public: - static axis_bits_t axis_relative; + static relative_t axis_relative; + + GcodeSuite() { // Relative motion mode for each logical axis + axis_relative = AxisBits(AXIS_RELATIVE_MODES).bits; + } static bool axis_is_relative(const AxisEnum a) { #if HAS_EXTRUDERS @@ -403,7 +410,7 @@ class GcodeSuite { } FORCE_INLINE static void reset_stepper_timeout(const millis_t ms=millis()) { previous_move_ms = ms; } - #if HAS_DISABLE_INACTIVE_AXIS + #if HAS_DISABLE_IDLE_AXES static millis_t stepper_inactive_time; FORCE_INLINE static bool stepper_inactive_timeout(const millis_t ms=millis()) { return ELAPSED(ms, previous_move_ms + stepper_inactive_time); @@ -435,7 +442,7 @@ class GcodeSuite { process_subcommands_now(keep_leveling ? FPSTR(G28_STR) : TERN(CAN_SET_LEVELING_AFTER_G28, F("G28L0"), FPSTR(G28_STR))); } - #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) + #if ANY(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) static bool autoreport_paused; static bool set_autoreport_paused(const bool p) { const bool was = autoreport_paused; @@ -454,7 +461,7 @@ class GcodeSuite { */ enum MarlinBusyState : char { NOT_BUSY, // Not in a handler - IN_HANDLER, // Processing a GCode + IN_HANDLER, // Processing a G-Code IN_PROCESS, // Known to be blocking command input (as in G29) PAUSED_FOR_USER, // Blocking pending any input PAUSED_FOR_INPUT // Blocking pending text input (concept) @@ -582,7 +589,7 @@ class GcodeSuite { static void G59(); #endif - #if BOTH(PTC_PROBE, PTC_BED) + #if ALL(PTC_PROBE, PTC_BED) static void G76(); #endif @@ -614,11 +621,11 @@ class GcodeSuite { static void M7(); #endif - #if EITHER(AIR_ASSIST, COOLANT_FLOOD) + #if ANY(AIR_ASSIST, COOLANT_FLOOD) static void M8(); #endif - #if EITHER(AIR_ASSIST, COOLANT_CONTROL) + #if ANY(AIR_ASSIST, COOLANT_CONTROL) static void M9(); #endif @@ -639,7 +646,7 @@ class GcodeSuite { static void M18_M84(); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA static void M20(); static void M21(); static void M22(); @@ -655,14 +662,14 @@ class GcodeSuite { static void M31(); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA #if HAS_MEDIA_SUBCALLS static void M32(); #endif #if ENABLED(LONG_FILENAME_HOST_SUPPORT) static void M33(); #endif - #if BOTH(SDCARD_SORT_ALPHA, SDSORT_GCODE) + #if ALL(SDCARD_SORT_ALPHA, SDSORT_GCODE) static void M34(); #endif #endif @@ -713,7 +720,7 @@ class GcodeSuite { static void M102_report(const bool forReplay=true); #endif - #if HAS_EXTRUDERS + #if HAS_HOTEND static void M104_M109(const bool isM109); FORCE_INLINE static void M104() { M104_M109(false); } FORCE_INLINE static void M109() { M104_M109(true); } @@ -811,7 +818,7 @@ class GcodeSuite { static void M154(); #endif - #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) + #if ALL(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) static void M155(); #endif @@ -979,7 +986,7 @@ class GcodeSuite { static bool M364(); #endif - #if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) + #if ANY(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) static void M380(); static void M381(); #endif @@ -1055,7 +1062,7 @@ class GcodeSuite { #endif #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA static void M524(); #endif @@ -1081,7 +1088,7 @@ class GcodeSuite { static void M575(); #endif - #if HAS_SHAPING + #if HAS_ZV_SHAPING static void M593(); static void M593_report(const bool forReplay=true); #endif @@ -1101,7 +1108,7 @@ class GcodeSuite { static void M665_report(const bool forReplay=true); #endif - #if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) + #if ANY(DELTA, HAS_EXTRA_ENDSTOPS) static void M666(); static void M666_report(const bool forReplay=true); #endif @@ -1188,7 +1195,7 @@ class GcodeSuite { static void M910(); #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA static void M928(); #endif @@ -1200,7 +1207,7 @@ class GcodeSuite { static void M995(); #endif - #if BOTH(SPI_FLASH, SDSUPPORT) + #if ALL(SPI_FLASH, HAS_MEDIA) static void M993(); static void M994(); #endif @@ -1222,7 +1229,7 @@ class GcodeSuite { static void M423_report(const bool forReplay=true); #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA static void M1001(); #endif diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index be431eed0d78..28edf9dcdb1e 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -199,7 +199,7 @@ void GcodeSuite::D(const int16_t dcode) { SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset."); } break; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA case 101: { // D101 Test SD Write card.openFileWrite("test.gco"); @@ -250,7 +250,7 @@ void GcodeSuite::D(const int16_t dcode) { card.closefile(); } break; - #endif // SDSUPPORT + #endif // HAS_MEDIA #if ENABLED(POSTMORTEM_DEBUGGING) diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index b36f21d3c08f..dfe4170620ec 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -88,28 +88,28 @@ void GcodeSuite::G92() { case 0: LOOP_LOGICAL_AXES(i) { if (parser.seenval(AXIS_CHAR(i))) { - const float l = parser.value_axis_units((AxisEnum)i), // Given axis coordinate value, converted to millimeters + const float l = parser.value_axis_units((AxisEnum)i), // Given axis coordinate value, converted to millimeters v = TERN0(HAS_EXTRUDERS, i == E_AXIS) ? l : LOGICAL_TO_NATIVE(l, i), // Axis position in NATIVE space (applying the existing offset) - d = v - current_position[i]; // How much is the current axis position altered by? + d = v - current_position[i]; // How much is the current axis position altered by? if (!NEAR_ZERO(d)) { - #if HAS_POSITION_SHIFT && NONE(IS_SCARA, POLARGRAPH) // When using workspaces... + #if HAS_POSITION_SHIFT && NONE(IS_SCARA, POLARGRAPH) // When using workspaces... if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) { - position_shift[i] += d; // ...most axes offset the workspace... + position_shift[i] += d; // ...most axes offset the workspace... update_workspace_offset((AxisEnum)i); } else { #if HAS_EXTRUDERS sync_E = true; - current_position.e = v; // ...but E is set directly + current_position.e = v; // ...but E is set directly #endif } - #else // Without workspaces... + #else // Without workspaces... if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) sync_XYZE = true; else { TERN_(HAS_EXTRUDERS, sync_E = true); } - current_position[i] = v; // ...set Current Position directly (like Marlin 1.0) + current_position[i] = v; // ...set Current Position directly (like Marlin 1.0) #endif } } diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index 494b2115b826..b055f0e20734 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -33,9 +33,7 @@ /** * M206: Set Additional Homing Offset (X Y Z). SCARA aliases T=X, P=Y * - * *** @thinkyhead: I recommend deprecating M206 for SCARA in favor of M665. - * *** M206 for SCARA will remain enabled in 1.1.x for compatibility. - * *** In the 2.0 release, it will simply be disabled by default. + * *** TODO: Deprecate M206 for SCARA in favor of M665. */ void GcodeSuite::M206() { if (!parser.seen_any()) return M206_report(); @@ -91,7 +89,7 @@ void GcodeSuite::M428() { diff[i] = -current_position[i]; if (!WITHIN(diff[i], -20, 20)) { SERIAL_ERROR_MSG(STR_ERR_M428_TOO_FAR); - LCD_ALERTMESSAGE_F("Err: Too far!"); + LCD_ALERTMESSAGE(MSG_ERR_M428_TOO_FAR); ERR_BUZZ(); return; } diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 60359eeecfae..bcc9f817f196 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -30,7 +30,7 @@ void report_all_axis_pos(const xyze_pos_t &pos, const uint8_t n=LOGICAL_AXES, const uint8_t precision=3) { char str[12]; - LOOP_L_N(a, n) { + for (uint8_t a = 0; a < n; ++a) { SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_LBL[a])); if (pos[a] >= 0) SERIAL_CHAR(' '); SERIAL_ECHO(dtostrf(pos[a], 1, precision, str)); @@ -128,9 +128,7 @@ void GcodeSuite::M114() { #if ENABLED(M114_DETAIL) if (parser.seen_test('D')) { - #if DISABLED(M114_LEGACY) - planner.synchronize(); - #endif + IF_DISABLED(M114_LEGACY, planner.synchronize()); report_current_position(); report_current_position_detail(); return; @@ -143,9 +141,7 @@ void GcodeSuite::M114() { #endif #endif - #if ENABLED(M114_REALTIME) - if (parser.seen_test('R')) { report_real_position(); return; } - #endif + TERN_(M114_REALTIME, if (parser.seen_test('R')) return report_real_position()); TERN_(M114_LEGACY, planner.synchronize()); report_current_position_projected(); diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 8ffe0d570051..6d79430e9e8e 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -39,30 +39,27 @@ //#define MINIMAL_CAP_LINES // Don't even mention the disabled capabilities #if ENABLED(EXTENDED_CAPABILITIES_REPORT) - #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); + inline void cap_line(FSTR_P const name, const bool ena=true) { + #if ENABLED(MINIMAL_CAP_LINES) + if (ena) SERIAL_ECHOLNPGM("Cap:", name, ":1"); + #else + SERIAL_ECHOPGM("Cap:", name); SERIAL_CHAR(':', '0' + ena); SERIAL_EOL(); - } - #endif + #endif + } #endif /** * M115: Capabilities string and extended capabilities report * If a capability is not reported, hosts should assume * the capability is not present. + * + * NOTE: Always make sure to add new capabilities to the RepRap Wiki + * at https://reprap.org/wiki/Firmware_Capabilities_Protocol */ void GcodeSuite::M115() { + SERIAL_ECHOPGM("FIRMWARE_NAME:Marlin" " " DETAILED_BUILD_VERSION " (" __DATE__ " " __TIME__ ")" " SOURCE_CODE_URL:" SOURCE_CODE_URL @@ -85,7 +82,7 @@ void GcodeSuite::M115() { // Although this code should work on all STM32 based boards SERIAL_ECHOPGM(" UUID:"); uint32_t *uid_address = (uint32_t*)UID_BASE; - LOOP_L_N(i, 3) { + for (uint8_t i = 0; i < 3; ++i) { const uint32_t UID = uint32_t(READ_REG(*(uid_address))); uid_address += 4U; for (int B = 24; B >= 0; B -= 8) print_hex_byte(UID >> B); @@ -100,10 +97,10 @@ void GcodeSuite::M115() { serial_index_t port = queue.ring_buffer.command_port(); // PAREN_COMMENTS - TERN_(PAREN_COMMENTS, cap_line(F("PAREN_COMMENTS"), true)); + TERN_(PAREN_COMMENTS, cap_line(F("PAREN_COMMENTS"))); // QUOTED_STRINGS - TERN_(GCODE_QUOTED_STRINGS, cap_line(F("QUOTED_STRINGS"), true)); + TERN_(GCODE_QUOTED_STRINGS, cap_line(F("QUOTED_STRINGS"))); // SERIAL_XON_XOFF cap_line(F("SERIAL_XON_XOFF"), ENABLED(SERIAL_XON_XOFF)); @@ -124,10 +121,10 @@ void GcodeSuite::M115() { cap_line(F("AUTOREPORT_TEMP"), ENABLED(AUTO_REPORT_TEMPERATURES)); // PROGRESS (M530 S L, M531 , M532 X L) - cap_line(F("PROGRESS")); + cap_line(F("PROGRESS"), false); // Print Job timer M75, M76, M77 - cap_line(F("PRINT_JOB"), true); + cap_line(F("PRINT_JOB")); // AUTOLEVEL (G29) cap_line(F("AUTOLEVEL"), ENABLED(HAS_AUTOLEVEL)); @@ -153,9 +150,9 @@ void GcodeSuite::M115() { // SPINDLE AND LASER CONTROL (M3, M4, M5) #if ENABLED(SPINDLE_FEATURE) - cap_line(F("SPINDLE"), true); + cap_line(F("SPINDLE")); #elif ENABLED(LASER_FEATURE) - cap_line(F("LASER"), true); + cap_line(F("LASER")); #endif // EMERGENCY_PARSER (M108, M112, M410, M876) @@ -168,10 +165,10 @@ void GcodeSuite::M115() { cap_line(F("PROMPT_SUPPORT"), ENABLED(HOST_PROMPT_SUPPORT)); // SDCARD (M20, M23, M24, etc.) - cap_line(F("SDCARD"), ENABLED(SDSUPPORT)); + cap_line(F("SDCARD"), ENABLED(HAS_MEDIA)); // MULTI_VOLUME (M21 S/M21 U) - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA cap_line(F("MULTI_VOLUME"), ENABLED(MULTI_VOLUME)); #endif @@ -179,7 +176,7 @@ void GcodeSuite::M115() { cap_line(F("REPEAT"), ENABLED(GCODE_REPEAT_MARKERS)); // SD_WRITE (M928, M28, M29) - cap_line(F("SD_WRITE"), ENABLED(SDSUPPORT) && DISABLED(SDCARD_READONLY)); + cap_line(F("SD_WRITE"), ENABLED(HAS_MEDIA) && DISABLED(SDCARD_READONLY)); // AUTOREPORT_SD_STATUS (M27 extension) cap_line(F("AUTOREPORT_SD_STATUS"), ENABLED(AUTO_REPORT_SD_STATUS)); @@ -232,7 +229,7 @@ void GcodeSuite::M115() { const xyz_pos_t lmin = dmin.asLogical(), lmax = dmax.asLogical(), wmin = cmin.asLogical(), wmax = cmax.asLogical(); - SERIAL_ECHOLNPGM( + SERIAL_ECHOPGM( "area:{" "full:{" "min:{" @@ -249,6 +246,8 @@ void GcodeSuite::M115() { ), "}" // max "}," // full + ); + SERIAL_ECHOLNPGM( "work:{" "min:{" LIST_N(DOUBLE(NUM_AXES), diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index b3a95a35aaec..f7da9284411d 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -37,7 +37,7 @@ static void config_prefix(PGM_P const name, PGM_P const pref=nullptr, const int8 SERIAL_ECHOPGM("Config:"); if (pref) SERIAL_ECHOPGM_P(pref); if (ind >= 0) { SERIAL_ECHO(ind); SERIAL_CHAR(':'); } - SERIAL_ECHOPGM_P(name, AS_CHAR(':')); + SERIAL_ECHOPGM_P(name, C(':')); } static void config_line(PGM_P const name, const float val, PGM_P const pref=nullptr, const int8_t ind=-1) { config_prefix(name, pref, ind); @@ -70,7 +70,7 @@ void GcodeSuite::M360() { config_line(F("InputBuffer"), MAX_CMD_SIZE); config_line(F("PrintlineCache"), BUFSIZE); config_line(F("MixingExtruder"), ENABLED(MIXING_EXTRUDER)); - config_line(F("SDCard"), ENABLED(SDSUPPORT)); + config_line(F("SDCard"), ENABLED(HAS_MEDIA)); config_line(F("Fan"), ENABLED(HAS_FAN)); config_line(F("LCD"), ENABLED(HAS_DISPLAY)); config_line(F("SoftwarePowerSwitch"), 1); diff --git a/Marlin/src/gcode/lcd/M145.cpp b/Marlin/src/gcode/lcd/M145.cpp index 942d20afd2f8..d72d5d678989 100644 --- a/Marlin/src/gcode/lcd/M145.cpp +++ b/Marlin/src/gcode/lcd/M145.cpp @@ -62,7 +62,7 @@ void GcodeSuite::M145() { void GcodeSuite::M145_report(const bool forReplay/*=true*/) { report_heading(forReplay, F(STR_MATERIAL_HEATUP)); - LOOP_L_N(i, PREHEAT_COUNT) { + for (uint8_t i = 0; i < PREHEAT_COUNT; ++i) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M145 S"), i diff --git a/Marlin/src/gcode/lcd/M300.cpp b/Marlin/src/gcode/lcd/M300.cpp index 76d4b96b2428..2658b52a7ce4 100644 --- a/Marlin/src/gcode/lcd/M300.cpp +++ b/Marlin/src/gcode/lcd/M300.cpp @@ -30,10 +30,24 @@ #include "../../libs/buzzer.h" // Buzzer, if possible /** - * M300: Play beep sound S P + * M300: Play a Tone / Add a tone to the queue + * + * S - (Hz) The frequency of the tone. 0 for silence. + * P - (ms) The duration of the tone. + * + * With SOUND_MENU_ITEM: + * E<0|1> - Mute or enable sound */ void GcodeSuite::M300() { - uint16_t const frequency = parser.ushortval('S', 260); + + #if ENABLED(SOUND_MENU_ITEM) + if (parser.seen('E')) { + ui.sound_on = parser.value_bool(); + return; + } + #endif + + const uint16_t frequency = parser.ushortval('S', 260); uint16_t duration = parser.ushortval('P', 1000); // Limits the tone duration to 0-5 seconds. diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index cee2f050807e..adbc6e5c0bfa 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -25,7 +25,7 @@ #include "../../MarlinCore.h" -#if BOTH(FWRETRACT, FWRETRACT_AUTORETRACT) +#if ALL(FWRETRACT, FWRETRACT_AUTORETRACT) #include "../../feature/fwretract.h" #endif @@ -87,7 +87,7 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { } #endif - #if BOTH(FWRETRACT, FWRETRACT_AUTORETRACT) + #if ALL(FWRETRACT, FWRETRACT_AUTORETRACT) if (MIN_AUTORETRACT <= MAX_AUTORETRACT) { // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves diff --git a/Marlin/src/gcode/motion/G4.cpp b/Marlin/src/gcode/motion/G4.cpp index ebaa6aabc062..3244c4ea4d51 100644 --- a/Marlin/src/gcode/motion/G4.cpp +++ b/Marlin/src/gcode/motion/G4.cpp @@ -38,7 +38,8 @@ void GcodeSuite::G4() { SERIAL_ECHOLNPGM(STR_Z_MOVE_COMP); #endif - if (!ui.has_status()) LCD_MESSAGE(MSG_DWELL); - - dwell(dwell_ms); + if (dwell_ms) { + if (!ui.has_status()) LCD_MESSAGE(MSG_DWELL); + dwell(dwell_ms); + } } diff --git a/Marlin/src/gcode/control/M400.cpp b/Marlin/src/gcode/motion/M400.cpp similarity index 100% rename from Marlin/src/gcode/control/M400.cpp rename to Marlin/src/gcode/motion/M400.cpp diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index 3fc1fc1625ad..16c3b2d9bd0b 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -21,7 +21,7 @@ */ /** - * parser.cpp - Parser for a GCode line, providing a parameter interface. + * parser.cpp - Parser for a G-Code line, providing a parameter interface. */ #include "parser.h" @@ -66,7 +66,7 @@ uint16_t GCodeParser::codenum; char *GCodeParser::command_args; // start of parameters #endif -// Create a global instance of the GCode parser singleton +// Create a global instance of the G-Code parser singleton GCodeParser parser; /** @@ -108,7 +108,7 @@ void GCodeParser::reset() { /** * Populate the command line state (command_letter, codenum, subcode, and string_arg) - * by parsing a single line of GCode. 58 bytes of SRAM are used to speed up seen/value. + * by parsing a single line of G-Code. 58 bytes of SRAM are used to speed up seen/value. */ void GCodeParser::parse(char *p) { @@ -189,7 +189,13 @@ void GCodeParser::parse(char *p) { #endif // Bail if there's no command code number - if (!TERN(SIGNED_CODENUM, NUMERIC_SIGNED(*p), NUMERIC(*p))) return; + if (!TERN(SIGNED_CODENUM, NUMERIC_SIGNED(*p), NUMERIC(*p))) { + if (TERN0(HAS_MULTI_EXTRUDER, letter == 'T')) { + p[0] = '*'; p[1] = '\0'; string_arg = p; // Convert 'T' alone into 'T*' + command_letter = letter; + } + return; + } // Save the command letter at this point // A '?' signifies an unknown command @@ -229,11 +235,11 @@ void GCodeParser::parse(char *p) { } #endif - } break; + } break; #if ENABLED(GCODE_MOTION_MODES) - #if EITHER(BEZIER_CURVE_SUPPORT, ARC_SUPPORT) + #if ANY(BEZIER_CURVE_SUPPORT, ARC_SUPPORT) case 'I' ... 'J': case 'P': if (TERN1(BEZIER_CURVE_SUPPORT, motion_mode_codenum != 5) && TERN1(ARC_P_CIRCLES, !WITHIN(motion_mode_codenum, 2, 3)) @@ -311,7 +317,7 @@ void GCodeParser::parse(char *p) { #endif #if ENABLED(FASTER_GCODE_PARSER) - // Arguments MUST be uppercase for fast GCode parsing + // Arguments MUST be uppercase for fast G-Code parsing #define PARAM_OK(P) WITHIN((P), 'A', 'Z') #else #define PARAM_OK(P) true @@ -333,7 +339,7 @@ void GCodeParser::parse(char *p) { #if ENABLED(DEBUG_GCODE_PARSER) if (debug) { - SERIAL_ECHOPGM("Got param ", AS_CHAR(param), " at index ", p - command_ptr - 1); + SERIAL_ECHOPGM("Got param ", C(param), " at index ", p - command_ptr - 1); if (has_val) SERIAL_ECHOPGM(" (has_val)"); } #endif diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index c05d6f32c521..94c5b284e06f 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -22,8 +22,8 @@ #pragma once /** - * parser.h - Parser for a GCode line, providing a parameter interface. - * Codes like M149 control the way the GCode parser behaves, + * parser.h - Parser for a G-Code line, providing a parameter interface. + * Codes like M149 control the way the G-Code parser behaves, * so settings for these codes are located in this class. */ @@ -43,7 +43,7 @@ #endif /** - * GCode parser + * G-Code parser * * - Parse a single G-code line for its letter, code, subcode, and parameters * - FASTER_GCODE_PARSER: @@ -68,7 +68,7 @@ class GCodeParser { public: - // Global states for GCode-level units features + // Global states for G-Code-level units features static bool volumetric_enabled; @@ -233,7 +233,7 @@ class GCodeParser { FORCE_INLINE static char* unescape_string(char* &src) { return src; } #endif - // Populate all fields by parsing a single line of GCode + // Populate all fields by parsing a single line of G-Code // This uses 54 bytes of SRAM to speed up seen/value static void parse(char * p); @@ -288,6 +288,17 @@ class GCodeParser { // Bool is true with no value or non-zero static bool value_bool() { return !has_value() || !!value_byte(); } + static constexpr bool axis_is_rotational(const AxisEnum axis) { + return (false + || TERN0(AXIS4_ROTATES, axis == I_AXIS) + || TERN0(AXIS5_ROTATES, axis == J_AXIS) + || TERN0(AXIS6_ROTATES, axis == K_AXIS) + || TERN0(AXIS7_ROTATES, axis == U_AXIS) + || TERN0(AXIS8_ROTATES, axis == V_AXIS) + || TERN0(AXIS9_ROTATES, axis == W_AXIS) + ); + } + // Units modes: Inches, Fahrenheit, Kelvin #if ENABLED(INCH_MODE_SUPPORT) @@ -307,14 +318,7 @@ class GCodeParser { } static float axis_unit_factor(const AxisEnum axis) { - if (false - || TERN0(AXIS4_ROTATES, axis == I_AXIS) - || TERN0(AXIS5_ROTATES, axis == J_AXIS) - || TERN0(AXIS6_ROTATES, axis == K_AXIS) - || TERN0(AXIS7_ROTATES, axis == U_AXIS) - || TERN0(AXIS8_ROTATES, axis == V_AXIS) - || TERN0(AXIS9_ROTATES, axis == W_AXIS) - ) return 1.0f; + if (axis_is_rotational(axis)) return 1.0f; #if HAS_EXTRUDERS if (axis >= E_AXIS && volumetric_enabled) return volumetric_unit_factor; #endif @@ -327,12 +331,12 @@ class GCodeParser { #else - 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 constexpr float mm_to_linear_unit(const_float_t mm) { return mm; } + static constexpr float mm_to_volumetric_unit(const_float_t mm) { return mm; } - 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; } + static constexpr float linear_value_to_mm(const_float_t v) { return v; } + static constexpr float axis_value_to_mm(const AxisEnum, const float v) { return v; } + static constexpr float per_axis_value(const AxisEnum, const float v) { return v; } #endif @@ -402,7 +406,7 @@ class GCodeParser { #else // !TEMPERATURE_UNITS_SUPPORT - static float to_temp_units(int16_t c) { return (float)c; } + static constexpr float to_temp_units(int16_t c) { return (float)c; } static celsius_t value_celsius() { return value_int(); } static celsius_t value_celsius_diff() { return value_int(); } diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index 42a081960d08..df9dc86c62f3 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -39,7 +39,7 @@ #endif /** - * G30: Do a single Z probe at the current XY + * G30: Do a single Z probe at the given XY (default: current) * * Parameters: * @@ -76,7 +76,7 @@ void GcodeSuite::G30() { TERN_(HAS_PTC, ptc.set_enabled(true)); if (!isnan(measured_z)) { SERIAL_ECHOLNPGM("Bed X: ", pos.asLogical().x, " Y: ", pos.asLogical().y, " Z: ", measured_z); - #if EITHER(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) + #if ANY(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) char msg[31], str_1[6], str_2[6], str_3[6]; sprintf_P(msg, PSTR("X:%s, Y:%s, Z:%s"), dtostrf(pos.x, 1, 1, str_1), diff --git a/Marlin/src/gcode/probe/G38.cpp b/Marlin/src/gcode/probe/G38.cpp index 5b138fdaf6dd..1f22cc84ed5c 100644 --- a/Marlin/src/gcode/probe/G38.cpp +++ b/Marlin/src/gcode/probe/G38.cpp @@ -105,6 +105,7 @@ inline bool G38_run_probe() { * G38.5 - Probe away from workpiece, stop on contact break */ void GcodeSuite::G38(const int8_t subcode) { + // Get X Y Z E F get_destination_from_command(); diff --git a/Marlin/src/gcode/probe/M401_M402.cpp b/Marlin/src/gcode/probe/M401_M402.cpp index 33895749193f..8d6e62661b48 100644 --- a/Marlin/src/gcode/probe/M401_M402.cpp +++ b/Marlin/src/gcode/probe/M401_M402.cpp @@ -62,7 +62,9 @@ void GcodeSuite::M401() { */ void GcodeSuite::M402() { probe.stow(); - probe.move_z_after_probing(); + #ifdef Z_AFTER_PROBING + do_z_clearance(Z_AFTER_PROBING); + #endif report_current_position(); } diff --git a/Marlin/src/gcode/probe/M423.cpp b/Marlin/src/gcode/probe/M423.cpp index fde5aaaf87c9..7c82a4f8af30 100644 --- a/Marlin/src/gcode/probe/M423.cpp +++ b/Marlin/src/gcode/probe/M423.cpp @@ -88,7 +88,7 @@ void GcodeSuite::M423() { void GcodeSuite::M423_report(const bool forReplay/*=true*/) { report_heading(forReplay, F("X-Twist Correction")); SERIAL_ECHOLNPGM(" M423 A", xatc.start, " I", xatc.spacing); - LOOP_L_N(x, XATC_MAX_POINTS) { + for (uint8_t x = 0; x < XATC_MAX_POINTS; ++x) { const float z = xatc.z_offset[x]; SERIAL_ECHOPGM(" M423 X", x, " Z"); serial_offset(isnan(z) ? 0 : z); diff --git a/Marlin/src/gcode/probe/M951.cpp b/Marlin/src/gcode/probe/M951.cpp index 7a06400e3336..93feffdce999 100644 --- a/Marlin/src/gcode/probe/M951.cpp +++ b/Marlin/src/gcode/probe/M951.cpp @@ -46,7 +46,7 @@ void mpe_settings_init() { mpe_settings.parking_xpos[0] = pex[0]; // M951 L mpe_settings.parking_xpos[1] = pex[1]; // M951 R mpe_settings.grab_distance = PARKING_EXTRUDER_GRAB_DISTANCE; // M951 I - TERN_(HAS_HOME_OFFSET, set_home_offset(X_AXIS, mpe_settings.grab_distance * -1)); + TERN_(HAS_HOME_OFFSET, set_home_offset(X_AXIS, -mpe_settings.grab_distance)); mpe_settings.slow_feedrate = MMM_TO_MMS(MPE_SLOW_SPEED); // M951 J mpe_settings.fast_feedrate = MMM_TO_MMS(MPE_FAST_SPEED); // M951 H mpe_settings.travel_distance = MPE_TRAVEL_DISTANCE; // M951 D @@ -59,7 +59,7 @@ void GcodeSuite::M951() { if (parser.seenval('R')) mpe_settings.parking_xpos[1] = parser.value_linear_units(); if (parser.seenval('I')) { mpe_settings.grab_distance = parser.value_linear_units(); - TERN_(HAS_HOME_OFFSET, set_home_offset(X_AXIS, mpe_settings.grab_distance * -1)); + TERN_(HAS_HOME_OFFSET, set_home_offset(X_AXIS, -mpe_settings.grab_distance)); } if (parser.seenval('J')) mpe_settings.slow_feedrate = MMM_TO_MMS(parser.value_linear_units()); if (parser.seenval('H')) mpe_settings.fast_feedrate = MMM_TO_MMS(parser.value_linear_units()); diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index c951fc633364..375829e0bc60 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -37,14 +37,6 @@ GCodeQueue queue; #include "../MarlinCore.h" #include "../core/bug_on.h" -#if ENABLED(PRINTER_EVENT_LEDS) - #include "../feature/leds/printer_event_leds.h" -#endif - -#if HAS_ETHERNET - #include "../feature/ethernet.h" -#endif - #if ENABLED(BINARY_FILE_TRANSFER) #include "../feature/binary_stream.h" #endif @@ -99,7 +91,11 @@ PGM_P GCodeQueue::injected_commands_P; // = nullptr */ char GCodeQueue::injected_commands[64]; // = { 0 } -void GCodeQueue::RingBuffer::commit_command(bool skip_ok +/** + * Commit the accumulated G-code command to the ring buffer, + * also setting its origin info. + */ +void GCodeQueue::RingBuffer::commit_command(const bool skip_ok OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind/*=-1*/) ) { commands[index_w].skip_ok = skip_ok; @@ -113,7 +109,7 @@ void GCodeQueue::RingBuffer::commit_command(bool skip_ok * Return true if the command was successfully added. * Return false for a full buffer, or if the 'command' is a comment. */ -bool GCodeQueue::RingBuffer::enqueue(const char *cmd, bool skip_ok/*=true*/ +bool GCodeQueue::RingBuffer::enqueue(const char *cmd, const bool skip_ok/*=true*/ OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind/*=-1*/) ) { if (*cmd == ';' || length >= BUFSIZE) return false; @@ -294,7 +290,7 @@ static bool serial_data_available(serial_index_t index) { #if NO_TIMEOUTS > 0 // Multiserial already handles dispatch to/from multiple ports static bool any_serial_data_available() { - LOOP_L_N(p, NUM_SERIAL) + for (uint8_t p = 0; p < NUM_SERIAL; ++p) if (serial_data_available(p)) return true; return false; @@ -303,6 +299,24 @@ static bool serial_data_available(serial_index_t index) { inline int read_serial(const serial_index_t index) { return SERIAL_IMPL.read(index); } +#if (defined(ARDUINO_ARCH_STM32F4) || defined(ARDUINO_ARCH_STM32)) && defined(USBCON) + + /** + * arduinoststm32's USB receive buffer is not well behaved when the buffer overflows + * + * This can happen when the host programs (such as Pronterface) automatically + * send M105 temperature requests. + */ + void GCodeQueue::flush_rx() { + // Flush receive buffer + for (uint8_t p = 0; p < NUM_SERIAL; ++p) { + if (!serial_data_available(p)) continue; // No data for this port? Skip. + while (SERIAL_IMPL.available(p)) (void)read_serial(p); + } + } + +#endif // (ARDUINO_ARCH_STM32F4 || ARDUINO_ARCH_STM32) && USBCON + void GCodeQueue::gcode_line_error(FSTR_P const ferr, const serial_index_t serial_ind) { PORT_REDIRECT(SERIAL_PORTMASK(serial_ind)); // Reply to the serial port that sent the command SERIAL_ERROR_START(); @@ -423,7 +437,7 @@ void GCodeQueue::get_serial_commands() { // Unless a serial port has data, this will exit on next iteration hadData = false; - LOOP_L_N(p, NUM_SERIAL) { + for (uint8_t p = 0; p < NUM_SERIAL; ++p) { // Check if the queue is full and exit if it is. if (ring_buffer.full()) return; @@ -494,7 +508,7 @@ void GCodeQueue::get_serial_commands() { serial.last_N = gcode_N; } - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA // Pronterface "M29" and "M29 " has no line number else if (card.flag.saving && !is_M29(command)) { gcode_line_error(F(STR_ERR_NO_CHECKSUM), p); @@ -544,7 +558,7 @@ void GCodeQueue::get_serial_commands() { } // queue has space, serial has data } -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA /** * Get lines from the SD Card until the command buffer is full @@ -597,7 +611,7 @@ void GCodeQueue::get_serial_commands() { } } -#endif // SDSUPPORT +#endif // HAS_MEDIA /** * Add to the circular command queue the next command from: @@ -610,7 +624,7 @@ void GCodeQueue::get_available_commands() { get_serial_commands(); - TERN_(SDSUPPORT, get_sdcard_commands()); + TERN_(HAS_MEDIA, get_sdcard_commands()); } /** @@ -649,7 +663,7 @@ void GCodeQueue::advance() { } #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (card.flag.saving) { char * const cmd = ring_buffer.peek_next_command_string(); @@ -685,7 +699,7 @@ void GCodeQueue::advance() { gcode.process_next_command(); - #endif // SDSUPPORT + #endif // HAS_MEDIA // The queue may be reset by a command handler or by code invoked by idle() within a handler ring_buffer.advance_pos(ring_buffer.index_r, -1); @@ -695,8 +709,8 @@ void GCodeQueue::advance() { void GCodeQueue::report_buffer_statistics() { SERIAL_ECHOLNPGM("D576" - " P:", planner.moves_free(), " ", -planner_buffer_underruns, " (", max_planner_buffer_empty_duration, ")" - " B:", BUFSIZE - ring_buffer.length, " ", -command_buffer_underruns, " (", max_command_buffer_empty_duration, ")" + " P:", planner.moves_free(), " ", planner_buffer_underruns, " (", max_planner_buffer_empty_duration, ")" + " B:", BUFSIZE - ring_buffer.length, " ", command_buffer_underruns, " (", max_command_buffer_empty_duration, ")" ); command_buffer_underruns = planner_buffer_underruns = 0; max_command_buffer_empty_duration = max_planner_buffer_empty_duration = 0; diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 142283008001..32be7f2339de 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -35,7 +35,7 @@ class GCodeQueue { */ struct SerialState { /** - * GCode line number handling. Hosts may include line numbers when sending + * G-Code line number handling. Hosts may include line numbers when sending * commands to Marlin, and lines will be checked for sequentiality. * M110 N sets the current line number. */ @@ -48,7 +48,7 @@ class GCodeQueue { static SerialState serial_state[NUM_SERIAL]; //!< Serial states for each serial port /** - * GCode Command Queue + * G-Code Command Queue * A simple (circular) ring buffer of BUFSIZE command strings. * * Commands are copied into this buffer by the command injectors @@ -79,12 +79,12 @@ class GCodeQueue { void advance_pos(uint8_t &p, const int inc) { if (++p >= BUFSIZE) p = 0; length += inc; } - void commit_command(bool skip_ok - OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind = serial_index_t()) + void commit_command(const bool skip_ok + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind=serial_index_t()) ); - bool enqueue(const char *cmd, bool skip_ok = true - OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind = serial_index_t()) + bool enqueue(const char *cmd, const bool skip_ok=true + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind=serial_index_t()) ); void ok_to_send(); @@ -201,6 +201,12 @@ class GCodeQueue { */ static void flush_and_request_resend(const serial_index_t serial_ind); + #if (defined(ARDUINO_ARCH_STM32F4) || defined(ARDUINO_ARCH_STM32)) && defined(USBCON) + static void flush_rx(); + #else + static void flush_rx() {} + #endif + /** * (Re)Set the current line number for the last received command */ @@ -250,7 +256,7 @@ class GCodeQueue { static void get_serial_commands(); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA static void get_sdcard_commands(); #endif diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index 1d1d1a4b7f80..a00ca6122845 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../gcode.h" #include "../../module/planner.h" @@ -34,7 +34,7 @@ #include "../queue.h" #endif -#if EITHER(SET_PROGRESS_MANUALLY, SD_REPRINT_LAST_SELECTED_FILE) +#if ANY(SET_PROGRESS_MANUALLY, SD_REPRINT_LAST_SELECTED_FILE) #include "../../lcd/marlinui.h" #endif @@ -49,8 +49,6 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_LCD_PROUI) - #include "../../lcd/e3v2/proui/dwin.h" #endif #if ENABLED(HOST_ACTION_COMMANDS) @@ -114,4 +112,4 @@ void GcodeSuite::M1001() { TERN_(SD_REPRINT_LAST_SELECTED_FILE, ui.reselect_last_file()); } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/gcode/sd/M20.cpp b/Marlin/src/gcode/sd/M20.cpp index 2a7e0d08df71..9dca2bb3e036 100644 --- a/Marlin/src/gcode/sd/M20.cpp +++ b/Marlin/src/gcode/sd/M20.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../gcode.h" #include "../../sd/cardreader.h" @@ -51,4 +51,4 @@ void GcodeSuite::M20() { SERIAL_ECHO_MSG(STR_NO_MEDIA); } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/gcode/sd/M21_M22.cpp b/Marlin/src/gcode/sd/M21_M22.cpp index aec0de27ca5c..3347168151e7 100644 --- a/Marlin/src/gcode/sd/M21_M22.cpp +++ b/Marlin/src/gcode/sd/M21_M22.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../gcode.h" #include "../../sd/cardreader.h" @@ -52,4 +52,4 @@ void GcodeSuite::M22() { if (!IS_SD_PRINTING()) card.release(); } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/gcode/sd/M23.cpp b/Marlin/src/gcode/sd/M23.cpp index 8722e9b6de95..7727d4958f10 100644 --- a/Marlin/src/gcode/sd/M23.cpp +++ b/Marlin/src/gcode/sd/M23.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../gcode.h" #include "../../sd/cardreader.h" @@ -41,4 +41,4 @@ void GcodeSuite::M23() { TERN_(SET_PROGRESS_PERCENT, ui.set_progress(0)); } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/gcode/sd/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp index 64ac0cce09fd..94fc45c7f951 100644 --- a/Marlin/src/gcode/sd/M24_M25.cpp +++ b/Marlin/src/gcode/sd/M24_M25.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../gcode.h" #include "../../sd/cardreader.h" @@ -70,7 +70,7 @@ void GcodeSuite::M24() { #endif if (card.isFileOpen()) { - card.startOrResumeFilePrinting(); // SD card will now be read for commands + card.startOrResumeFilePrinting(); // SD card will now be read for commands startOrResumeJob(); // Start (or resume) the print job timer TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); } @@ -101,9 +101,7 @@ void GcodeSuite::M25() { #else // Set initial pause flag to prevent more commands from landing in the queue while we try to pause - #if ENABLED(SDSUPPORT) - if (IS_SD_PRINTING()) card.pauseSDPrint(); - #endif + if (IS_SD_PRINTING()) card.pauseSDPrint(); #if ENABLED(POWER_LOSS_RECOVERY) && DISABLED(DGUS_LCD_UI_MKS) if (recovery.enabled) recovery.save(true); @@ -125,4 +123,4 @@ void GcodeSuite::M25() { #endif } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/gcode/sd/M26.cpp b/Marlin/src/gcode/sd/M26.cpp index e0557bfa14fa..9ddc436e8ccd 100644 --- a/Marlin/src/gcode/sd/M26.cpp +++ b/Marlin/src/gcode/sd/M26.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../gcode.h" #include "../../sd/cardreader.h" @@ -35,4 +35,4 @@ void GcodeSuite::M26() { card.setIndex(parser.value_long()); } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/gcode/sd/M27.cpp b/Marlin/src/gcode/sd/M27.cpp index 88238190e259..590efbf79d3f 100644 --- a/Marlin/src/gcode/sd/M27.cpp +++ b/Marlin/src/gcode/sd/M27.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../gcode.h" #include "../../sd/cardreader.h" @@ -49,4 +49,4 @@ void GcodeSuite::M27() { card.report_status(); } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/gcode/sd/M28_M29.cpp b/Marlin/src/gcode/sd/M28_M29.cpp index 373938d99b4b..ac1ba0878870 100644 --- a/Marlin/src/gcode/sd/M28_M29.cpp +++ b/Marlin/src/gcode/sd/M28_M29.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../gcode.h" #include "../../sd/cardreader.h" @@ -69,4 +69,4 @@ void GcodeSuite::M29() { card.flag.saving = false; } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/gcode/sd/M30.cpp b/Marlin/src/gcode/sd/M30.cpp index b95a895f1e92..da8e51bb8be5 100644 --- a/Marlin/src/gcode/sd/M30.cpp +++ b/Marlin/src/gcode/sd/M30.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../gcode.h" #include "../../sd/cardreader.h" @@ -37,4 +37,4 @@ void GcodeSuite::M30() { } } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/gcode/sd/M34.cpp b/Marlin/src/gcode/sd/M34.cpp index 2dd7dc580c93..3a7544292842 100644 --- a/Marlin/src/gcode/sd/M34.cpp +++ b/Marlin/src/gcode/sd/M34.cpp @@ -22,16 +22,26 @@ #include "../../inc/MarlinConfig.h" -#if BOTH(SDCARD_SORT_ALPHA, SDSORT_GCODE) +#if ALL(SDCARD_SORT_ALPHA, SDSORT_GCODE) #include "../gcode.h" #include "../../sd/cardreader.h" /** * M34: Set SD Card Sorting Options + * + * S - Default sorting (i.e., SDSORT_REVERSE) + * S-1 - Reverse alpha sorting + * S0 - FID Order (not always newest) + * S1 - Forward alpha sorting + * S2 - Alias for S-1 [deprecated] + * + * F-1 - Folders above files + * F0 - Sort According to 'S' + * F1 - Folders after files */ void GcodeSuite::M34() { - if (parser.seen('S')) card.setSortOn(parser.value_bool()); + if (parser.seen('S')) card.setSortOn(SortFlag(parser.ushortval('S', TERN(SDSORT_REVERSE, AS_REV, AS_FWD)))); if (parser.seenval('F')) { const int v = parser.value_long(); card.setSortFolders(v < 0 ? -1 : v > 0 ? 1 : 0); diff --git a/Marlin/src/gcode/sd/M524.cpp b/Marlin/src/gcode/sd/M524.cpp index f2b9274223c2..a3c03e90bab6 100644 --- a/Marlin/src/gcode/sd/M524.cpp +++ b/Marlin/src/gcode/sd/M524.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../gcode.h" #include "../../sd/cardreader.h" @@ -51,4 +51,4 @@ void GcodeSuite::M524() { } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/gcode/sd/M928.cpp b/Marlin/src/gcode/sd/M928.cpp index 03a7877a90d0..0d86b330c785 100644 --- a/Marlin/src/gcode/sd/M928.cpp +++ b/Marlin/src/gcode/sd/M928.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../gcode.h" #include "../../sd/cardreader.h" @@ -36,4 +36,4 @@ void GcodeSuite::M928() { } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp index 331ceeb61db1..4df86edc55be 100644 --- a/Marlin/src/gcode/temp/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -28,7 +28,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_EXTRUDERS +#if HAS_HOTEND #include "../gcode.h" #include "../../module/temperature.h" @@ -45,10 +45,6 @@ #endif #endif -#if ENABLED(SINGLENOZZLE_STANDBY_TEMP) - #include "../../module/tool_change.h" -#endif - /** * M104: Set Hotend Temperature target and return immediately * M109: Set Hotend Temperature target and wait @@ -135,4 +131,4 @@ void GcodeSuite::M104_M109(const bool isM109) { (void)thermalManager.wait_for_hotend(target_extruder, no_wait_for_cooling); } -#endif // EXTRUDERS +#endif // HAS_HOTEND diff --git a/Marlin/src/gcode/temp/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp index ae517c977b29..6ba64cd7ba3d 100644 --- a/Marlin/src/gcode/temp/M106_M107.cpp +++ b/Marlin/src/gcode/temp/M106_M107.cpp @@ -85,7 +85,7 @@ void GcodeSuite::M106() { if (!got_preset && parser.seenval('S')) speed = parser.value_ushort(); - TERN_(FOAMCUTTER_XYUV, speed *= 2.55); // Get command in % of max heat + TERN_(FOAMCUTTER_XYUV, speed *= 2.55f); // Get command in % of max heat // Set speed, with constraint thermalManager.set_fan_speed(pfan, speed); diff --git a/Marlin/src/gcode/temp/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp index c5e3c000290c..5f122b53bcbf 100644 --- a/Marlin/src/gcode/temp/M140_M190.cpp +++ b/Marlin/src/gcode/temp/M140_M190.cpp @@ -87,13 +87,15 @@ void GcodeSuite::M140_M190(const bool isM190) { // With PRINTJOB_TIMER_AUTOSTART, M190 can start the timer, and M140 can stop it TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.auto_job_check_timer(isM190, !isM190)); - if (isM190) + if (isM190) { thermalManager.wait_for_bed(no_wait_for_cooling); - else + } + else { ui.set_status_reset_fn([]{ const celsius_t c = thermalManager.degTargetBed(); return c < 30 || thermalManager.degBedNear(c); }); + } } #endif // HAS_HEATED_BED diff --git a/Marlin/src/gcode/temp/M155.cpp b/Marlin/src/gcode/temp/M155.cpp index 48c23986aeb5..4166cd52cacd 100644 --- a/Marlin/src/gcode/temp/M155.cpp +++ b/Marlin/src/gcode/temp/M155.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) +#if ALL(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) #include "../gcode.h" #include "../../module/temperature.h" diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index 820b1556d611..8435cb7624bf 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -25,6 +25,7 @@ #if HAS_PID_HEATING #include "../gcode.h" +#include "../queue.h" // for flush_tx #include "../../lcd/marlinui.h" #include "../../module/temperature.h" @@ -78,7 +79,7 @@ void GcodeSuite::M303() { const celsius_t temp = seenS ? parser.value_celsius() : default_temp; const bool u = parser.boolval('U'); - #if ENABLED(DWIN_LCD_PROUI) && EITHER(PIDTEMP, PIDTEMPBED) + #if ENABLED(DWIN_LCD_PROUI) && ANY(PIDTEMP, PIDTEMPBED) if (seenC) HMI_data.PidCycles = c; if (seenS) { switch (hid) { @@ -89,13 +90,13 @@ void GcodeSuite::M303() { } #endif - #if DISABLED(BUSY_WHILE_HEATING) - KEEPALIVE_STATE(NOT_BUSY); - #endif + IF_DISABLED(BUSY_WHILE_HEATING, KEEPALIVE_STATE(NOT_BUSY)); LCD_MESSAGE(MSG_PID_AUTOTUNE); thermalManager.PID_autotune(temp, hid, c, u); ui.reset_status(); + + queue.flush_rx(); } #endif // HAS_PID_HEATING diff --git a/Marlin/src/gcode/temp/M306.cpp b/Marlin/src/gcode/temp/M306.cpp index c6b700eac3b6..1a137acd9dcc 100644 --- a/Marlin/src/gcode/temp/M306.cpp +++ b/Marlin/src/gcode/temp/M306.cpp @@ -52,15 +52,15 @@ void GcodeSuite::M306() { if (parser.seen("ACFPRH")) { const heater_id_t hid = (heater_id_t)parser.intval('E', 0); - MPC_t &constants = thermalManager.temp_hotend[hid].constants; - if (parser.seenval('P')) constants.heater_power = parser.value_float(); - if (parser.seenval('C')) constants.block_heat_capacity = parser.value_float(); - if (parser.seenval('R')) constants.sensor_responsiveness = parser.value_float(); - if (parser.seenval('A')) constants.ambient_xfer_coeff_fan0 = parser.value_float(); + MPC_t &mpc = thermalManager.temp_hotend[hid].mpc; + if (parser.seenval('P')) mpc.heater_power = parser.value_float(); + if (parser.seenval('C')) mpc.block_heat_capacity = parser.value_float(); + if (parser.seenval('R')) mpc.sensor_responsiveness = parser.value_float(); + if (parser.seenval('A')) mpc.ambient_xfer_coeff_fan0 = parser.value_float(); #if ENABLED(MPC_INCLUDE_FAN) - if (parser.seenval('F')) constants.fan255_adjustment = parser.value_float() - constants.ambient_xfer_coeff_fan0; + if (parser.seenval('F')) mpc.fan255_adjustment = parser.value_float() - mpc.ambient_xfer_coeff_fan0; #endif - if (parser.seenval('H')) constants.filament_heat_capacity_permm = parser.value_float(); + if (parser.seenval('H')) mpc.filament_heat_capacity_permm = parser.value_float(); return; } @@ -71,16 +71,16 @@ void GcodeSuite::M306_report(const bool forReplay/*=true*/) { report_heading(forReplay, F("Model predictive control")); HOTEND_LOOP() { report_echo_start(forReplay); - MPC_t& constants = thermalManager.temp_hotend[e].constants; + MPC_t& mpc = thermalManager.temp_hotend[e].mpc; SERIAL_ECHOPGM(" M306 E", e); - SERIAL_ECHOPAIR_F(" P", constants.heater_power, 2); - SERIAL_ECHOPAIR_F(" C", constants.block_heat_capacity, 2); - SERIAL_ECHOPAIR_F(" R", constants.sensor_responsiveness, 4); - SERIAL_ECHOPAIR_F(" A", constants.ambient_xfer_coeff_fan0, 4); + SERIAL_ECHOPAIR_F(" P", mpc.heater_power, 2); + SERIAL_ECHOPAIR_F(" C", mpc.block_heat_capacity, 2); + SERIAL_ECHOPAIR_F(" R", mpc.sensor_responsiveness, 4); + SERIAL_ECHOPAIR_F(" A", mpc.ambient_xfer_coeff_fan0, 4); #if ENABLED(MPC_INCLUDE_FAN) - SERIAL_ECHOPAIR_F(" F", constants.ambient_xfer_coeff_fan0 + constants.fan255_adjustment, 4); + SERIAL_ECHOPAIR_F(" F", mpc.ambient_xfer_coeff_fan0 + mpc.fan255_adjustment, 4); #endif - SERIAL_ECHOPAIR_F(" H", constants.filament_heat_capacity_permm, 4); + SERIAL_ECHOPAIR_F(" H", mpc.filament_heat_capacity_permm, 4); SERIAL_EOL(); } } diff --git a/Marlin/src/gcode/units/M149.cpp b/Marlin/src/gcode/units/M149.cpp index a04247cbcb17..1906041bf04e 100644 --- a/Marlin/src/gcode/units/M149.cpp +++ b/Marlin/src/gcode/units/M149.cpp @@ -38,7 +38,7 @@ void GcodeSuite::M149() { void GcodeSuite::M149_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, F(STR_TEMPERATURE_UNITS)); - SERIAL_ECHOPGM(" M149 ", AS_CHAR(parser.temp_units_code()), " ; Units in "); + SERIAL_ECHOPGM(" M149 ", C(parser.temp_units_code()), " ; Units in "); SERIAL_ECHOLNF(parser.temp_units_name()); } diff --git a/Marlin/src/inc/Changes.h b/Marlin/src/inc/Changes.h new file mode 100644 index 000000000000..719b5dbd356b --- /dev/null +++ b/Marlin/src/inc/Changes.h @@ -0,0 +1,643 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 + +/** + * Changes.h + * + * Alert about Configuration changes at compile-time. + */ + +/** + * Warnings for old configurations + */ +#ifdef GITHUB_ACTION + // Skip change alerts during CI Test +#elif WATCH_TEMP_PERIOD > 500 + #error "WATCH_TEMP_PERIOD now uses seconds instead of milliseconds." +#elif DISABLED(THERMAL_PROTECTION_HOTENDS) && (defined(WATCH_TEMP_PERIOD) || defined(THERMAL_PROTECTION_PERIOD)) + #error "Thermal Runaway Protection for hotends is now enabled with THERMAL_PROTECTION_HOTENDS." +#elif DISABLED(THERMAL_PROTECTION_BED) && defined(THERMAL_PROTECTION_BED_PERIOD) + #error "Thermal Runaway Protection for the bed is now enabled with THERMAL_PROTECTION_BED." +#elif (CORE_IS_XZ || CORE_IS_YZ) && ENABLED(Z_LATE_ENABLE) + #error "Z_LATE_ENABLE can't be used with COREXZ, COREZX, COREYZ, or COREZY." +#elif defined(X_HOME_RETRACT_MM) + #error "[XYZ]_HOME_RETRACT_MM settings have been renamed [XYZ]_HOME_BUMP_MM." +#elif defined(SDCARDDETECTINVERTED) + #error "SDCARDDETECTINVERTED is now SD_DETECT_STATE (HIGH)." +#elif defined(SD_DETECT_INVERTED) + #error "SD_DETECT_INVERTED is now SD_DETECT_STATE (HIGH)." +#elif defined(BTENABLED) + #error "BTENABLED is now BLUETOOTH." +#elif defined(CUSTOM_MENDEL_NAME) + #error "CUSTOM_MENDEL_NAME is now CUSTOM_MACHINE_NAME." +#elif defined(HAS_AUTOMATIC_VERSIONING) + #error "HAS_AUTOMATIC_VERSIONING is now CUSTOM_VERSION_FILE." +#elif defined(USE_AUTOMATIC_VERSIONING) + #error "USE_AUTOMATIC_VERSIONING is now CUSTOM_VERSION_FILE." +#elif defined(SDSLOW) + #error "SDSLOW deprecated. Set SD_SPI_SPEED to SPI_HALF_SPEED instead." +#elif defined(SDEXTRASLOW) + #error "SDEXTRASLOW deprecated. Set SD_SPI_SPEED to SPI_QUARTER_SPEED instead." +#elif defined(FILAMENT_SENSOR) + #error "FILAMENT_SENSOR is now FILAMENT_WIDTH_SENSOR." +#elif defined(ENDSTOPPULLUP_FIL_RUNOUT) + #error "ENDSTOPPULLUP_FIL_RUNOUT is now FIL_RUNOUT_PULLUP." +#elif defined(DISABLE_MAX_ENDSTOPS) || defined(DISABLE_MIN_ENDSTOPS) + #error "DISABLE_MAX_ENDSTOPS and DISABLE_MIN_ENDSTOPS deprecated. Use individual USE_*_PLUG options instead." +#elif defined(LANGUAGE_INCLUDE) + #error "LANGUAGE_INCLUDE has been replaced by LCD_LANGUAGE." +#elif defined(EXTRUDER_OFFSET_X) || defined(EXTRUDER_OFFSET_Y) + #error "EXTRUDER_OFFSET_[XY] is deprecated. Use HOTEND_OFFSET_[XY] instead." +#elif defined(PID_PARAMS_PER_EXTRUDER) + #error "PID_PARAMS_PER_EXTRUDER is deprecated. Use PID_PARAMS_PER_HOTEND instead." +#elif defined(EXTRUDER_WATTS) || defined(BED_WATTS) + #error "EXTRUDER_WATTS and BED_WATTS are deprecated and should be removed." +#elif defined(SERVO_ENDSTOP_ANGLES) + #error "SERVO_ENDSTOP_ANGLES is deprecated. Use Z_SERVO_ANGLES instead." +#elif defined(X_ENDSTOP_SERVO_NR) || defined(Y_ENDSTOP_SERVO_NR) + #error "X_ENDSTOP_SERVO_NR and Y_ENDSTOP_SERVO_NR are deprecated and should be removed." +#elif defined(Z_ENDSTOP_SERVO_NR) + #error "Z_ENDSTOP_SERVO_NR is now Z_PROBE_SERVO_NR." +#elif defined(DEFAULT_XYJERK) + #error "DEFAULT_XYJERK is deprecated. Use DEFAULT_XJERK and DEFAULT_YJERK instead." +#elif defined(XY_TRAVEL_SPEED) + #error "XY_TRAVEL_SPEED is now XY_PROBE_FEEDRATE." +#elif defined(XY_PROBE_SPEED) + #error "XY_PROBE_SPEED is now XY_PROBE_FEEDRATE." +#elif defined(Z_PROBE_SPEED_FAST) + #error "Z_PROBE_SPEED_FAST is now Z_PROBE_FEEDRATE_FAST." +#elif defined(Z_PROBE_SPEED_SLOW) + #error "Z_PROBE_SPEED_SLOW is now Z_PROBE_FEEDRATE_SLOW." +#elif defined(PROBE_SERVO_DEACTIVATION_DELAY) + #error "PROBE_SERVO_DEACTIVATION_DELAY is deprecated. Use DEACTIVATE_SERVOS_AFTER_MOVE instead." +#elif defined(SERVO_DEACTIVATION_DELAY) + #error "SERVO_DEACTIVATION_DELAY is now SERVO_DELAY." +#elif ENABLED(FILAMENTCHANGEENABLE) + #error "FILAMENTCHANGEENABLE is now ADVANCED_PAUSE_FEATURE." +#elif ENABLED(FILAMENT_CHANGE_FEATURE) + #error "FILAMENT_CHANGE_FEATURE is now ADVANCED_PAUSE_FEATURE." +#elif defined(FILAMENT_CHANGE_X_POS) || defined(FILAMENT_CHANGE_Y_POS) + #error "FILAMENT_CHANGE_[XY]_POS is now set with NOZZLE_PARK_POINT." +#elif defined(FILAMENT_CHANGE_Z_ADD) + #error "FILAMENT_CHANGE_Z_ADD is now set with NOZZLE_PARK_POINT." +#elif defined(FILAMENT_CHANGE_XY_FEEDRATE) + #error "FILAMENT_CHANGE_XY_FEEDRATE is now NOZZLE_PARK_XY_FEEDRATE." +#elif defined(FILAMENT_CHANGE_Z_FEEDRATE) + #error "FILAMENT_CHANGE_Z_FEEDRATE is now NOZZLE_PARK_Z_FEEDRATE." +#elif defined(PAUSE_PARK_X_POS) || defined(PAUSE_PARK_Y_POS) + #error "PAUSE_PARK_[XY]_POS is now set with NOZZLE_PARK_POINT." +#elif defined(PAUSE_PARK_Z_ADD) + #error "PAUSE_PARK_Z_ADD is now set with NOZZLE_PARK_POINT." +#elif defined(PAUSE_PARK_XY_FEEDRATE) + #error "PAUSE_PARK_XY_FEEDRATE is now NOZZLE_PARK_XY_FEEDRATE." +#elif defined(PAUSE_PARK_Z_FEEDRATE) + #error "PAUSE_PARK_Z_FEEDRATE is now NOZZLE_PARK_Z_FEEDRATE." +#elif defined(FILAMENT_CHANGE_RETRACT_FEEDRATE) + #error "FILAMENT_CHANGE_RETRACT_FEEDRATE is now PAUSE_PARK_RETRACT_FEEDRATE." +#elif defined(FILAMENT_CHANGE_RETRACT_LENGTH) + #error "FILAMENT_CHANGE_RETRACT_LENGTH is now PAUSE_PARK_RETRACT_LENGTH." +#elif defined(FILAMENT_CHANGE_EXTRUDE_FEEDRATE) + #error "FILAMENT_CHANGE_EXTRUDE_FEEDRATE is now ADVANCED_PAUSE_PURGE_FEEDRATE." +#elif defined(ADVANCED_PAUSE_EXTRUDE_FEEDRATE) + #error "ADVANCED_PAUSE_EXTRUDE_FEEDRATE is now ADVANCED_PAUSE_PURGE_FEEDRATE." +#elif defined(FILAMENT_CHANGE_EXTRUDE_LENGTH) + #error "FILAMENT_CHANGE_EXTRUDE_LENGTH is now ADVANCED_PAUSE_PURGE_LENGTH." +#elif defined(ADVANCED_PAUSE_EXTRUDE_LENGTH) + #error "ADVANCED_PAUSE_EXTRUDE_LENGTH is now ADVANCED_PAUSE_PURGE_LENGTH." +#elif defined(FILAMENT_CHANGE_NOZZLE_TIMEOUT) + #error "FILAMENT_CHANGE_NOZZLE_TIMEOUT is now PAUSE_PARK_NOZZLE_TIMEOUT." +#elif defined(FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS) + #error "FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS is now FILAMENT_CHANGE_ALERT_BEEPS." +#elif defined(FILAMENT_CHANGE_NO_STEPPER_TIMEOUT) + #error "FILAMENT_CHANGE_NO_STEPPER_TIMEOUT is now PAUSE_PARK_NO_STEPPER_TIMEOUT." +#elif defined(PLA_PREHEAT_HOTEND_TEMP) + #error "PLA_PREHEAT_HOTEND_TEMP is now PREHEAT_1_TEMP_HOTEND." +#elif defined(PLA_PREHEAT_HPB_TEMP) + #error "PLA_PREHEAT_HPB_TEMP is now PREHEAT_1_TEMP_BED." +#elif defined(PLA_PREHEAT_FAN_SPEED) + #error "PLA_PREHEAT_FAN_SPEED is now PREHEAT_1_FAN_SPEED." +#elif defined(ABS_PREHEAT_HOTEND_TEMP) + #error "ABS_PREHEAT_HOTEND_TEMP is now PREHEAT_2_TEMP_HOTEND." +#elif defined(ABS_PREHEAT_HPB_TEMP) + #error "ABS_PREHEAT_HPB_TEMP is now PREHEAT_2_TEMP_BED." +#elif defined(ABS_PREHEAT_FAN_SPEED) + #error "ABS_PREHEAT_FAN_SPEED is now PREHEAT_2_FAN_SPEED." +#elif defined(ENDSTOPS_ONLY_FOR_HOMING) + #error "ENDSTOPS_ONLY_FOR_HOMING is deprecated. Use (disable) ENDSTOPS_ALWAYS_ON_DEFAULT instead." +#elif defined(HOMING_FEEDRATE) + #error "HOMING_FEEDRATE is now set using the HOMING_FEEDRATE_MM_M array instead." +#elif (defined(HOMING_FEEDRATE_XY) || defined(HOMING_FEEDRATE_Z)) && !defined(HOMING_FEEDRATE_MM_M) + #error "HOMING_FEEDRATE_XY and HOMING_FEEDRATE_Z are now set using the HOMING_FEEDRATE_MM_M array instead." +#elif defined(MANUAL_HOME_POSITIONS) + #error "MANUAL_HOME_POSITIONS is deprecated. Set MANUAL_[XYZ]_HOME_POS as-needed instead." +#elif defined(PID_ADD_EXTRUSION_RATE) + #error "PID_ADD_EXTRUSION_RATE is now PID_EXTRUSION_SCALING and is DISABLED by default." +#elif defined(Z_RAISE_BEFORE_HOMING) + #error "Z_RAISE_BEFORE_HOMING is now Z_HOMING_HEIGHT." +#elif defined(MIN_Z_HEIGHT_FOR_HOMING) + #error "MIN_Z_HEIGHT_FOR_HOMING is now Z_HOMING_HEIGHT." +#elif defined(Z_RAISE_BEFORE_PROBING) || defined(Z_RAISE_AFTER_PROBING) + #error "Z_RAISE_(BEFORE|AFTER)_PROBING are deprecated. Use Z_CLEARANCE_DEPLOY_PROBE and Z_AFTER_PROBING instead." +#elif defined(Z_RAISE_PROBE_DEPLOY_STOW) || defined(Z_RAISE_BETWEEN_PROBINGS) + #error "Z_RAISE_PROBE_DEPLOY_STOW and Z_RAISE_BETWEEN_PROBINGS are now Z_CLEARANCE_DEPLOY_PROBE and Z_CLEARANCE_BETWEEN_PROBES." +#elif defined(Z_PROBE_DEPLOY_HEIGHT) || defined(Z_PROBE_TRAVEL_HEIGHT) + #error "Z_PROBE_DEPLOY_HEIGHT and Z_PROBE_TRAVEL_HEIGHT are now Z_CLEARANCE_DEPLOY_PROBE and Z_CLEARANCE_BETWEEN_PROBES." +#elif defined(MANUAL_BED_LEVELING) + #error "MANUAL_BED_LEVELING is now LCD_BED_LEVELING." +#elif defined(MESH_HOME_SEARCH_Z) + #error "MESH_HOME_SEARCH_Z is now LCD_PROBE_Z_RANGE." +#elif defined(MANUAL_PROBE_Z_RANGE) + #error "MANUAL_PROBE_Z_RANGE is now LCD_PROBE_Z_RANGE." +#elif !defined(MIN_STEPS_PER_SEGMENT) + #error "Please replace 'const int dropsegments' with '#define MIN_STEPS_PER_SEGMENT' (and increase by 1)." +#elif MIN_STEPS_PER_SEGMENT <= 0 + #error "MIN_STEPS_PER_SEGMENT must be at least 1." +#elif defined(PREVENT_DANGEROUS_EXTRUDE) + #error "PREVENT_DANGEROUS_EXTRUDE is now PREVENT_COLD_EXTRUSION." +#elif defined(SCARA) + #error "SCARA is now MORGAN_SCARA." +#elif defined(ENABLE_AUTO_BED_LEVELING) + #error "ENABLE_AUTO_BED_LEVELING is deprecated. Specify AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_3POINT." +#elif defined(AUTO_BED_LEVELING_FEATURE) + #error "AUTO_BED_LEVELING_FEATURE is deprecated. Specify AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_3POINT." +#elif defined(ABL_GRID_POINTS) + #error "ABL_GRID_POINTS is now GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y." +#elif defined(ABL_GRID_POINTS_X) || defined(ABL_GRID_POINTS_Y) + #error "ABL_GRID_POINTS_[XY] is now GRID_MAX_POINTS_[XY]." +#elif defined(ABL_GRID_MAX_POINTS_X) || defined(ABL_GRID_MAX_POINTS_Y) + #error "ABL_GRID_MAX_POINTS_[XY] is now GRID_MAX_POINTS_[XY]." +#elif defined(MESH_NUM_X_POINTS) || defined(MESH_NUM_Y_POINTS) + #error "MESH_NUM_[XY]_POINTS is now GRID_MAX_POINTS_[XY]." +#elif defined(UBL_MESH_NUM_X_POINTS) || defined(UBL_MESH_NUM_Y_POINTS) + #error "UBL_MESH_NUM_[XY]_POINTS is now GRID_MAX_POINTS_[XY]." +#elif defined(UBL_G26_MESH_VALIDATION) + #error "UBL_G26_MESH_VALIDATION is now G26_MESH_VALIDATION." +#elif defined(UBL_MESH_EDIT_ENABLED) + #error "UBL_MESH_EDIT_ENABLED is now G26_MESH_VALIDATION." +#elif defined(UBL_MESH_EDITING) + #error "UBL_MESH_EDITING is now G26_MESH_VALIDATION." +#elif defined(BLTOUCH_HEATERS_OFF) + #error "BLTOUCH_HEATERS_OFF is now PROBING_HEATERS_OFF." +#elif defined(BLTOUCH_V3) + #error "BLTOUCH_V3 is obsolete." +#elif defined(BLTOUCH_FORCE_OPEN_DRAIN_MODE) + #error "BLTOUCH_FORCE_OPEN_DRAIN_MODE is obsolete." +#elif defined(BEEPER) + #error "BEEPER is now BEEPER_PIN." +#elif defined(SDCARDDETECT) + #error "SDCARDDETECT is now SD_DETECT_PIN." +#elif defined(STAT_LED_RED) || defined(STAT_LED_BLUE) + #error "STAT_LED_RED/STAT_LED_BLUE are now STAT_LED_RED_PIN/STAT_LED_BLUE_PIN." +#elif defined(LCD_PIN_BL) + #error "LCD_PIN_BL is now LCD_BACKLIGHT_PIN." +#elif defined(LCD_PIN_RESET) + #error "LCD_PIN_RESET is now LCD_RESET_PIN." +#elif defined(EXTRUDER_0_AUTO_FAN_PIN) || defined(EXTRUDER_1_AUTO_FAN_PIN) || defined(EXTRUDER_2_AUTO_FAN_PIN) || defined(EXTRUDER_3_AUTO_FAN_PIN) + #error "EXTRUDER_[0123]_AUTO_FAN_PIN is now E[0123]_AUTO_FAN_PIN." +#elif defined(PID_FAN_SCALING) && !HAS_FAN + #error "PID_FAN_SCALING needs at least one fan enabled." +#elif defined(min_software_endstops) || defined(max_software_endstops) + #error "(min|max)_software_endstops are now (MIN|MAX)_SOFTWARE_ENDSTOPS." +#elif ENABLED(Z_PROBE_SLED) && defined(SLED_PIN) + #error "Replace SLED_PIN with SOL1_PIN (applies to both Z_PROBE_SLED and SOLENOID_PROBE)." +#elif defined(CONTROLLERFAN_PIN) + #error "CONTROLLERFAN_PIN is now CONTROLLER_FAN_PIN, enabled with USE_CONTROLLER_FAN." +#elif defined(CONTROLLERFAN_SPEED) + #error "CONTROLLERFAN_SPEED is now CONTROLLERFAN_SPEED_ACTIVE." +#elif defined(CONTROLLERFAN_SECS) + #error "CONTROLLERFAN_SECS is now CONTROLLERFAN_IDLE_TIME." +#elif defined(MIN_RETRACT) + #error "MIN_RETRACT is now MIN_AUTORETRACT and MAX_AUTORETRACT." +#elif defined(ADVANCE) + #error "ADVANCE is now LIN_ADVANCE." +#elif defined(LIN_ADVANCE_E_D_RATIO) + #error "LIN_ADVANCE (1.5) no longer uses LIN_ADVANCE_E_D_RATIO." +#elif defined(NEOPIXEL_RGBW_LED) + #error "NEOPIXEL_RGBW_LED is now NEOPIXEL_LED." +#elif ENABLED(DELTA) && defined(DELTA_PROBEABLE_RADIUS) + #error "Remove DELTA_PROBEABLE_RADIUS and use PROBING_MARGIN to inset the probe area instead." +#elif ENABLED(DELTA) && defined(DELTA_CALIBRATION_RADIUS) + #error "Remove DELTA_CALIBRATION_RADIUS and use PROBING_MARGIN to inset the probe area instead." +#elif defined(UBL_MESH_INSET) + #error "UBL_MESH_INSET is now just MESH_INSET." +#elif defined(UBL_MESH_MIN_X) || defined(UBL_MESH_MIN_Y) || defined(UBL_MESH_MAX_X) || defined(UBL_MESH_MAX_Y) + #error "UBL_MESH_(MIN|MAX)_[XY] is now just MESH_(MIN|MAX)_[XY]." +#elif defined(ABL_PROBE_PT_1_X) || defined(ABL_PROBE_PT_1_Y) || defined(ABL_PROBE_PT_2_X) || defined(ABL_PROBE_PT_2_Y) || defined(ABL_PROBE_PT_3_X) || defined(ABL_PROBE_PT_3_Y) + #error "ABL_PROBE_PT_[123]_[XY] is no longer required. Please remove it." +#elif defined(UBL_PROBE_PT_1_X) || defined(UBL_PROBE_PT_1_Y) || defined(UBL_PROBE_PT_2_X) || defined(UBL_PROBE_PT_2_Y) || defined(UBL_PROBE_PT_3_X) || defined(UBL_PROBE_PT_3_Y) + #error "UBL_PROBE_PT_[123]_[XY] is no longer required. Please remove it." +#elif defined(MIN_PROBE_EDGE) + #error "MIN_PROBE_EDGE is now called PROBING_MARGIN." +#elif defined(MIN_PROBE_EDGE_LEFT) + #error "MIN_PROBE_EDGE_LEFT is now called PROBING_MARGIN_LEFT." +#elif defined(MIN_PROBE_EDGE_RIGHT) + #error "MIN_PROBE_EDGE_RIGHT is now called PROBING_MARGIN_RIGHT." +#elif defined(MIN_PROBE_EDGE_FRONT) + #error "MIN_PROBE_EDGE_FRONT is now called PROBING_MARGIN_FRONT." +#elif defined(MIN_PROBE_EDGE_BACK) + #error "MIN_PROBE_EDGE_BACK is now called PROBING_MARGIN_BACK." +#elif defined(LEFT_PROBE_BED_POSITION) + #error "LEFT_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_LEFT instead." +#elif defined(RIGHT_PROBE_BED_POSITION) + #error "RIGHT_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_RIGHT instead." +#elif defined(FRONT_PROBE_BED_POSITION) + #error "FRONT_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_FRONT instead." +#elif defined(BACK_PROBE_BED_POSITION) + #error "BACK_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_BACK instead." +#elif defined(ENABLE_MESH_EDIT_GFX_OVERLAY) + #error "ENABLE_MESH_EDIT_GFX_OVERLAY is now MESH_EDIT_GFX_OVERLAY." +#elif defined(BABYSTEP_ZPROBE_GFX_REVERSE) + #error "BABYSTEP_ZPROBE_GFX_REVERSE is now set by OVERLAY_GFX_REVERSE." +#elif defined(UBL_GRANULAR_SEGMENTATION_FOR_CARTESIAN) + #error "UBL_GRANULAR_SEGMENTATION_FOR_CARTESIAN is now SEGMENT_LEVELED_MOVES." +#elif HAS_PID_HEATING && (defined(K1) || !defined(PID_K1)) + #error "K1 is now PID_K1." +#elif defined(PROBE_DOUBLE_TOUCH) + #error "PROBE_DOUBLE_TOUCH is now MULTIPLE_PROBING." +#elif defined(ANET_KEYPAD_LCD) + #error "ANET_KEYPAD_LCD is now ZONESTAR_LCD." +#elif defined(LCD_I2C_SAINSMART_YWROBOT) + #error "LCD_I2C_SAINSMART_YWROBOT is now LCD_SAINSMART_I2C_(1602|2004)." +#elif defined(MEASURED_LOWER_LIMIT) || defined(MEASURED_UPPER_LIMIT) + #error "MEASURED_(UPPER|LOWER)_LIMIT is now FILWIDTH_ERROR_MARGIN." +#elif defined(HAVE_TMCDRIVER) + #error "HAVE_TMCDRIVER is now [AXIS]_DRIVER_TYPE TMC26X." +#elif defined(STEALTHCHOP) + #error "STEALTHCHOP is now STEALTHCHOP_(XY|Z|E)." +#elif defined(HAVE_TMC26X) + #error "HAVE_TMC26X is now [AXIS]_DRIVER_TYPE TMC26X." +#elif defined(HAVE_TMC2130) + #error "HAVE_TMC2130 is now [AXIS]_DRIVER_TYPE TMC2130." +#elif defined(HAVE_TMC2208) + #error "HAVE_TMC2208 is now [AXIS]_DRIVER_TYPE TMC2208." +#elif defined(HAVE_L6470DRIVER) + #error "HAVE_L6470DRIVER is obsolete. L64xx stepper drivers are no longer supported in Marlin." +#elif defined(X_IS_TMC) || defined(X2_IS_TMC) || defined(Y_IS_TMC) || defined(Y2_IS_TMC) || defined(Z_IS_TMC) || defined(Z2_IS_TMC) || defined(Z3_IS_TMC) \ + || defined(E0_IS_TMC) || defined(E1_IS_TMC) || defined(E2_IS_TMC) || defined(E3_IS_TMC) || defined(E4_IS_TMC) || defined(E5_IS_TMC) || defined(E6_IS_TMC) || defined(E7_IS_TMC) + #error "[AXIS]_IS_TMC is now [AXIS]_DRIVER_TYPE TMC26X." +#elif defined(X_IS_TMC26X) || defined(X2_IS_TMC26X) || defined(Y_IS_TMC26X) || defined(Y2_IS_TMC26X) || defined(Z_IS_TMC26X) || defined(Z2_IS_TMC26X) || defined(Z3_IS_TMC26X) \ + || defined(E0_IS_TMC26X) || defined(E1_IS_TMC26X) || defined(E2_IS_TMC26X) || defined(E3_IS_TMC26X) || defined(E4_IS_TMC26X) || defined(E5_IS_TMC26X) || defined(E6_IS_TMC26X) || defined(E7_IS_TMC26X) + #error "[AXIS]_IS_TMC26X is now [AXIS]_DRIVER_TYPE TMC26X." +#elif defined(X_IS_TMC2130) || defined(X2_IS_TMC2130) || defined(Y_IS_TMC2130) || defined(Y2_IS_TMC2130) || defined(Z_IS_TMC2130) || defined(Z2_IS_TMC2130) || defined(Z3_IS_TMC2130) \ + || defined(E0_IS_TMC2130) || defined(E1_IS_TMC2130) || defined(E2_IS_TMC2130) || defined(E3_IS_TMC2130) || defined(E4_IS_TMC2130) || defined(E5_IS_TMC2130) || defined(E6_IS_TMC2130) || defined(E7_IS_TMC2130) + #error "[AXIS]_IS_TMC2130 is now [AXIS]_DRIVER_TYPE TMC2130." +#elif defined(X_IS_TMC2208) || defined(X2_IS_TMC2208) || defined(Y_IS_TMC2208) || defined(Y2_IS_TMC2208) || defined(Z_IS_TMC2208) || defined(Z2_IS_TMC2208) || defined(Z3_IS_TMC2208) \ + || defined(E0_IS_TMC2208) || defined(E1_IS_TMC2208) || defined(E2_IS_TMC2208) || defined(E3_IS_TMC2208) || defined(E4_IS_TMC2208) || defined(E5_IS_TMC2208) || defined(E6_IS_TMC2208) || defined(E7_IS_TMC2208) + #error "[AXIS]_IS_TMC2208 is now [AXIS]_DRIVER_TYPE TMC2208." +#elif defined(AUTOMATIC_CURRENT_CONTROL) + #error "AUTOMATIC_CURRENT_CONTROL is now MONITOR_DRIVER_STATUS." +#elif defined(FILAMENT_CHANGE_LOAD_LENGTH) + #error "FILAMENT_CHANGE_LOAD_LENGTH is now FILAMENT_CHANGE_FAST_LOAD_LENGTH." +#elif defined(LEVEL_CORNERS_INSET) + #error "LEVEL_CORNERS_INSET is now BED_TRAMMING_INSET_LFRB." +#elif defined(BEZIER_JERK_CONTROL) + #error "BEZIER_JERK_CONTROL is now S_CURVE_ACCELERATION." +#elif HAS_JUNCTION_DEVIATION && defined(JUNCTION_DEVIATION_FACTOR) + #error "JUNCTION_DEVIATION_FACTOR is now JUNCTION_DEVIATION_MM." +#elif defined(JUNCTION_ACCELERATION_FACTOR) + #error "JUNCTION_ACCELERATION_FACTOR is obsolete. Delete it from Configuration_adv.h." +#elif defined(JUNCTION_ACCELERATION) + #error "JUNCTION_ACCELERATION is obsolete. Delete it from Configuration_adv.h." +#elif defined(MAX7219_DEBUG_STEPPER_HEAD) + #error "MAX7219_DEBUG_STEPPER_HEAD is now MAX7219_DEBUG_PLANNER_HEAD." +#elif defined(MAX7219_DEBUG_STEPPER_TAIL) + #error "MAX7219_DEBUG_STEPPER_TAIL is now MAX7219_DEBUG_PLANNER_TAIL." +#elif defined(MAX7219_DEBUG_STEPPER_QUEUE) + #error "MAX7219_DEBUG_STEPPER_QUEUE is now MAX7219_DEBUG_PLANNER_QUEUE." +#elif defined(ENDSTOP_NOISE_FILTER) + #error "ENDSTOP_NOISE_FILTER is now ENDSTOP_NOISE_THRESHOLD [2-7]." +#elif defined(RETRACT_ZLIFT) + #error "RETRACT_ZLIFT is now RETRACT_ZRAISE." +#elif defined(TOOLCHANGE_FS_INIT_BEFORE_SWAP) + #error "TOOLCHANGE_FS_INIT_BEFORE_SWAP is now TOOLCHANGE_FS_SLOW_FIRST_PRIME." +#elif defined(TOOLCHANGE_PARK_ZLIFT) || defined(TOOLCHANGE_UNPARK_ZLIFT) + #error "TOOLCHANGE_PARK_ZLIFT and TOOLCHANGE_UNPARK_ZLIFT are now TOOLCHANGE_ZRAISE." +#elif defined(SINGLENOZZLE_TOOLCHANGE_ZRAISE) + #error "SINGLENOZZLE_TOOLCHANGE_ZRAISE is now TOOLCHANGE_ZRAISE." +#elif defined(SINGLENOZZLE_SWAP_LENGTH) + #error "SINGLENOZZLE_SWAP_LENGTH is now TOOLCHANGE_FIL_SWAP_LENGTH." +#elif defined(SINGLENOZZLE_SWAP_RETRACT_SPEED) + #error "SINGLENOZZLE_SWAP_RETRACT_SPEED is now TOOLCHANGE_FIL_SWAP_RETRACT_SPEED." +#elif defined(SINGLENOZZLE_SWAP_PRIME_SPEED) + #error "SINGLENOZZLE_SWAP_PRIME_SPEED is now TOOLCHANGE_FIL_SWAP_PRIME_SPEED." +#elif defined(SINGLENOZZLE_SWAP_PARK) + #error "SINGLENOZZLE_SWAP_PARK is now TOOLCHANGE_PARK." +#elif defined(SINGLENOZZLE_TOOLCHANGE_XY) + #error "SINGLENOZZLE_TOOLCHANGE_XY is now TOOLCHANGE_PARK_XY." +#elif defined(SINGLENOZZLE_PARK_XY_FEEDRATE) + #error "SINGLENOZZLE_PARK_XY_FEEDRATE is now TOOLCHANGE_PARK_XY_FEEDRATE." +#elif defined(PARKING_EXTRUDER_SECURITY_RAISE) + #error "PARKING_EXTRUDER_SECURITY_RAISE is now TOOLCHANGE_ZRAISE." +#elif defined(SWITCHING_TOOLHEAD_SECURITY_RAISE) + #error "SWITCHING_TOOLHEAD_SECURITY_RAISE is now TOOLCHANGE_ZRAISE." +#elif defined(G0_FEEDRATE) && G0_FEEDRATE == 0 + #error "G0_FEEDRATE is now used to set the G0 feedrate." +#elif defined(MBL_Z_STEP) + #error "MBL_Z_STEP is now MESH_EDIT_Z_STEP." +#elif defined(CHDK) + #error "CHDK is now CHDK_PIN." +#elif ANY_PIN( \ + MAX6675_SS, MAX6675_SS2, MAX6675_SS3, MAX6675_CS, MAX6675_CS2, MAX6675_CS3,\ + MAX31855_SS, MAX31855_SS2, MAX31855_SS3, MAX31855_CS, MAX31855_CS2, MAX31855_CS3, \ + MAX31865_SS, MAX31865_SS2, MAX31865_SS3, MAX31865_CS, MAX31865_CS2, MAX31865_CS3) + #warning "MAX*_SS_PIN, MAX*_SS2_PIN, MAX*_SS3_PIN, MAX*_CS_PIN, MAX*_CS2_PIN, and MAX*_CS3_PIN, are obsolete. Please use TEMP_0_CS_PIN/TEMP_1_CS_PIN/TEMP_2_CS_PIN instead." +#elif ANY_PIN(MAX6675_SCK, MAX31855_SCK, MAX31865_SCK) + #warning "MAX*_SCK_PIN is obsolete. Please use TEMP_0_SCK_PIN/TEMP_1_SCK_PIN/TEMP_2_SCK_PIN instead." +#elif ANY_PIN(MAX6675_MISO, MAX6675_DO, MAX31855_MISO, MAX31855_DO, MAX31865_MISO, MAX31865_DO) + #warning "MAX*_MISO_PIN and MAX*_DO_PIN are obsolete. Please use TEMP_0_MISO_PIN/TEMP_1_MISO_PIN/TEMP_2_MISO_PIN instead." +#elif PIN_EXISTS(MAX31865_MOSI) + #warning "MAX31865_MOSI_PIN is obsolete. Please use TEMP_0_MOSI_PIN/TEMP_1_MOSI_PIN/TEMP_2_MOSI_PIN instead." +#elif ANY_PIN(THERMO_CS1_PIN, THERMO_CS2_PIN, THERMO_CS3_PIN, THERMO_DO_PIN, THERMO_SCK_PIN) + #error "THERMO_*_PIN is now TEMP_n_CS_PIN, TEMP_n_SCK_PIN, TEMP_n_MOSI_PIN, TEMP_n_MISO_PIN." +#elif defined(MAX31865_SENSOR_OHMS) + #error "MAX31865_SENSOR_OHMS is now MAX31865_SENSOR_OHMS_0." +#elif defined(MAX31865_CALIBRATION_OHMS) + #error "MAX31865_CALIBRATION_OHMS is now MAX31865_CALIBRATION_OHMS_0." +#elif defined(SPINDLE_LASER_ENABLE) + #error "SPINDLE_LASER_ENABLE is now SPINDLE_FEATURE or LASER_FEATURE." +#elif defined(SPINDLE_LASER_ENABLE_PIN) + #error "SPINDLE_LASER_ENABLE_PIN is now SPINDLE_LASER_ENA_PIN." +#elif defined(SPINDLE_DIR_CHANGE) + #error "SPINDLE_DIR_CHANGE is now SPINDLE_CHANGE_DIR." +#elif defined(SPINDLE_STOP_ON_DIR_CHANGE) + #error "SPINDLE_STOP_ON_DIR_CHANGE is now SPINDLE_CHANGE_DIR_STOP." +#elif defined(SPINDLE_LASER_ACTIVE_HIGH) + #error "SPINDLE_LASER_ACTIVE_HIGH is now SPINDLE_LASER_ACTIVE_STATE." +#elif defined(SPINDLE_LASER_ENABLE_INVERT) + #error "SPINDLE_LASER_ENABLE_INVERT is now SPINDLE_LASER_ACTIVE_STATE." +#elif defined(LASER_POWER_INLINE) + #error "LASER_POWER_INLINE is not required, inline mode is enabled with 'M3 I' and disabled with 'M5 I'." +#elif defined(LASER_POWER_INLINE_TRAPEZOID) + #error "LASER_POWER_INLINE_TRAPEZOID is now LASER_POWER_TRAP." +#elif defined(LASER_POWER_INLINE_TRAPEZOID_CONT) + #error "LASER_POWER_INLINE_TRAPEZOID_CONT is replaced with LASER_POWER_TRAP." +#elif defined(LASER_POWER_INLINE_TRAPEZOID_PER) + #error "LASER_POWER_INLINE_TRAPEZOID_CONT_PER replaced with LASER_POWER_TRAP." +#elif defined(LASER_POWER_INLINE_CONTINUOUS) + #error "LASER_POWER_INLINE_CONTINUOUS is not required, inline mode is enabled with 'M3 I' and disabled with 'M5 I'." +#elif defined(CUTTER_POWER_DISPLAY) + #error "CUTTER_POWER_DISPLAY is now CUTTER_POWER_UNIT." +#elif defined(CHAMBER_HEATER_PIN) + #error "CHAMBER_HEATER_PIN is now HEATER_CHAMBER_PIN." +#elif defined(TMC_Z_CALIBRATION) + #error "TMC_Z_CALIBRATION has been deprecated in favor of MECHANICAL_GANTRY_CALIBRATION." +#elif defined(Z_MIN_PROBE_ENDSTOP) + #error "Z_MIN_PROBE_ENDSTOP is no longer required. Please remove it." +#elif defined(DUAL_NOZZLE_DUPLICATION_MODE) + #error "DUAL_NOZZLE_DUPLICATION_MODE is now MULTI_NOZZLE_DUPLICATION." +#elif defined(MENU_ITEM_CASE_LIGHT) + #error "MENU_ITEM_CASE_LIGHT is now CASE_LIGHT_MENU." +#elif defined(CASE_LIGHT_NEOPIXEL_COLOR) + #error "CASE_LIGHT_NEOPIXEL_COLOR is now CASE_LIGHT_DEFAULT_COLOR." +#elif defined(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) + #error "ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED is now SD_ABORT_ON_ENDSTOP_HIT." +#elif defined(LPC_SD_LCD) || defined(LPC_SD_ONBOARD) || defined(LPC_SD_CUSTOM_CABLE) + #error "LPC_SD_(LCD|ONBOARD|CUSTOM_CABLE) are now SDCARD_CONNECTION." +#elif defined(USB_SD_DISABLED) + #error "USB_SD_DISABLED is now NO_SD_HOST_DRIVE." +#elif defined(USB_SD_ONBOARD) + #error "USB_SD_ONBOARD is obsolete. Disable NO_SD_HOST_DRIVE instead." +#elif defined(PSU_ACTIVE_HIGH) + #error "PSU_ACTIVE_HIGH is now PSU_ACTIVE_STATE." +#elif POWER_SUPPLY == 1 + #error "Replace POWER_SUPPLY 1 by enabling PSU_CONTROL and setting PSU_ACTIVE_STATE to 'LOW'." +#elif POWER_SUPPLY == 2 + #error "Replace POWER_SUPPLY 2 by enabling PSU_CONTROL and setting PSU_ACTIVE_STATE to 'HIGH'." +#elif defined(POWER_SUPPLY) + #error "POWER_SUPPLY is now obsolete. Please remove it." +#elif defined(MKS_ROBIN_TFT) + #error "MKS_ROBIN_TFT is now FSMC_GRAPHICAL_TFT." +#elif defined(SDPOWER) + #error "SDPOWER is now SDPOWER_PIN." +#elif defined(STRING_SPLASH_LINE1) || defined(STRING_SPLASH_LINE2) + #error "STRING_SPLASH_LINE[12] are now obsolete. Please remove them." +#elif defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_X) || defined(Z_PROBE_ALLEN_KEY_STOW_1_X) + #error "Z_PROBE_ALLEN_KEY_(DEPLOY|STOW) coordinates are now a single setting." +#elif defined(X_PROBE_OFFSET_FROM_EXTRUDER) || defined(Y_PROBE_OFFSET_FROM_EXTRUDER) || defined(Z_PROBE_OFFSET_FROM_EXTRUDER) + #error "[XYZ]_PROBE_OFFSET_FROM_EXTRUDER is now NOZZLE_TO_PROBE_OFFSET." +#elif defined(MIN_PROBE_X) || defined(MIN_PROBE_Y) || defined(MAX_PROBE_X) || defined(MAX_PROBE_Y) + #error "(MIN|MAX)_PROBE_[XY] are now calculated at runtime. Please remove them." +#elif defined(Z_STEPPER_ALIGN_X) || defined(Z_STEPPER_ALIGN_X) + #error "Z_STEPPER_ALIGN_X and Z_STEPPER_ALIGN_Y are now combined as Z_STEPPER_ALIGN_XY." +#elif defined(JUNCTION_DEVIATION) + #error "JUNCTION_DEVIATION is no longer required. (See CLASSIC_JERK). Please remove it." +#elif defined(BABYSTEP_MULTIPLICATOR) + #error "BABYSTEP_MULTIPLICATOR is now BABYSTEP_MULTIPLICATOR_[XY|Z]." +#elif defined(LULZBOT_TOUCH_UI) + #error "LULZBOT_TOUCH_UI is now TOUCH_UI_FTDI_EVE." +#elif defined(PS_DEFAULT_OFF) + #error "PS_DEFAULT_OFF is now PSU_DEFAULT_OFF." +#elif defined(FILAMENT_UNLOAD_RETRACT_LENGTH) + #error "FILAMENT_UNLOAD_RETRACT_LENGTH is now FILAMENT_UNLOAD_PURGE_RETRACT." +#elif defined(FILAMENT_UNLOAD_DELAY) + #error "FILAMENT_UNLOAD_DELAY is now FILAMENT_UNLOAD_PURGE_DELAY." +#elif defined(HOME_USING_SPREADCYCLE) + #error "HOME_USING_SPREADCYCLE is now obsolete. Please remove it." +#elif defined(DGUS_LCD) + #error "DGUS_LCD is now DGUS_LCD_UI ORIGIN|FYSETC|HIPRECY)." +#elif defined(DGUS_SERIAL_PORT) + #error "DGUS_SERIAL_PORT is now LCD_SERIAL_PORT." +#elif defined(DGUS_BAUDRATE) + #error "DGUS_BAUDRATE is now LCD_BAUDRATE." +#elif defined(DGUS_STATS_RX_BUFFER_OVERRUNS) + #error "DGUS_STATS_RX_BUFFER_OVERRUNS is now STATS_RX_BUFFER_OVERRUNS." +#elif defined(ANYCUBIC_LCD_SERIAL_PORT) + #error "ANYCUBIC_LCD_SERIAL_PORT is now LCD_SERIAL_PORT." +#elif defined(INTERNAL_SERIAL_PORT) + #error "INTERNAL_SERIAL_PORT is now MMU2_SERIAL_PORT." +#elif defined(X_DUAL_ENDSTOPS_ADJUSTMENT) || defined(Y_DUAL_ENDSTOPS_ADJUSTMENT) || defined(Z_DUAL_ENDSTOPS_ADJUSTMENT) + #error "[XYZ]_DUAL_ENDSTOPS_ADJUSTMENT is now [XYZ]2_ENDSTOP_ADJUSTMENT." +#elif defined(Z_TRIPLE_ENDSTOPS_ADJUSTMENT2) || defined(Z_TRIPLE_ENDSTOPS_ADJUSTMENT3) + #error "Z_TRIPLE_ENDSTOPS_ADJUSTMENT[23] is now Z[23]_ENDSTOP_ADJUSTMENT." +#elif defined(Z_QUAD_ENDSTOPS_ADJUSTMENT2) || defined(Z_QUAD_ENDSTOPS_ADJUSTMENT3) || defined(Z_QUAD_ENDSTOPS_ADJUSTMENT4) + #error "Z_QUAD_ENDSTOPS_ADJUSTMENT[234] is now Z[234]_ENDSTOP_ADJUSTMENT." +#elif defined(Z_DUAL_STEPPER_DRIVERS) + #error "Z_DUAL_STEPPER_DRIVERS is no longer needed and should be removed." +#elif defined(Z_TRIPLE_STEPPER_DRIVERS) + #error "Z_TRIPLE_STEPPER_DRIVERS is no longer needed and should be removed." +#elif defined(Z_QUAD_STEPPER_DRIVERS) + #error "Z_QUAD_STEPPER_DRIVERS is no longer needed and should be removed." +#elif defined(Z_DUAL_ENDSTOPS) || defined(Z_TRIPLE_ENDSTOPS) || defined(Z_QUAD_ENDSTOPS) + #error "Z_(DUAL|TRIPLE|QUAD)_ENDSTOPS is now Z_MULTI_ENDSTOPS." +#elif defined(DUGS_UI_MOVE_DIS_OPTION) + #error "DUGS_UI_MOVE_DIS_OPTION is spelled DGUS_UI_MOVE_DIS_OPTION." +#elif defined(ORIG_E0_AUTO_FAN_PIN) || defined(ORIG_E1_AUTO_FAN_PIN) || defined(ORIG_E2_AUTO_FAN_PIN) || defined(ORIG_E3_AUTO_FAN_PIN) || defined(ORIG_E4_AUTO_FAN_PIN) || defined(ORIG_E5_AUTO_FAN_PIN) || defined(ORIG_E6_AUTO_FAN_PIN) || defined(ORIG_E7_AUTO_FAN_PIN) + #error "ORIG_Ex_AUTO_FAN_PIN is now just Ex_AUTO_FAN_PIN." +#elif defined(ORIG_CHAMBER_AUTO_FAN_PIN) + #error "ORIG_CHAMBER_AUTO_FAN_PIN is now just CHAMBER_AUTO_FAN_PIN." +#elif defined(HOMING_BACKOFF_MM) + #error "HOMING_BACKOFF_MM is now HOMING_BACKOFF_POST_MM." +#elif defined(X_HOME_BUMP_MM) || defined(Y_HOME_BUMP_MM) || defined(Z_HOME_BUMP_MM) + #error "[XYZ]_HOME_BUMP_MM is now HOMING_BUMP_MM." +#elif defined(DIGIPOT_I2C) + #error "DIGIPOT_I2C is now DIGIPOT_MCP4451 (or DIGIPOT_MCP4018)." +#elif defined(TOUCH_BUTTONS) + #error "TOUCH_BUTTONS is now TOUCH_SCREEN." +#elif defined(LCD_FULL_PIXEL_HEIGHT) || defined(LCD_FULL_PIXEL_WIDTH) + #error "LCD_FULL_PIXEL_(WIDTH|HEIGHT) is deprecated and should be removed." +#elif defined(FSMC_UPSCALE) + #error "FSMC_UPSCALE is now GRAPHICAL_TFT_UPSCALE." +#elif defined(ANYCUBIC_TFT_MODEL) + #error "ANYCUBIC_TFT_MODEL is now ANYCUBIC_LCD_I3MEGA." +#elif defined(EVENT_GCODE_SD_STOP) + #error "EVENT_GCODE_SD_STOP is now EVENT_GCODE_SD_ABORT." +#elif defined(GRAPHICAL_TFT_ROTATE_180) + #error "GRAPHICAL_TFT_ROTATE_180 is now TFT_ROTATION set to TFT_ROTATE_180." +#elif defined(PROBE_OFFSET_START) + #error "PROBE_OFFSET_START is now PROBE_OFFSET_WIZARD_START_Z." +#elif defined(POWER_LOSS_PULL) + #error "POWER_LOSS_PULL is now specifically POWER_LOSS_PULL(UP|DOWN)." +#elif defined(SHORT_MANUAL_Z_MOVE) + #error "SHORT_MANUAL_Z_MOVE is now FINE_MANUAL_MOVE, applying to Z on most printers." +#elif defined(FIL_RUNOUT_INVERTING) + #if FIL_RUNOUT_INVERTING + #error "FIL_RUNOUT_INVERTING true is now FIL_RUNOUT_STATE HIGH." + #else + #error "FIL_RUNOUT_INVERTING false is now FIL_RUNOUT_STATE LOW." + #endif +#elif defined(ASSISTED_TRAMMING_MENU_ITEM) + #error "ASSISTED_TRAMMING_MENU_ITEM is deprecated and should be removed." +#elif defined(UNKNOWN_Z_NO_RAISE) + #error "UNKNOWN_Z_NO_RAISE is replaced by setting Z_IDLE_HEIGHT to Z_MAX_POS." +#elif defined(Z_AFTER_DEACTIVATE) + #error "Z_AFTER_DEACTIVATE is replaced by Z_IDLE_HEIGHT." +#elif defined(MEATPACK) + #error "MEATPACK is now enabled with MEATPACK_ON_SERIAL_PORT_1, MEATPACK_ON_SERIAL_PORT_2, etc." +#elif defined(CUSTOM_USER_MENUS) + #error "CUSTOM_USER_MENUS has been replaced by CUSTOM_MENU_MAIN and CUSTOM_MENU_CONFIG." +#elif defined(MKS_LCD12864) + #error "MKS_LCD12864 is now MKS_LCD12864A or MKS_LCD12864B." +#elif defined(DOGM_SD_PERCENT) + #error "DOGM_SD_PERCENT is now SHOW_PROGRESS_PERCENT." +#elif defined(NEOPIXEL_BKGD_LED_INDEX) + #error "NEOPIXEL_BKGD_LED_INDEX is now NEOPIXEL_BKGD_INDEX_FIRST." +#elif defined(TEMP_SENSOR_1_AS_REDUNDANT) + #error "TEMP_SENSOR_1_AS_REDUNDANT is now TEMP_SENSOR_REDUNDANT, with associated TEMP_SENSOR_REDUNDANT_* config." +#elif defined(MAX_REDUNDANT_TEMP_SENSOR_DIFF) + #error "MAX_REDUNDANT_TEMP_SENSOR_DIFF is now TEMP_SENSOR_REDUNDANT_MAX_DIFF" +#elif defined(LCD_ALEPHOBJECTS_CLCD_UI) + #error "LCD_ALEPHOBJECTS_CLCD_UI is now LCD_LULZBOT_CLCD_UI." +#elif defined(MIN_ARC_SEGMENTS) + #error "MIN_ARC_SEGMENTS is now MIN_CIRCLE_SEGMENTS." +#elif defined(ARC_SEGMENTS_PER_R) + #error "ARC_SUPPORT no longer uses ARC_SEGMENTS_PER_R." +#elif ENABLED(ARC_SUPPORT) && (!defined(MIN_ARC_SEGMENT_MM) || !defined(MAX_ARC_SEGMENT_MM)) + #error "ARC_SUPPORT now requires MIN_ARC_SEGMENT_MM and MAX_ARC_SEGMENT_MM." +#elif defined(LASER_POWER_INLINE) + #error "LASER_POWER_INLINE is obsolete." +#elif defined(SPINDLE_LASER_PWM) + #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." +#elif defined(LCD_SCREEN_ROT_90) + #error "LCD_SCREEN_ROT_90 is now LCD_SCREEN_ROTATE with a value of 90." +#elif defined(LCD_SCREEN_ROT_180) + #error "LCD_SCREEN_ROT_180 is now LCD_SCREEN_ROTATE with a value of 180." +#elif defined(LCD_SCREEN_ROT_270) + #error "LCD_SCREEN_ROT_270 is now LCD_SCREEN_ROTATE with a value of 270." +#elif defined(DEFAULT_LCD_BRIGHTNESS) + #error "DEFAULT_LCD_BRIGHTNESS is now LCD_BRIGHTNESS_DEFAULT." +#elif defined(NOZZLE_PARK_X_ONLY) + #error "NOZZLE_PARK_X_ONLY is now NOZZLE_PARK_MOVE 1." +#elif defined(NOZZLE_PARK_Y_ONLY) + #error "NOZZLE_PARK_Y_ONLY is now NOZZLE_PARK_MOVE 2." +#elif defined(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS is now just Z_STEPPER_ALIGN_STEPPER_XY." +#elif defined(DWIN_CREALITY_LCD_ENHANCED) + #error "DWIN_CREALITY_LCD_ENHANCED is now DWIN_LCD_PROUI." +#elif defined(LINEAR_AXES) + #error "LINEAR_AXES is now NUM_AXES (to account for rotational axes)." +#elif defined(X_DUAL_STEPPER_DRIVERS) + #error "X_DUAL_STEPPER_DRIVERS is no longer needed and should be removed." +#elif defined(Y_DUAL_STEPPER_DRIVERS) + #error "Y_DUAL_STEPPER_DRIVERS is no longer needed and should be removed." +#elif defined(NUM_Z_STEPPER_DRIVERS) + #error "NUM_Z_STEPPER_DRIVERS is no longer needed and should be removed." +#elif defined(LEVEL_BED_CORNERS) + #error "LEVEL_BED_CORNERS is now LCD_BED_TRAMMING." +#elif defined(LEVEL_CORNERS_INSET_LFRB) || defined(LEVEL_CORNERS_HEIGHT) || defined(LEVEL_CORNERS_Z_HOP) || defined(LEVEL_CORNERS_USE_PROBE) || defined(LEVEL_CORNERS_PROBE_TOLERANCE) || defined(LEVEL_CORNERS_VERIFY_RAISED) || defined(LEVEL_CORNERS_AUDIO_FEEDBACK) + #error "LEVEL_CORNERS_* settings have been renamed BED_TRAMMING_*." +#elif defined(LEVEL_CENTER_TOO) + #error "LEVEL_CENTER_TOO is now BED_TRAMMING_INCLUDE_CENTER." +#elif defined(TOUCH_IDLE_SLEEP) + #error "TOUCH_IDLE_SLEEP (seconds) is now TOUCH_IDLE_SLEEP_MINS (minutes)." +#elif defined(LCD_BACKLIGHT_TIMEOUT) + #error "LCD_BACKLIGHT_TIMEOUT (seconds) is now LCD_BACKLIGHT_TIMEOUT_MINS (minutes)." +#elif defined(LCD_SET_PROGRESS_MANUALLY) + #error "LCD_SET_PROGRESS_MANUALLY is now SET_PROGRESS_MANUALLY." +#elif defined(USE_M73_REMAINING_TIME) + #error "USE_M73_REMAINING_TIME is now SET_REMAINING_TIME." +#elif defined(SHOW_SD_PERCENT) + #error "SHOW_SD_PERCENT is now SHOW_PROGRESS_PERCENT." +#elif defined(LIN_ADVANCE_K) + #error "LIN_ADVANCE_K is now ADVANCE_K." +#elif defined(EXTRA_LIN_ADVANCE_K) + #error "EXTRA_LIN_ADVANCE_K is now ADVANCE_K_EXTRA." +#elif defined(POLAR_SEGMENTS_PER_SECOND) || defined(DELTA_SEGMENTS_PER_SECOND) || defined(SCARA_SEGMENTS_PER_SECOND) || defined(TPARA_SEGMENTS_PER_SECOND) + #error "(POLAR|DELTA|SCARA|TPARA)_SEGMENTS_PER_SECOND is now DEFAULT_SEGMENTS_PER_SECOND." +#elif defined(EXPERIMENTAL_SCURVE) + #error "EXPERIMENTAL_SCURVE is no longer needed and should be removed." +#elif defined(DISABLE_INACTIVE_EXTRUDER) + #error "DISABLE_INACTIVE_EXTRUDER is now DISABLE_OTHER_EXTRUDERS." +#elif defined(FAN_PIN) + #error "FAN_PIN is now FAN0_PIN." +#elif defined(DISABLE_INACTIVE_X) || defined(DISABLE_INACTIVE_Y) || defined(DISABLE_INACTIVE_Z) \ + || defined(DISABLE_INACTIVE_I) || defined(DISABLE_INACTIVE_J) || defined(DISABLE_INACTIVE_K) \ + || defined(DISABLE_INACTIVE_U) || defined(DISABLE_INACTIVE_V) || defined(DISABLE_INACTIVE_W) || defined(DISABLE_INACTIVE_E) + #error "DISABLE_INACTIVE_[XYZIJKUVWE] is now DISABLE_IDLE_[XYZIJKUVWE]." +#elif defined(DEFAULT_STEPPER_DEACTIVE_TIME) + #error "DEFAULT_STEPPER_DEACTIVE_TIME is now DEFAULT_STEPPER_TIMEOUT_SEC." +#elif defined(TFT_SHARED_SPI) + #error "TFT_SHARED_SPI is now TFT_SHARED_IO." +#elif defined(LCD_PINS_ENABLE) + #error "LCD_PINS_ENABLE is now LCD_PINS_EN." +#elif defined(FOLDER_SORTING) + #error "FOLDER_SORTING is now SDSORT_FOLDERS." +#elif defined(BTT_MINI_12864_V1) + #error "BTT_MINI_12864_V1 is now BTT_MINI_12864." +#elif defined(SDIO_SUPPORT) + #error "SDIO_SUPPORT is now ONBOARD_SDIO." +#endif + +// L64xx stepper drivers have been removed +#define _L6470 0x6470 +#define _L6474 0x6474 +#define _L6480 0x6480 +#define _POWERSTEP01 0xF00D +#if HAS_DRIVER(L6470) + #error "L6470 stepper drivers are no longer supported in Marlin." +#elif HAS_DRIVER(L6474) + #error "L6474 stepper drivers are no longer supported in Marlin." +#elif HAS_DRIVER(L6480) + #error "L6480 stepper drivers are no longer supported in Marlin." +#elif HAS_DRIVER(POWERSTEP01) + #error "POWERSTEP01 stepper drivers are no longer supported in Marlin." +#endif +#undef _L6470 +#undef _L6474 +#undef _L6480 +#undef _POWERSTEP01 diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index eee877be80fd..5b9a8503db31 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -26,1013 +26,1063 @@ * Conditionals that need to be set before Configuration_adv.h or pins.h */ -// MKS_LCD12864A/B is a variant of MKS_MINI_12864 -#if EITHER(MKS_LCD12864A, MKS_LCD12864B) - #define MKS_MINI_12864 -#endif - -// MKS_MINI_12864_V3 and BTT_MINI_12864_V1 are identical to FYSETC_MINI_12864_2_1 -#if EITHER(MKS_MINI_12864_V3, BTT_MINI_12864_V1) - #define FYSETC_MINI_12864_2_1 -#endif - /** - * General Flags that may be set below by specific LCDs + * Extruders have some combination of stepper motors and hotends + * so we separate these concepts into the defines: * - * DOGLCD : Run a Graphical LCD through U8GLib (with MarlinUI) - * IS_ULTIPANEL : Define LCD_PINS_D5/6/7 for direct-connected "Ultipanel" LCDs - * HAS_WIRED_LCD : Ultra LCD, not necessarily Ultipanel. - * IS_RRD_SC : Common RRD Smart Controller digital interface pins - * IS_RRD_FG_SC : Common RRD Full Graphical Smart Controller digital interface pins - * IS_U8GLIB_ST7920 : Most common DOGM display SPI interface, supporting a "lightweight" display mode. - * U8GLIB_SH1106 : SH1106 OLED with I2C interface via U8GLib - * IS_U8GLIB_SSD1306 : SSD1306 OLED with I2C interface via U8GLib (U8GLIB_SSD1306) - * U8GLIB_SSD1309 : SSD1309 OLED with I2C interface via U8GLib (HAS_U8GLIB_I2C_OLED, HAS_WIRED_LCD, DOGLCD) - * IS_U8GLIB_ST7565_64128N : ST7565 128x64 LCD with SPI interface via U8GLib - * IS_U8GLIB_LM6059_AF : LM6059 with Hardware SPI via U8GLib + * EXTRUDERS - Number of Selectable Tools + * HOTENDS - Number of hotends, whether connected or separate + * E_STEPPERS - Number of actual E stepper motors + * E_MANUAL - Number of E steppers for LCD move options + * + * These defines must be simple constants for use in REPEAT, etc. */ -#if EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) - - #define MINIPANEL - -#elif ENABLED(YHCB2004) - - #define IS_ULTIPANEL 1 - -#elif ENABLED(CARTESIO_UI) - - #define DOGLCD - #define IS_ULTIPANEL 1 - -#elif EITHER(DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) - - #define IS_DWIN_MARLINUI 1 - #define IS_ULTIPANEL 1 - -#elif ENABLED(ZONESTAR_LCD) - - #define HAS_ADC_BUTTONS 1 - #define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 - #define ADC_KEY_NUM 8 - #define IS_ULTIPANEL 1 +#if EXTRUDERS + #define HAS_EXTRUDERS 1 + #if EXTRUDERS > 1 + #define HAS_MULTI_EXTRUDER 1 + #endif + #define E_AXIS_N(E) AxisEnum(E_AXIS + E_INDEX_N(E)) +#else + #undef EXTRUDERS + #define EXTRUDERS 0 + #undef TEMP_SENSOR_0 + #undef TEMP_SENSOR_1 + #undef TEMP_SENSOR_2 + #undef TEMP_SENSOR_3 + #undef TEMP_SENSOR_4 + #undef TEMP_SENSOR_5 + #undef TEMP_SENSOR_6 + #undef TEMP_SENSOR_7 + #undef SINGLENOZZLE + #undef SWITCHING_EXTRUDER + #undef SWITCHING_NOZZLE + #undef MIXING_EXTRUDER + #undef HOTEND_IDLE_TIMEOUT + #undef DISABLE_E + #undef PREVENT_LENGTHY_EXTRUDE + #undef FILAMENT_RUNOUT_SENSOR + #undef FILAMENT_RUNOUT_DISTANCE_MM + #undef DISABLE_OTHER_EXTRUDERS +#endif - // This helps to implement HAS_ADC_BUTTONS menus - #define REVERSE_MENU_DIRECTION - #define STD_ENCODER_PULSES_PER_STEP 1 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 - #define ENCODER_FEEDRATE_DEADZONE 2 +#define E_OPTARG(N) OPTARG(HAS_MULTI_EXTRUDER, N) +#define E_TERN_(N) TERN_(HAS_MULTI_EXTRUDER, N) +#define E_TERN0(N) TERN0(HAS_MULTI_EXTRUDER, N) -#elif ENABLED(ZONESTAR_12864LCD) - #define DOGLCD - #define IS_RRD_SC 1 - #define IS_U8GLIB_ST7920 1 +/** + * Multi-Material-Unit supported models + */ +#define PRUSA_MMU1 1 +#define PRUSA_MMU2 2 +#define PRUSA_MMU2S 3 +#define EXTENDABLE_EMU_MMU2 12 +#define EXTENDABLE_EMU_MMU2S 13 -#elif ENABLED(ZONESTAR_12864OLED) - #define IS_RRD_SC 1 - #define U8GLIB_SH1106 +#ifdef MMU_MODEL + #define HAS_MMU 1 + #define SINGLENOZZLE + #if MMU_MODEL == PRUSA_MMU1 + #define HAS_PRUSA_MMU1 1 + #elif MMU_MODEL % 10 == PRUSA_MMU2 + #define HAS_PRUSA_MMU2 1 + #elif MMU_MODEL % 10 == PRUSA_MMU2S + #define HAS_PRUSA_MMU2 1 + #define HAS_PRUSA_MMU2S 1 + #endif + #if MMU_MODEL >= EXTENDABLE_EMU_MMU2 + #define HAS_EXTENDABLE_MMU 1 + #endif +#endif -#elif ENABLED(ZONESTAR_12864OLED_SSD1306) - #define IS_RRD_SC 1 - #define IS_U8GLIB_SSD1306 +#undef PRUSA_MMU1 +#undef PRUSA_MMU2 +#undef PRUSA_MMU2S +#undef EXTENDABLE_EMU_MMU2 +#undef EXTENDABLE_EMU_MMU2S -#elif ENABLED(RADDS_DISPLAY) - #define IS_ULTIPANEL 1 - #define STD_ENCODER_PULSES_PER_STEP 2 +#if ENABLED(E_DUAL_STEPPER_DRIVERS) // E0/E1 steppers act in tandem as E0 -#elif ANY(miniVIKI, VIKI2, WYH_L12864, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864, EMOTION_TECH_LCD) + #define E_STEPPERS 2 + #define E_MANUAL 1 - #define DOGLCD - #define IS_DOGM_12864 1 - #define IS_ULTIPANEL 1 +#elif ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS - #if ENABLED(miniVIKI) - #define IS_U8GLIB_ST7565_64128N 1 - #elif ENABLED(VIKI2) - #define IS_U8GLIB_ST7565_64128N 1 - #elif ENABLED(WYH_L12864) - #define IS_U8GLIB_ST7565_64128N 1 - #define ST7565_XOFFSET 0x04 - #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define IS_U8GLIB_LM6059_AF 1 - #elif ENABLED(AZSMZ_12864) - #define IS_U8GLIB_ST7565_64128N 1 - #elif ENABLED(EMOTION_TECH_LCD) - #define IS_U8GLIB_ST7565_64128N 1 - #define ST7565_VOLTAGE_DIVIDER_VALUE 0x07 + #if EXTRUDERS > 4 + #define E_STEPPERS 3 + #elif EXTRUDERS > 2 + #define E_STEPPERS 2 + #else + #define E_STEPPERS 1 #endif -#elif ENABLED(OLED_PANEL_TINYBOY2) - - #define IS_U8GLIB_SSD1306 - #define IS_ULTIPANEL 1 +#elif ENABLED(MIXING_EXTRUDER) // Multiple feeds are mixed proportionally -#elif ENABLED(RA_CONTROL_PANEL) + #define E_STEPPERS MIXING_STEPPERS + #define E_MANUAL 1 + #if MIXING_STEPPERS == 2 + #define HAS_DUAL_MIXING 1 + #endif - #define LCD_I2C_TYPE_PCA8574 - #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander - #define IS_ULTIPANEL 1 +#elif ENABLED(SWITCHING_TOOLHEAD) // Toolchanger -#elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) + #define E_STEPPERS EXTRUDERS + #define E_MANUAL EXTRUDERS - #define DOGLCD - #define IS_U8GLIB_ST7920 1 - #define IS_ULTIPANEL 1 - #define ENCODER_PULSES_PER_STEP 2 +#elif HAS_PRUSA_MMU2 // Průša Multi-Material Unit v2 -#elif ENABLED(MKS_12864OLED) + #define E_STEPPERS 1 + #define E_MANUAL 1 - #define IS_RRD_SC 1 - #define U8GLIB_SH1106 +#endif -#elif ENABLED(MKS_12864OLED_SSD1306) +// No inactive extruders with SWITCHING_NOZZLE or Průša MMU1 +#if ANY(SWITCHING_NOZZLE, HAS_PRUSA_MMU1) + #undef DISABLE_OTHER_EXTRUDERS +#endif - #define IS_RRD_SC 1 - #define IS_U8GLIB_SSD1306 +// Default E steppers / manual motion is one per extruder +#ifndef E_STEPPERS + #define E_STEPPERS EXTRUDERS +#endif +#ifndef E_MANUAL + #define E_MANUAL EXTRUDERS +#endif -#elif ENABLED(SAV_3DGLCD) +// Number of hotends... +#if ANY(SINGLENOZZLE, MIXING_EXTRUDER) // Only one for singlenozzle or mixing extruder + #define HOTENDS 1 +#elif ENABLED(SWITCHING_EXTRUDER) && DISABLED(SWITCHING_NOZZLE) // One for each pair of abstract "extruders" + #define HOTENDS E_STEPPERS +#elif TEMP_SENSOR_0 + #define HOTENDS EXTRUDERS // One per extruder if at least one heater exists +#else + #define HOTENDS 0 // A machine with no hotends at all can still extrude +#endif - #ifdef U8GLIB_SSD1306 - #define IS_U8GLIB_SSD1306 // Allow for U8GLIB_SSD1306 + SAV_3DGLCD +// At least one hotend... +#if HOTENDS + #define HAS_HOTEND 1 + #ifndef HOTEND_OVERSHOOT + #define HOTEND_OVERSHOOT 15 #endif - #define IS_NEWPANEL 1 - -#elif ENABLED(FYSETC_242_OLED_12864) - - #define IS_RRD_SC 1 - #define U8GLIB_SH1106 +#endif - #ifndef NEOPIXEL_BRIGHTNESS - #define NEOPIXEL_BRIGHTNESS 127 +// More than one hotend... +#if HOTENDS > 1 + #define HAS_MULTI_HOTEND 1 + #define HAS_HOTEND_OFFSET 1 + #ifndef HOTEND_OFFSET_X + #define HOTEND_OFFSET_X { 0 } // X offsets for each extruder #endif - -#elif ANY(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) - - #define FYSETC_MINI_12864 - #define DOGLCD - #define IS_ULTIPANEL 1 - #define LED_COLORS_REDUCE_GREEN - - // Require LED backlighting enabled - #if ENABLED(FYSETC_MINI_12864_2_1) - #ifndef NEOPIXEL_BRIGHTNESS - #define NEOPIXEL_BRIGHTNESS 127 - #endif - //#define NEOPIXEL_STARTUP_TEST + #ifndef HOTEND_OFFSET_Y + #define HOTEND_OFFSET_Y { 0 } // Y offsets for each extruder #endif - -#elif ENABLED(ULTI_CONTROLLER) - - #define IS_ULTIPANEL 1 - #define U8GLIB_SSD1309 - #define LCD_RESET_PIN LCD_PINS_D6 // This controller need a reset pin - #define STD_ENCODER_PULSES_PER_STEP 4 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 - #ifndef PCA9632 - #define PCA9632 + #ifndef HOTEND_OFFSET_Z + #define HOTEND_OFFSET_Z { 0 } // Z offsets for each extruder #endif +#else + #undef HOTEND_OFFSET_X + #undef HOTEND_OFFSET_Y + #undef HOTEND_OFFSET_Z +#endif -#elif ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602) - - #define IS_RRD_SC 1 - #define LCD_WIDTH 16 - #define LCD_HEIGHT 2 - -#elif EITHER(TFTGLCD_PANEL_SPI, TFTGLCD_PANEL_I2C) - - #define IS_TFTGLCD_PANEL 1 - #define IS_ULTIPANEL 1 // Note that IS_ULTIPANEL leads to HAS_WIRED_LCD - - #if ENABLED(SDSUPPORT) && DISABLED(LCD_PROGRESS_BAR) - #define LCD_PROGRESS_BAR +// Clean up E-stepper-based settings... +#if E_STEPPERS <= 7 + #undef INVERT_E7_DIR + #undef E7_DRIVER_TYPE + #if E_STEPPERS <= 6 + #undef INVERT_E6_DIR + #undef E6_DRIVER_TYPE + #if E_STEPPERS <= 5 + #undef INVERT_E5_DIR + #undef E5_DRIVER_TYPE + #if E_STEPPERS <= 4 + #undef INVERT_E4_DIR + #undef E4_DRIVER_TYPE + #if E_STEPPERS <= 3 + #undef INVERT_E3_DIR + #undef E3_DRIVER_TYPE + #if E_STEPPERS <= 2 + #undef INVERT_E2_DIR + #undef E2_DRIVER_TYPE + #if E_STEPPERS <= 1 + #undef INVERT_E1_DIR + #undef E1_DRIVER_TYPE + #if E_STEPPERS == 0 + #undef INVERT_E0_DIR + #undef E0_DRIVER_TYPE + #endif + #endif + #endif + #endif + #endif + #endif #endif - #if ENABLED(TFTGLCD_PANEL_I2C) - #define LCD_I2C_ADDRESS 0x33 // Must be 0x33 for STM32 main boards and equal to panel's I2C slave address +#endif + +/** + * Number of Linear Axes (e.g., XYZIJKUVW) + * All the logical axes except for the tool (E) axis + */ +#ifdef NUM_AXES + #undef NUM_AXES + #define NUM_AXES_WARNING 1 +#endif + +#ifdef W_DRIVER_TYPE + #define NUM_AXES 9 +#elif defined(V_DRIVER_TYPE) + #define NUM_AXES 8 +#elif defined(U_DRIVER_TYPE) + #define NUM_AXES 7 +#elif defined(K_DRIVER_TYPE) + #define NUM_AXES 6 +#elif defined(J_DRIVER_TYPE) + #define NUM_AXES 5 +#elif defined(I_DRIVER_TYPE) + #define NUM_AXES 4 +#elif defined(Z_DRIVER_TYPE) + #define NUM_AXES 3 +#elif defined(Y_DRIVER_TYPE) + #define NUM_AXES 2 +#elif defined(X_DRIVER_TYPE) + #define NUM_AXES 1 +#else + #define NUM_AXES 0 +#endif +#if NUM_AXES >= 1 + #define HAS_X_AXIS 1 + #define HAS_A_AXIS 1 + #if NUM_AXES >= XY + #define HAS_Y_AXIS 1 + #define HAS_B_AXIS 1 + #if NUM_AXES >= XYZ + #define HAS_Z_AXIS 1 + #define HAS_C_AXIS 1 + #if NUM_AXES >= 4 + #define HAS_I_AXIS 1 + #if NUM_AXES >= 5 + #define HAS_J_AXIS 1 + #if NUM_AXES >= 6 + #define HAS_K_AXIS 1 + #if NUM_AXES >= 7 + #define HAS_U_AXIS 1 + #if NUM_AXES >= 8 + #define HAS_V_AXIS 1 + #if NUM_AXES >= 9 + #define HAS_W_AXIS 1 + #endif + #endif + #endif + #endif + #endif + #endif + #endif #endif - #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD, used for both I2C and SPI buses (LiquidTWI2 not required) - #define STD_ENCODER_PULSES_PER_STEP 2 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 - #define LCD_WIDTH 20 // 20 or 24 chars in line - #define LCD_HEIGHT 10 // Character lines - #define LCD_CONTRAST_MIN 127 - #define LCD_CONTRAST_MAX 255 - #define LCD_CONTRAST_DEFAULT 250 - #define CONVERT_TO_EXT_ASCII // Use extended 128-255 symbols from ASCII table. - // At this time present conversion only for cyrillic - bg, ru and uk languages. - // First 7 ASCII symbols in panel font must be replaced with Marlin's special symbols. +#endif + +#if !HAS_X_AXIS + #undef ENDSTOPPULLUP_XMIN + #undef ENDSTOPPULLUP_XMAX + #undef X_MIN_ENDSTOP_INVERTING + #undef X_MAX_ENDSTOP_INVERTING + #undef X2_DRIVER_TYPE + #undef X_ENABLE_ON + #undef DISABLE_X + #undef INVERT_X_DIR + #undef X_HOME_DIR + #undef X_MIN_POS + #undef X_MAX_POS + #undef MANUAL_X_HOME_POS + #undef MIN_SOFTWARE_ENDSTOPS + #undef MAX_SOFTWARE_ENDSTOPS +#endif + +#if !HAS_Y_AXIS + #undef ENDSTOPPULLUP_YMIN + #undef ENDSTOPPULLUP_YMAX + #undef Y_MIN_ENDSTOP_INVERTING + #undef Y_MAX_ENDSTOP_INVERTING + #undef Y2_DRIVER_TYPE + #undef Y_ENABLE_ON + #undef DISABLE_Y + #undef INVERT_Y_DIR + #undef Y_HOME_DIR + #undef Y_MIN_POS + #undef Y_MAX_POS + #undef MANUAL_Y_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_Y + #undef MAX_SOFTWARE_ENDSTOP_Y +#endif + +#if HAS_Z_AXIS + #ifdef Z4_DRIVER_TYPE + #define NUM_Z_STEPPERS 4 + #elif defined(Z3_DRIVER_TYPE) + #define NUM_Z_STEPPERS 3 + #elif defined(Z2_DRIVER_TYPE) + #define NUM_Z_STEPPERS 2 + #else + #define NUM_Z_STEPPERS 1 + #endif +#else + #undef ENDSTOPPULLUP_ZMIN + #undef ENDSTOPPULLUP_ZMAX + #undef Z_MIN_ENDSTOP_INVERTING + #undef Z_MAX_ENDSTOP_INVERTING + #undef Z2_DRIVER_TYPE + #undef Z3_DRIVER_TYPE + #undef Z4_DRIVER_TYPE + #undef Z_ENABLE_ON + #undef DISABLE_Z + #undef INVERT_Z_DIR + #undef Z_HOME_DIR + #undef Z_MIN_POS + #undef Z_MAX_POS + #undef MANUAL_Z_HOME_POS + #undef Z_SAFE_HOMING + #undef MIN_SOFTWARE_ENDSTOP_Z + #undef MAX_SOFTWARE_ENDSTOP_Z +#endif + +#if !HAS_I_AXIS + #undef ENDSTOPPULLUP_IMIN + #undef ENDSTOPPULLUP_IMAX + #undef I_MIN_ENDSTOP_INVERTING + #undef I_MAX_ENDSTOP_INVERTING + #undef I_ENABLE_ON + #undef DISABLE_I + #undef INVERT_I_DIR + #undef I_HOME_DIR + #undef I_MIN_POS + #undef I_MAX_POS + #undef MANUAL_I_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_I + #undef MAX_SOFTWARE_ENDSTOP_I +#endif + +#if !HAS_J_AXIS + #undef ENDSTOPPULLUP_JMIN + #undef ENDSTOPPULLUP_JMAX + #undef J_MIN_ENDSTOP_INVERTING + #undef J_MAX_ENDSTOP_INVERTING + #undef J_ENABLE_ON + #undef DISABLE_J + #undef INVERT_J_DIR + #undef J_HOME_DIR + #undef J_MIN_POS + #undef J_MAX_POS + #undef MANUAL_J_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_J + #undef MAX_SOFTWARE_ENDSTOP_J +#endif + +#if !HAS_K_AXIS + #undef ENDSTOPPULLUP_KMIN + #undef ENDSTOPPULLUP_KMAX + #undef K_MIN_ENDSTOP_INVERTING + #undef K_MAX_ENDSTOP_INVERTING + #undef K_ENABLE_ON + #undef DISABLE_K + #undef INVERT_K_DIR + #undef K_HOME_DIR + #undef K_MIN_POS + #undef K_MAX_POS + #undef MANUAL_K_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_K + #undef MAX_SOFTWARE_ENDSTOP_K +#endif + +#if !HAS_U_AXIS + #undef ENDSTOPPULLUP_UMIN + #undef ENDSTOPPULLUP_UMAX + #undef U_MIN_ENDSTOP_INVERTING + #undef U_MAX_ENDSTOP_INVERTING + #undef U_ENABLE_ON + #undef DISABLE_U + #undef INVERT_U_DIR + #undef U_HOME_DIR + #undef U_MIN_POS + #undef U_MAX_POS + #undef MANUAL_U_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_U + #undef MAX_SOFTWARE_ENDSTOP_U +#endif + +#if !HAS_V_AXIS + #undef ENDSTOPPULLUP_VMIN + #undef ENDSTOPPULLUP_VMAX + #undef V_MIN_ENDSTOP_INVERTING + #undef V_MAX_ENDSTOP_INVERTING + #undef V_ENABLE_ON + #undef DISABLE_V + #undef INVERT_V_DIR + #undef V_HOME_DIR + #undef V_MIN_POS + #undef V_MAX_POS + #undef MANUAL_V_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_V + #undef MAX_SOFTWARE_ENDSTOP_V +#endif + +#if !HAS_W_AXIS + #undef ENDSTOPPULLUP_WMIN + #undef ENDSTOPPULLUP_WMAX + #undef W_MIN_ENDSTOP_INVERTING + #undef W_MAX_ENDSTOP_INVERTING + #undef W_ENABLE_ON + #undef DISABLE_W + #undef INVERT_W_DIR + #undef W_HOME_DIR + #undef W_MIN_POS + #undef W_MAX_POS + #undef MANUAL_W_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_W + #undef MAX_SOFTWARE_ENDSTOP_W +#endif + +#define _OR_HAS_DA(A) ENABLED(DISABLE_##A) || +#if MAP(_OR_HAS_DA, X, Y, Z, I, J, K, U, V, W) 0 + #define HAS_DISABLE_MAIN_AXES 1 +#endif +#if HAS_DISABLE_MAIN_AXES || ENABLED(DISABLE_E) + #define HAS_DISABLE_AXES 1 +#endif +#undef _OR_HAS_DA + +#ifdef X2_DRIVER_TYPE + #define HAS_X2_STEPPER 1 +#endif +#ifdef Y2_DRIVER_TYPE + #define HAS_Y2_STEPPER 1 +#endif + +/** + * Number of Primary Linear Axes (e.g., XYZ) + * X, XY, or XYZ axes. Excluding duplicate axes (X2, Y2, Z2, Z3, Z4) + */ +#if NUM_AXES >= 3 + #define PRIMARY_LINEAR_AXES 3 +#else + #define PRIMARY_LINEAR_AXES NUM_AXES +#endif + +/** + * Number of Secondary Axes (e.g., IJKUVW) + * All linear/rotational axes between XYZ and E. + */ +#define SECONDARY_AXES SUB3(NUM_AXES) + +/** + * Number of Rotational Axes (e.g., IJK) + * All axes for which AXIS*_ROTATES is defined. + * For these axes, positions are specified in angular degrees. + */ +#if ENABLED(AXIS9_ROTATES) + #define ROTATIONAL_AXES 6 +#elif ENABLED(AXIS8_ROTATES) + #define ROTATIONAL_AXES 5 +#elif ENABLED(AXIS7_ROTATES) + #define ROTATIONAL_AXES 4 +#elif ENABLED(AXIS6_ROTATES) + #define ROTATIONAL_AXES 3 +#elif ENABLED(AXIS5_ROTATES) + #define ROTATIONAL_AXES 2 +#elif ENABLED(AXIS4_ROTATES) + #define ROTATIONAL_AXES 1 +#else + #define ROTATIONAL_AXES 0 +#endif + +/** + * Number of Secondary Linear Axes (e.g., UVW) + * All secondary axes for which AXIS*_ROTATES is not defined. + * Excluding primary axes and excluding duplicate axes (X2, Y2, Z2, Z3, Z4) + */ +#define SECONDARY_LINEAR_AXES (NUM_AXES - PRIMARY_LINEAR_AXES - ROTATIONAL_AXES) + +/** + * Number of Logical Axes (e.g., XYZIJKUVWE) + * All logical axes that can be commanded directly by G-code. + * Delta maps stepper-specific values to ABC steppers. + */ +#if HAS_EXTRUDERS + #define LOGICAL_AXES INCREMENT(NUM_AXES) +#else + #define LOGICAL_AXES NUM_AXES +#endif + +/** + * DISTINCT_E_FACTORS is set to give extruders (some) individual settings. + * + * DISTINCT_AXES is the number of distinct addressable axes (not steppers). + * Includes all linear axes plus all distinguished extruders. + * The default behavior is to treat all extruders as a single E axis + * with shared motion and temperature settings. + * + * DISTINCT_E is the number of distinguished extruders. By default this + * will be 1 which indicates all extruders share the same settings. + * + * E_INDEX_N(E) should be used to get the E index of any item that might be + * distinguished. + */ +#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 + #define DISTINCT_AXES (NUM_AXES + E_STEPPERS) + #define DISTINCT_E E_STEPPERS + #define E_INDEX_N(E) (E) +#else + #undef DISTINCT_E_FACTORS + #define DISTINCT_AXES LOGICAL_AXES + #define DISTINCT_E 1 + #define E_INDEX_N(E) 0 +#endif -#elif ENABLED(CR10_STOCKDISPLAY) +// Helper macros for extruder and hotend arrays +#define _EXTRUDER_LOOP(E) for (int8_t E = 0; E < EXTRUDERS; E++) +#define EXTRUDER_LOOP() _EXTRUDER_LOOP(e) +#define _HOTEND_LOOP(H) for (int8_t H = 0; H < HOTENDS; H++) +#define HOTEND_LOOP() _HOTEND_LOOP(e) - #define IS_RRD_FG_SC 1 - #define LCD_ST7920_DELAY_1 125 - #define LCD_ST7920_DELAY_2 125 - #define LCD_ST7920_DELAY_3 125 +#define ARRAY_BY_EXTRUDERS(V...) ARRAY_N(EXTRUDERS, V) +#define ARRAY_BY_EXTRUDERS1(v1) ARRAY_N_1(EXTRUDERS, v1) +#define ARRAY_BY_HOTENDS(V...) ARRAY_N(HOTENDS, V) +#define ARRAY_BY_HOTENDS1(v1) ARRAY_N_1(HOTENDS, v1) -#elif EITHER(ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING) +// Support for SD Card and other file storage +#if ENABLED(SDSUPPORT) + #define HAS_MEDIA 1 +#endif - #define IS_RRD_FG_SC 1 - #define LCD_ST7920_DELAY_1 150 - #define LCD_ST7920_DELAY_2 150 - #define LCD_ST7920_DELAY_3 150 +/** + * Conditionals for the configured LCD / Controller + */ -#elif ANY(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, BQ_LCD_SMART_CONTROLLER, K3D_FULL_GRAPHIC_SMART_CONTROLLER) +// MKS_LCD12864A/B is a variant of MKS_MINI_12864 +#if ANY(MKS_LCD12864A, MKS_LCD12864B) + #define MKS_MINI_12864 +#endif - #define IS_RRD_FG_SC 1 +// MKS_MINI_12864_V3 and BTT_MINI_12864 have identical pinouts to FYSETC_MINI_12864_2_1 +#if ANY(MKS_MINI_12864_V3, BTT_MINI_12864) + #define FYSETC_MINI_12864_2_1 +#endif -#elif ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) +/** + * General Flags that may be set below by specific LCDs + * + * DOGLCD : Run a Graphical LCD through U8GLib (with MarlinUI) + * IS_ULTIPANEL : Define LCD_PINS_D5/6/7 for direct-connected "Ultipanel" LCDs + * HAS_WIRED_LCD : Ultra LCD, not necessarily Ultipanel. + * IS_RRD_SC : Common RRD Smart Controller digital interface pins + * IS_RRD_FG_SC : Common RRD Full Graphical Smart Controller digital interface pins + * IS_U8GLIB_ST7920 : Most common DOGM display SPI interface, supporting a "lightweight" display mode. + * U8GLIB_SH1106 : SH1106 OLED with I2C interface via U8GLib + * IS_U8GLIB_SSD1306 : SSD1306 OLED with I2C interface via U8GLib (U8GLIB_SSD1306) + * U8GLIB_SSD1309 : SSD1309 OLED with I2C interface via U8GLib (HAS_U8GLIB_I2C_OLED, HAS_WIRED_LCD, DOGLCD) + * IS_U8GLIB_ST7565_64128N : ST7565 128x64 LCD with SPI interface via U8GLib + * IS_U8GLIB_LM6059_AF : LM6059 with Hardware SPI via U8GLib + */ +#if ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) - #define IS_RRD_SC 1 // RepRapDiscount LCD or Graphical LCD with rotary click encoder + #define MINIPANEL -#elif ENABLED(K3D_242_OLED_CONTROLLER) +#elif ENABLED(YHCB2004) - #define IS_RRD_SC 1 - #define U8GLIB_SSD1309 + #define IS_ULTIPANEL 1 -#endif +#elif ENABLED(CARTESIO_UI) -// ST7920-based graphical displays -#if ANY(IS_RRD_FG_SC, LCD_FOR_MELZI, SILVER_GATE_GLCD_CONTROLLER) #define DOGLCD - #define IS_U8GLIB_ST7920 1 - #define IS_RRD_SC 1 -#endif + #define IS_ULTIPANEL 1 -// ST7565 / 64128N graphical displays -#if EITHER(MAKRPANEL, MINIPANEL) +#elif ANY(DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) + + #define IS_DWIN_MARLINUI 1 #define IS_ULTIPANEL 1 - #define DOGLCD - #if ENABLED(MAKRPANEL) - #define IS_U8GLIB_ST7565_64128N 1 - #endif -#endif -#if ENABLED(IS_U8GLIB_SSD1306) - #define U8GLIB_SSD1306 -#endif +#elif ENABLED(ZONESTAR_LCD) -#if ENABLED(OVERLORD_OLED) + #define HAS_ADC_BUTTONS 1 + #define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 + #define ADC_KEY_NUM 8 #define IS_ULTIPANEL 1 - #define U8GLIB_SH1106 - /** - * PCA9632 for buzzer and LEDs via i2c - * No auto-inc, red and green leds switched, buzzer - */ - #define PCA9632 - #define PCA9632_NO_AUTO_INC - #define PCA9632_GRN 0x00 - #define PCA9632_RED 0x02 - #define PCA9632_BUZZER - #define PCA9632_BUZZER_DATA { 0x09, 0x02 } - #define STD_ENCODER_PULSES_PER_STEP 1 // Overlord uses buttons + // This helps to implement HAS_ADC_BUTTONS menus + #define REVERSE_MENU_DIRECTION + #define STD_ENCODER_PULSES_PER_STEP 1 #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 -#endif + #define ENCODER_FEEDRATE_DEADZONE 2 -// 128x64 I2C OLED LCDs - SSD1306/SSD1309/SH1106 -#if ANY(U8GLIB_SSD1306, U8GLIB_SSD1309, U8GLIB_SH1106) - #define HAS_U8GLIB_I2C_OLED 1 - #define HAS_WIRED_LCD 1 +#elif ENABLED(ZONESTAR_12864LCD) #define DOGLCD -#endif + #define IS_RRD_SC 1 + #define IS_U8GLIB_ST7920 1 -/** - * SPI Ultipanels - */ +#elif ENABLED(ZONESTAR_12864OLED) + #define IS_RRD_SC 1 + #define U8GLIB_SH1106 -// Basic Ultipanel-like displays -#if ANY(ULTIMAKERCONTROLLER, IS_RRD_SC, G3D_PANEL, RIGIDBOT_PANEL, PANEL_ONE, U8GLIB_SH1106) +#elif ENABLED(ZONESTAR_12864OLED_SSD1306) + #define IS_RRD_SC 1 + #define IS_U8GLIB_SSD1306 + +#elif ENABLED(RADDS_DISPLAY) #define IS_ULTIPANEL 1 -#endif + #define STD_ENCODER_PULSES_PER_STEP 2 + +#elif ANY(miniVIKI, VIKI2, WYH_L12864, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864, EMOTION_TECH_LCD) -// Einstart OLED has Cardinal nav via pins defined in pins_EINSTART-S.h -#if ENABLED(U8GLIB_SH1106_EINSTART) #define DOGLCD + #define IS_DOGM_12864 1 #define IS_ULTIPANEL 1 -#endif -// TFT Compatibility -#if ANY(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT, TFT_320x240, TFT_480x320, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) - #define IS_LEGACY_TFT 1 - #define TFT_GENERIC -#endif + #if ENABLED(miniVIKI) + #define IS_U8GLIB_ST7565_64128N 1 + #elif ENABLED(VIKI2) + #define IS_U8GLIB_ST7565_64128N 1 + #elif ENABLED(WYH_L12864) + #define IS_U8GLIB_ST7565_64128N 1 + #define ST7565_XOFFSET 0x04 + #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) + #define IS_U8GLIB_LM6059_AF 1 + #elif ENABLED(AZSMZ_12864) + #define IS_U8GLIB_ST7565_64128N 1 + #elif ENABLED(EMOTION_TECH_LCD) + #define IS_U8GLIB_ST7565_64128N 1 + #define ST7565_VOLTAGE_DIVIDER_VALUE 0x07 + #endif -#if ANY(FSMC_GRAPHICAL_TFT, TFT_320x240, TFT_480x320, TFT_LVGL_UI_FSMC) - #define TFT_INTERFACE_FSMC -#elif ANY(SPI_GRAPHICAL_TFT, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_SPI) - #define TFT_INTERFACE_SPI -#endif +#elif ENABLED(OLED_PANEL_TINYBOY2) -#if EITHER(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT) - #define TFT_CLASSIC_UI -#elif ANY(TFT_320x240, TFT_480x320, TFT_320x240_SPI, TFT_480x320_SPI) - #define TFT_COLOR_UI -#elif EITHER(TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) - #define TFT_LVGL_UI -#endif + #define IS_U8GLIB_SSD1306 + #define IS_ULTIPANEL 1 -// FSMC/SPI TFT Panels (LVGL) -#if ENABLED(TFT_LVGL_UI) - #define HAS_TFT_LVGL_UI 1 - #define SERIAL_RUNTIME_HOOK 1 -#endif +#elif ENABLED(RA_CONTROL_PANEL) -// FSMC/SPI TFT Panels -#if ENABLED(TFT_CLASSIC_UI) - #define TFT_SCALED_DOGLCD 1 -#endif + #define LCD_I2C_TYPE_PCA8574 + #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander + #define IS_ULTIPANEL 1 + +#elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) -#if TFT_SCALED_DOGLCD #define DOGLCD + #define IS_U8GLIB_ST7920 1 #define IS_ULTIPANEL 1 - #define DELAYED_BACKLIGHT_INIT -#elif HAS_TFT_LVGL_UI - #define DELAYED_BACKLIGHT_INIT -#endif + #define ENCODER_PULSES_PER_STEP 2 -// Color UI -#if ENABLED(TFT_COLOR_UI) - #define HAS_GRAPHICAL_TFT 1 - #define IS_ULTIPANEL 1 -#endif +#elif ENABLED(MKS_12864OLED) -/** - * I2C Panels - */ + #define IS_RRD_SC 1 + #define U8GLIB_SH1106 -#if ANY(IS_RRD_SC, IS_DOGM_12864, OLED_PANEL_TINYBOY2, LCD_I2C_PANELOLU2) +#elif ENABLED(MKS_12864OLED_SSD1306) - #define STD_ENCODER_PULSES_PER_STEP 4 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 + #define IS_RRD_SC 1 + #define IS_U8GLIB_SSD1306 - #if ENABLED(LCD_I2C_PANELOLU2) // PANELOLU2 LCD with status LEDs, separate encoder and click inputs - #define LCD_I2C_TYPE_MCP23017 // I2C Character-based 12864 display - #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander - #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD (optional) - #define IS_ULTIPANEL 1 +#elif ENABLED(SAV_3DGLCD) + + #ifdef U8GLIB_SSD1306 + #define IS_U8GLIB_SSD1306 // Allow for U8GLIB_SSD1306 + SAV_3DGLCD #endif + #define IS_NEWPANEL 1 -#elif EITHER(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) +#elif ENABLED(FYSETC_242_OLED_12864) - #define LCD_I2C_TYPE_PCF8575 // I2C Character-based 12864 display - #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander + #define IS_RRD_SC 1 + #define U8GLIB_SH1106 + + #ifndef NEOPIXEL_BRIGHTNESS + #define NEOPIXEL_BRIGHTNESS 127 + #endif + +#elif ANY(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) + + #define FYSETC_MINI_12864 + #define DOGLCD #define IS_ULTIPANEL 1 + #define LED_COLORS_REDUCE_GREEN - #if ENABLED(LCD_SAINSMART_I2C_2004) - #define LCD_WIDTH 20 - #define LCD_HEIGHT 4 + // Require LED backlighting enabled + #if ENABLED(FYSETC_MINI_12864_2_1) + #ifndef NEOPIXEL_BRIGHTNESS + #define NEOPIXEL_BRIGHTNESS 127 + #endif + //#define NEOPIXEL_STARTUP_TEST #endif -#elif ENABLED(LCD_I2C_VIKI) +#elif ENABLED(ULTI_CONTROLLER) - /** - * Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs - * - * This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 ) - * Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory. - * Note: The pause/stop/resume LCD button pin should be connected to the Arduino - * BTN_ENC pin (or set BTN_ENC to -1 if not used) - */ - #define LCD_I2C_TYPE_MCP23017 - #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander - #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later) #define IS_ULTIPANEL 1 + #define U8GLIB_SSD1309 + #define LCD_RESET_PIN LCD_PINS_D6 // This controller need a reset pin + #define STD_ENCODER_PULSES_PER_STEP 4 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 + #ifndef PCA9632 + #define PCA9632 + #endif - #define ENCODER_FEEDRATE_DEADZONE 4 +#elif ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602) - #define STD_ENCODER_PULSES_PER_STEP 1 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 2 + #define IS_RRD_SC 1 + #define LCD_WIDTH 16 + #define LCD_HEIGHT 2 -#elif ENABLED(G3D_PANEL) +#elif ANY(TFTGLCD_PANEL_SPI, TFTGLCD_PANEL_I2C) + #define IS_TFTGLCD_PANEL 1 + #define IS_ULTIPANEL 1 // Note that IS_ULTIPANEL leads to HAS_WIRED_LCD + + #if HAS_MEDIA && DISABLED(LCD_PROGRESS_BAR) + #define LCD_PROGRESS_BAR + #endif + #if ENABLED(TFTGLCD_PANEL_I2C) + #define LCD_I2C_ADDRESS 0x33 // Must be 0x33 for STM32 main boards and equal to panel's I2C slave address + #endif + #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD, used for both I2C and SPI buses (LiquidTWI2 not required) #define STD_ENCODER_PULSES_PER_STEP 2 #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 + #define LCD_WIDTH 20 // 20 or 24 chars in line + #define LCD_HEIGHT 10 // Character lines + #define LCD_CONTRAST_MIN 127 + #define LCD_CONTRAST_MAX 255 + #define LCD_CONTRAST_DEFAULT 250 + #define CONVERT_TO_EXT_ASCII // Use extended 128-255 symbols from ASCII table. + // At this time present conversion only for cyrillic - bg, ru and uk languages. + // First 7 ASCII symbols in panel font must be replaced with Marlin's special symbols. -#endif +#elif ENABLED(CR10_STOCKDISPLAY) -#if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && DISABLED(NO_LCD_DETECT) - #define DETECT_I2C_LCD_DEVICE 1 -#endif + #define IS_RRD_FG_SC 1 + #define LCD_ST7920_DELAY_1 125 + #define LCD_ST7920_DELAY_2 125 + #define LCD_ST7920_DELAY_3 125 -#ifndef STD_ENCODER_PULSES_PER_STEP - #if ENABLED(TOUCH_SCREEN) - #define STD_ENCODER_PULSES_PER_STEP 2 - #else - #define STD_ENCODER_PULSES_PER_STEP 5 - #endif -#endif -#ifndef STD_ENCODER_STEPS_PER_MENU_ITEM - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 -#endif -#ifndef ENCODER_PULSES_PER_STEP - #define ENCODER_PULSES_PER_STEP STD_ENCODER_PULSES_PER_STEP -#endif -#ifndef ENCODER_STEPS_PER_MENU_ITEM - #define ENCODER_STEPS_PER_MENU_ITEM STD_ENCODER_STEPS_PER_MENU_ITEM -#endif -#ifndef ENCODER_FEEDRATE_DEADZONE - #define ENCODER_FEEDRATE_DEADZONE 6 -#endif +#elif ANY(ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING) -// Shift register panels -// --------------------- -// 2 wire Non-latching LCD SR from: -// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection -#if ENABLED(FF_INTERFACEBOARD) - #define SR_LCD_3W_NL // Non latching 3 wire shift register - #define IS_ULTIPANEL 1 -#elif ENABLED(SAV_3DLCD) - #define SR_LCD_2W_NL // Non latching 2 wire shift register - #define IS_ULTIPANEL 1 -#elif ENABLED(ULTIPANEL) - #define IS_ULTIPANEL 1 -#endif + #define IS_RRD_FG_SC 1 + #define LCD_ST7920_DELAY_1 150 + #define LCD_ST7920_DELAY_2 150 + #define LCD_ST7920_DELAY_3 150 -#if EITHER(IS_ULTIPANEL, ULTRA_LCD) - #define HAS_WIRED_LCD 1 -#endif +#elif ANY(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, BQ_LCD_SMART_CONTROLLER, K3D_FULL_GRAPHIC_SMART_CONTROLLER) -#if EITHER(IS_ULTIPANEL, REPRAPWORLD_KEYPAD) - #define IS_NEWPANEL 1 -#endif + #define IS_RRD_FG_SC 1 -#if EITHER(ZONESTAR_LCD, REPRAPWORLD_KEYPAD) - #define IS_RRW_KEYPAD 1 - #ifndef REPRAPWORLD_KEYPAD_MOVE_STEP - #define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0 - #endif -#endif +#elif ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) -// Aliases for LCD features -#if ANY(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS) - #define HAS_DGUS_LCD_CLASSIC 1 -#endif + #define IS_RRD_SC 1 // RepRapDiscount LCD or Graphical LCD with rotary click encoder -#if EITHER(HAS_DGUS_LCD_CLASSIC, DGUS_LCD_UI_RELOADED) - #define HAS_DGUS_LCD 1 -#endif +#elif ENABLED(K3D_242_OLED_CONTROLLER) -// Extensible UI serial touch screens. (See src/lcd/extui) -#if ANY(HAS_DGUS_LCD, MALYAN_LCD, TOUCH_UI_FTDI_EVE, ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, NEXTION_TFT) - #define IS_EXTUI 1 - #define EXTENSIBLE_UI -#endif + #define IS_RRD_SC 1 + #define U8GLIB_SSD1309 -// Aliases for LCD features -#if EITHER(DWIN_CREALITY_LCD, DWIN_LCD_PROUI) - #define HAS_DWIN_E3V2_BASIC 1 -#endif -#if EITHER(HAS_DWIN_E3V2_BASIC, DWIN_CREALITY_LCD_JYERSUI) - #define HAS_DWIN_E3V2 1 -#endif -#if ENABLED(DWIN_LCD_PROUI) - #define DO_LIST_BIN_FILES 1 #endif -// E3V2 extras -#if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI - #define SERIAL_CATCHALL 0 - #define HAS_LCD_BRIGHTNESS 1 - #define LCD_BRIGHTNESS_MAX 250 - #if ENABLED(DWIN_LCD_PROUI) - #define LCD_BRIGHTNESS_DEFAULT 127 - #endif +// ST7920-based graphical displays +#if ANY(IS_RRD_FG_SC, LCD_FOR_MELZI, SILVER_GATE_GLCD_CONTROLLER) + #define DOGLCD + #define IS_U8GLIB_ST7920 1 + #define IS_RRD_SC 1 #endif -#if HAS_WIRED_LCD - #if ENABLED(DOGLCD) - #define HAS_MARLINUI_U8GLIB 1 - #elif IS_TFTGLCD_PANEL - // Neither DOGM nor HD44780. Fully customized interface. - #elif IS_DWIN_MARLINUI - // Since HAS_MARLINUI_U8GLIB refers to U8G displays - // the DWIN display can define its own flags - #elif !HAS_GRAPHICAL_TFT - #define HAS_MARLINUI_HD44780 1 +// ST7565 / 64128N graphical displays +#if ANY(MAKRPANEL, MINIPANEL) + #define IS_ULTIPANEL 1 + #define DOGLCD + #if ENABLED(MAKRPANEL) + #define IS_U8GLIB_ST7565_64128N 1 #endif #endif -#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) - #define HAS_DISPLAY 1 +#if ENABLED(IS_U8GLIB_SSD1306) + #define U8GLIB_SSD1306 #endif -#if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT && !IS_DWIN_MARLINUI - #define HAS_LCDPRINT 1 -#endif +#if ENABLED(OVERLORD_OLED) + #define IS_ULTIPANEL 1 + #define U8GLIB_SH1106 + /** + * PCA9632 for buzzer and LEDs via i2c + * No auto-inc, red and green leds switched, buzzer + */ + #define PCA9632 + #define PCA9632_NO_AUTO_INC + #define PCA9632_GRN 0x00 + #define PCA9632_RED 0x02 + #define PCA9632_BUZZER + #define PCA9632_BUZZER_DATA { 0x09, 0x02 } -#if HAS_DISPLAY || HAS_DWIN_E3V2 - #define HAS_STATUS_MESSAGE 1 + #define STD_ENCODER_PULSES_PER_STEP 1 // Overlord uses buttons + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 #endif -#if IS_ULTIPANEL && DISABLED(NO_LCD_MENUS) - #define HAS_MARLINUI_MENU 1 +// 128x64 I2C OLED LCDs - SSD1306/SSD1309/SH1106 +#if ANY(U8GLIB_SSD1306, U8GLIB_SSD1309, U8GLIB_SH1106) + #define HAS_U8GLIB_I2C_OLED 1 + #define HAS_WIRED_LCD 1 + #define DOGLCD #endif -#if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, HAS_DWIN_E3V2) - #define HAS_MANUAL_MOVE_MENU 1 -#endif +/** + * SPI Ultipanels + */ -#if HAS_MARLINUI_U8GLIB - #ifndef LCD_PIXEL_WIDTH - #define LCD_PIXEL_WIDTH 128 - #endif - #ifndef LCD_PIXEL_HEIGHT - #define LCD_PIXEL_HEIGHT 64 - #endif +// Basic Ultipanel-like displays +#if ANY(ULTIMAKERCONTROLLER, IS_RRD_SC, G3D_PANEL, RIGIDBOT_PANEL, PANEL_ONE, U8GLIB_SH1106) + #define IS_ULTIPANEL 1 #endif -/** - * Multi-Material-Unit supported models - */ -#define PRUSA_MMU1 1 -#define PRUSA_MMU2 2 -#define PRUSA_MMU2S 3 -#define EXTENDABLE_EMU_MMU2 12 -#define EXTENDABLE_EMU_MMU2S 13 +// Einstart OLED has Cardinal nav via pins defined in pins_EINSTART-S.h +#if ENABLED(U8GLIB_SH1106_EINSTART) + #define DOGLCD + #define IS_ULTIPANEL 1 +#endif -#ifdef MMU_MODEL - #define HAS_MMU 1 - #if MMU_MODEL == PRUSA_MMU1 - #define HAS_PRUSA_MMU1 1 - #elif MMU_MODEL % 10 == PRUSA_MMU2 - #define HAS_PRUSA_MMU2 1 - #elif MMU_MODEL % 10 == PRUSA_MMU2S - #define HAS_PRUSA_MMU2 1 - #define HAS_PRUSA_MMU2S 1 +// TFT Legacy options masquerade as TFT_GENERIC +#if ANY(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT, TFT_320x240, TFT_480x320, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) + #define IS_LEGACY_TFT 1 + #define TFT_GENERIC + #if ANY(FSMC_GRAPHICAL_TFT, TFT_320x240, TFT_480x320, TFT_LVGL_UI_FSMC) + #define TFT_INTERFACE_FSMC + #elif ANY(SPI_GRAPHICAL_TFT, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_SPI) + #define TFT_INTERFACE_SPI #endif - #if MMU_MODEL >= EXTENDABLE_EMU_MMU2 - #define HAS_EXTENDABLE_MMU 1 + #if ANY(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT) + #define TFT_CLASSIC_UI + #elif ANY(TFT_320x240, TFT_480x320, TFT_320x240_SPI, TFT_480x320_SPI) + #define TFT_COLOR_UI + #elif ANY(TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) + #define TFT_LVGL_UI #endif #endif -#undef PRUSA_MMU1 -#undef PRUSA_MMU2 -#undef PRUSA_MMU2S -#undef EXTENDABLE_EMU_MMU2 -#undef EXTENDABLE_EMU_MMU2S - -/** - * Extruders have some combination of stepper motors and hotends - * so we separate these concepts into the defines: - * - * EXTRUDERS - Number of Selectable Tools - * HOTENDS - Number of hotends, whether connected or separate - * E_STEPPERS - Number of actual E stepper motors - * E_MANUAL - Number of E steppers for LCD move options - * - * These defines must be simple constants for use in REPEAT, etc. - */ -#if EXTRUDERS - #define HAS_EXTRUDERS 1 - #if EXTRUDERS > 1 - #define HAS_MULTI_EXTRUDER 1 - #endif - #define E_AXIS_N(E) AxisEnum(E_AXIS + E_INDEX_N(E)) -#else - #undef EXTRUDERS - #define EXTRUDERS 0 - #undef TEMP_SENSOR_0 - #undef TEMP_SENSOR_1 - #undef TEMP_SENSOR_2 - #undef TEMP_SENSOR_3 - #undef TEMP_SENSOR_4 - #undef TEMP_SENSOR_5 - #undef TEMP_SENSOR_6 - #undef TEMP_SENSOR_7 - #undef SINGLENOZZLE - #undef SWITCHING_EXTRUDER - #undef SWITCHING_NOZZLE - #undef MIXING_EXTRUDER - #undef HOTEND_IDLE_TIMEOUT - #undef DISABLE_E - #undef THERMAL_PROTECTION_HOTENDS - #undef PREVENT_COLD_EXTRUSION - #undef PREVENT_LENGTHY_EXTRUDE - #undef FILAMENT_RUNOUT_SENSOR - #undef FILAMENT_RUNOUT_DISTANCE_MM - #undef DISABLE_INACTIVE_EXTRUDER +// FSMC/SPI TFT Panels (LVGL) +#if ENABLED(TFT_LVGL_UI) + #define HAS_TFT_LVGL_UI 1 + #define SERIAL_RUNTIME_HOOK 1 #endif -#define E_OPTARG(N) OPTARG(HAS_MULTI_EXTRUDER, N) -#define E_TERN_(N) TERN_(HAS_MULTI_EXTRUDER, N) -#define E_TERN0(N) TERN0(HAS_MULTI_EXTRUDER, N) +// FSMC/SPI TFT Panels +#if ENABLED(TFT_CLASSIC_UI) + #define TFT_SCALED_DOGLCD 1 +#endif -#if ENABLED(E_DUAL_STEPPER_DRIVERS) // E0/E1 steppers act in tandem as E0 +#if TFT_SCALED_DOGLCD + #define DOGLCD + #define IS_ULTIPANEL 1 + #define DELAYED_BACKLIGHT_INIT +#elif HAS_TFT_LVGL_UI + #define DELAYED_BACKLIGHT_INIT +#endif - #define E_STEPPERS 2 - #define E_MANUAL 1 +// Color UI +#if ENABLED(TFT_COLOR_UI) + #define HAS_GRAPHICAL_TFT 1 + #define IS_ULTIPANEL 1 +#endif -#elif ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS +/** + * I2C Panels + */ - #if EXTRUDERS > 4 - #define E_STEPPERS 3 - #elif EXTRUDERS > 2 - #define E_STEPPERS 2 - #else - #define E_STEPPERS 1 - #endif - #if DISABLED(SWITCHING_NOZZLE) - #define HOTENDS E_STEPPERS - #endif +#if ANY(IS_RRD_SC, IS_DOGM_12864, OLED_PANEL_TINYBOY2, LCD_I2C_PANELOLU2) -#elif ENABLED(MIXING_EXTRUDER) // Multiple feeds are mixed proportionally + #define STD_ENCODER_PULSES_PER_STEP 4 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 - #define E_STEPPERS MIXING_STEPPERS - #define E_MANUAL 1 - #if MIXING_STEPPERS == 2 - #define HAS_DUAL_MIXING 1 + #if ENABLED(LCD_I2C_PANELOLU2) // PANELOLU2 LCD with status LEDs, separate encoder and click inputs + #define LCD_I2C_TYPE_MCP23017 // I2C Character-based 12864 display + #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander + #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD (optional) + #define IS_ULTIPANEL 1 #endif -#elif ENABLED(SWITCHING_TOOLHEAD) // Toolchanger +#elif ANY(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) - #define E_STEPPERS EXTRUDERS - #define E_MANUAL EXTRUDERS + #define LCD_I2C_TYPE_PCF8575 // I2C Character-based 12864 display + #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander + #define IS_ULTIPANEL 1 -#elif HAS_PRUSA_MMU2 // Průša Multi-Material Unit v2 + #if ENABLED(LCD_SAINSMART_I2C_2004) + #define LCD_WIDTH 20 + #define LCD_HEIGHT 4 + #endif - #define E_STEPPERS 1 - #define E_MANUAL 1 +#elif ENABLED(LCD_I2C_VIKI) -#endif + /** + * Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs + * + * This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 ) + * Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory. + * Note: The pause/stop/resume LCD button pin should be connected to the Arduino + * BTN_ENC pin (or set BTN_ENC to -1 if not used) + */ + #define LCD_I2C_TYPE_MCP23017 + #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander + #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later) + #define IS_ULTIPANEL 1 -// No inactive extruders with SWITCHING_NOZZLE or Průša MMU1 -#if ENABLED(SWITCHING_NOZZLE) || HAS_PRUSA_MMU1 - #undef DISABLE_INACTIVE_EXTRUDER -#endif + #define ENCODER_FEEDRATE_DEADZONE 4 -// Průša MMU1, MMU(S) 2.0 and EXTENDABLE_EMU_MMU2(S) force SINGLENOZZLE -#if HAS_MMU - #define SINGLENOZZLE -#endif + #define STD_ENCODER_PULSES_PER_STEP 1 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 2 -#if EITHER(SINGLENOZZLE, MIXING_EXTRUDER) // One hotend, one thermistor, no XY offset - #undef HOTENDS - #define HOTENDS 1 - #undef HOTEND_OFFSET_X - #undef HOTEND_OFFSET_Y -#endif +#elif ENABLED(G3D_PANEL) -#ifndef HOTENDS - #define HOTENDS EXTRUDERS -#endif -#ifndef E_STEPPERS - #define E_STEPPERS EXTRUDERS -#endif -#ifndef E_MANUAL - #define E_MANUAL EXTRUDERS -#endif + #define STD_ENCODER_PULSES_PER_STEP 2 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 -#if E_STEPPERS <= 7 - #undef INVERT_E7_DIR - #undef E7_DRIVER_TYPE - #if E_STEPPERS <= 6 - #undef INVERT_E6_DIR - #undef E6_DRIVER_TYPE - #if E_STEPPERS <= 5 - #undef INVERT_E5_DIR - #undef E5_DRIVER_TYPE - #if E_STEPPERS <= 4 - #undef INVERT_E4_DIR - #undef E4_DRIVER_TYPE - #if E_STEPPERS <= 3 - #undef INVERT_E3_DIR - #undef E3_DRIVER_TYPE - #if E_STEPPERS <= 2 - #undef INVERT_E2_DIR - #undef E2_DRIVER_TYPE - #if E_STEPPERS <= 1 - #undef INVERT_E1_DIR - #undef E1_DRIVER_TYPE - #if E_STEPPERS == 0 - #undef INVERT_E0_DIR - #undef E0_DRIVER_TYPE - #endif - #endif - #endif - #endif - #endif - #endif - #endif #endif -/** - * Number of Linear Axes (e.g., XYZIJKUVW) - * All the logical axes except for the tool (E) axis - */ -#ifdef NUM_AXES - #undef NUM_AXES - #define NUM_AXES_WARNING 1 +#if ANY(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && DISABLED(NO_LCD_DETECT) + #define DETECT_I2C_LCD_DEVICE 1 #endif -#ifdef W_DRIVER_TYPE - #define NUM_AXES 9 -#elif defined(V_DRIVER_TYPE) - #define NUM_AXES 8 -#elif defined(U_DRIVER_TYPE) - #define NUM_AXES 7 -#elif defined(K_DRIVER_TYPE) - #define NUM_AXES 6 -#elif defined(J_DRIVER_TYPE) - #define NUM_AXES 5 -#elif defined(I_DRIVER_TYPE) - #define NUM_AXES 4 -#elif defined(Z_DRIVER_TYPE) - #define NUM_AXES 3 -#elif defined(Y_DRIVER_TYPE) - #define NUM_AXES 2 -#else - #define NUM_AXES 1 -#endif -#define HAS_X_AXIS 1 -#if NUM_AXES >= XY - #define HAS_Y_AXIS 1 - #if NUM_AXES >= XYZ - #define HAS_Z_AXIS 1 - #ifdef Z4_DRIVER_TYPE - #define NUM_Z_STEPPERS 4 - #elif defined(Z3_DRIVER_TYPE) - #define NUM_Z_STEPPERS 3 - #elif defined(Z2_DRIVER_TYPE) - #define NUM_Z_STEPPERS 2 - #else - #define NUM_Z_STEPPERS 1 - #endif - #if NUM_AXES >= 4 - #define HAS_I_AXIS 1 - #if NUM_AXES >= 5 - #define HAS_J_AXIS 1 - #if NUM_AXES >= 6 - #define HAS_K_AXIS 1 - #if NUM_AXES >= 7 - #define HAS_U_AXIS 1 - #if NUM_AXES >= 8 - #define HAS_V_AXIS 1 - #if NUM_AXES >= 9 - #define HAS_W_AXIS 1 - #endif - #endif - #endif - #endif - #endif - #endif +// Encoder behavior +#ifndef STD_ENCODER_PULSES_PER_STEP + #if ENABLED(TOUCH_SCREEN) + #define STD_ENCODER_PULSES_PER_STEP 2 + #else + #define STD_ENCODER_PULSES_PER_STEP 5 #endif #endif - -#if !HAS_Y_AXIS - #undef ENDSTOPPULLUP_YMIN - #undef ENDSTOPPULLUP_YMAX - #undef Y_MIN_ENDSTOP_INVERTING - #undef Y_MAX_ENDSTOP_INVERTING - #undef Y2_DRIVER_TYPE - #undef Y_ENABLE_ON - #undef DISABLE_Y - #undef INVERT_Y_DIR - #undef Y_HOME_DIR - #undef Y_MIN_POS - #undef Y_MAX_POS - #undef MANUAL_Y_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_Y - #undef MAX_SOFTWARE_ENDSTOP_Y -#endif - -#if !HAS_Z_AXIS - #undef ENDSTOPPULLUP_ZMIN - #undef ENDSTOPPULLUP_ZMAX - #undef Z_MIN_ENDSTOP_INVERTING - #undef Z_MAX_ENDSTOP_INVERTING - #undef Z2_DRIVER_TYPE - #undef Z3_DRIVER_TYPE - #undef Z4_DRIVER_TYPE - #undef Z_ENABLE_ON - #undef DISABLE_Z - #undef INVERT_Z_DIR - #undef Z_HOME_DIR - #undef Z_MIN_POS - #undef Z_MAX_POS - #undef MANUAL_Z_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_Z - #undef MAX_SOFTWARE_ENDSTOP_Z +#ifndef STD_ENCODER_STEPS_PER_MENU_ITEM + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 #endif - -#if !HAS_I_AXIS - #undef ENDSTOPPULLUP_IMIN - #undef ENDSTOPPULLUP_IMAX - #undef I_MIN_ENDSTOP_INVERTING - #undef I_MAX_ENDSTOP_INVERTING - #undef I_ENABLE_ON - #undef DISABLE_I - #undef INVERT_I_DIR - #undef I_HOME_DIR - #undef I_MIN_POS - #undef I_MAX_POS - #undef MANUAL_I_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_I - #undef MAX_SOFTWARE_ENDSTOP_I +#ifndef ENCODER_PULSES_PER_STEP + #define ENCODER_PULSES_PER_STEP STD_ENCODER_PULSES_PER_STEP #endif - -#if !HAS_J_AXIS - #undef ENDSTOPPULLUP_JMIN - #undef ENDSTOPPULLUP_JMAX - #undef J_MIN_ENDSTOP_INVERTING - #undef J_MAX_ENDSTOP_INVERTING - #undef J_ENABLE_ON - #undef DISABLE_J - #undef INVERT_J_DIR - #undef J_HOME_DIR - #undef J_MIN_POS - #undef J_MAX_POS - #undef MANUAL_J_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_J - #undef MAX_SOFTWARE_ENDSTOP_J +#ifndef ENCODER_STEPS_PER_MENU_ITEM + #define ENCODER_STEPS_PER_MENU_ITEM STD_ENCODER_STEPS_PER_MENU_ITEM #endif - -#if !HAS_K_AXIS - #undef ENDSTOPPULLUP_KMIN - #undef ENDSTOPPULLUP_KMAX - #undef K_MIN_ENDSTOP_INVERTING - #undef K_MAX_ENDSTOP_INVERTING - #undef K_ENABLE_ON - #undef DISABLE_K - #undef INVERT_K_DIR - #undef K_HOME_DIR - #undef K_MIN_POS - #undef K_MAX_POS - #undef MANUAL_K_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_K - #undef MAX_SOFTWARE_ENDSTOP_K +#ifndef ENCODER_FEEDRATE_DEADZONE + #define ENCODER_FEEDRATE_DEADZONE 6 #endif -#if !HAS_U_AXIS - #undef ENDSTOPPULLUP_UMIN - #undef ENDSTOPPULLUP_UMAX - #undef U_MIN_ENDSTOP_INVERTING - #undef U_MAX_ENDSTOP_INVERTING - #undef U_ENABLE_ON - #undef DISABLE_U - #undef INVERT_U_DIR - #undef U_HOME_DIR - #undef U_MIN_POS - #undef U_MAX_POS - #undef MANUAL_U_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_U - #undef MAX_SOFTWARE_ENDSTOP_U +// Shift register panels +// --------------------- +// 2 wire Non-latching LCD SR from: +// https://github.com/fmalpartida/New-LiquidCrystal/wiki/schematics#user-content-ShiftRegister_connection +#if ENABLED(FF_INTERFACEBOARD) + #define SR_LCD_3W_NL // Non latching 3 wire shift register + #define IS_ULTIPANEL 1 +#elif ENABLED(SAV_3DLCD) + #define SR_LCD_2W_NL // Non latching 2 wire shift register + #define IS_ULTIPANEL 1 +#elif ENABLED(ULTIPANEL) + #define IS_ULTIPANEL 1 #endif -#if !HAS_V_AXIS - #undef ENDSTOPPULLUP_VMIN - #undef ENDSTOPPULLUP_VMAX - #undef V_MIN_ENDSTOP_INVERTING - #undef V_MAX_ENDSTOP_INVERTING - #undef V_ENABLE_ON - #undef DISABLE_V - #undef INVERT_V_DIR - #undef V_HOME_DIR - #undef V_MIN_POS - #undef V_MAX_POS - #undef MANUAL_V_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_V - #undef MAX_SOFTWARE_ENDSTOP_V +#if ANY(IS_ULTIPANEL, ULTRA_LCD) + #define HAS_WIRED_LCD 1 #endif -#if !HAS_W_AXIS - #undef ENDSTOPPULLUP_WMIN - #undef ENDSTOPPULLUP_WMAX - #undef W_MIN_ENDSTOP_INVERTING - #undef W_MAX_ENDSTOP_INVERTING - #undef W_ENABLE_ON - #undef DISABLE_W - #undef INVERT_W_DIR - #undef W_HOME_DIR - #undef W_MIN_POS - #undef W_MAX_POS - #undef MANUAL_W_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_W - #undef MAX_SOFTWARE_ENDSTOP_W +#if ANY(IS_ULTIPANEL, REPRAPWORLD_KEYPAD) + #define IS_NEWPANEL 1 #endif -#ifdef X2_DRIVER_TYPE - #define HAS_X2_STEPPER 1 - // Dual X Carriage isn't known yet. TODO: Consider moving it to Configuration.h. +#if ANY(ZONESTAR_LCD, REPRAPWORLD_KEYPAD) + #define IS_RRW_KEYPAD 1 + #ifndef REPRAPWORLD_KEYPAD_MOVE_STEP + #define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0 + #endif #endif -#ifdef Y2_DRIVER_TYPE - #define HAS_Y2_STEPPER 1 - #define HAS_DUAL_Y_STEPPERS 1 + +// Aliases for LCD features +#if ANY(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS, DGUS_LCD_UI_RELOADED) + #define HAS_DGUS_LCD 1 + #if DISABLED(DGUS_LCD_UI_RELOADED) + #define HAS_DGUS_LCD_CLASSIC 1 + #endif #endif -/** - * Number of Primary Linear Axes (e.g., XYZ) - * X, XY, or XYZ axes. Excluding duplicate axes (X2, Y2, Z2, Z3, Z4) - */ -#if NUM_AXES >= 3 - #define PRIMARY_LINEAR_AXES 3 -#else - #define PRIMARY_LINEAR_AXES NUM_AXES +// Extensible UI serial touch screens. (See src/lcd/extui) +#if ANY(HAS_DGUS_LCD, MALYAN_LCD, ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, NEXTION_TFT, TOUCH_UI_FTDI_EVE) + #define IS_EXTUI 1 // Just for sanity check. + #define EXTENSIBLE_UI #endif -/** - * Number of Secondary Axes (e.g., IJKUVW) - * All linear/rotational axes between XYZ and E. - */ -#define SECONDARY_AXES SUB3(NUM_AXES) +// Aliases for LCD features +#if ANY(DWIN_CREALITY_LCD, DWIN_LCD_PROUI) + #define HAS_DWIN_E3V2_BASIC 1 +#endif +#if ANY(HAS_DWIN_E3V2_BASIC, DWIN_CREALITY_LCD_JYERSUI) + #define HAS_DWIN_E3V2 1 +#endif -/** - * Number of Rotational Axes (e.g., IJK) - * All axes for which AXIS*_ROTATES is defined. - * For these axes, positions are specified in angular degrees. - */ -#if ENABLED(AXIS9_ROTATES) - #define ROTATIONAL_AXES 6 -#elif ENABLED(AXIS8_ROTATES) - #define ROTATIONAL_AXES 5 -#elif ENABLED(AXIS7_ROTATES) - #define ROTATIONAL_AXES 4 -#elif ENABLED(AXIS6_ROTATES) - #define ROTATIONAL_AXES 3 -#elif ENABLED(AXIS5_ROTATES) - #define ROTATIONAL_AXES 2 -#elif ENABLED(AXIS4_ROTATES) - #define ROTATIONAL_AXES 1 -#else - #define ROTATIONAL_AXES 0 +// E3V2 extras +#if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI + #define SERIAL_CATCHALL 0 + #define HAS_LCD_BRIGHTNESS 1 + #define LCD_BRIGHTNESS_MAX 250 #endif -/** - * Number of Secondary Linear Axes (e.g., UVW) - * All secondary axes for which AXIS*_ROTATES is not defined. - * Excluding primary axes and excluding duplicate axes (X2, Y2, Z2, Z3, Z4) - */ -#define SECONDARY_LINEAR_AXES (NUM_AXES - PRIMARY_LINEAR_AXES - ROTATIONAL_AXES) +#if ENABLED(DWIN_LCD_PROUI) + #define DO_LIST_BIN_FILES 1 + #define LCD_BRIGHTNESS_DEFAULT 127 +#endif -/** - * Number of Logical Axes (e.g., XYZIJKUVWE) - * All logical axes that can be commanded directly by G-code. - * Delta maps stepper-specific values to ABC steppers. - */ -#if HAS_EXTRUDERS - #define LOGICAL_AXES INCREMENT(NUM_AXES) -#else - #define LOGICAL_AXES NUM_AXES +#if HAS_WIRED_LCD + #if ENABLED(DOGLCD) + #define HAS_MARLINUI_U8GLIB 1 + #elif IS_TFTGLCD_PANEL + // Neither DOGM nor HD44780. Fully customized interface. + #elif IS_DWIN_MARLINUI + // Since HAS_MARLINUI_U8GLIB refers to U8G displays + // the DWIN display can define its own flags + #elif !HAS_GRAPHICAL_TFT + #define HAS_MARLINUI_HD44780 1 + #endif #endif -/** - * DISTINCT_E_FACTORS is set to give extruders (some) individual settings. - * - * DISTINCT_AXES is the number of distinct addressable axes (not steppers). - * Includes all linear axes plus all distinguished extruders. - * The default behavior is to treat all extruders as a single E axis - * with shared motion and temperature settings. - * - * DISTINCT_E is the number of distinguished extruders. By default this - * will be 1 which indicates all extruders share the same settings. - * - * E_INDEX_N(E) should be used to get the E index of any item that might be - * distinguished. - */ -#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 - #define DISTINCT_AXES (NUM_AXES + E_STEPPERS) - #define DISTINCT_E E_STEPPERS - #define E_INDEX_N(E) (E) -#else - #undef DISTINCT_E_FACTORS - #define DISTINCT_AXES LOGICAL_AXES - #define DISTINCT_E 1 - #define E_INDEX_N(E) 0 +#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) + /** + * HAS_DISPLAY indicates the display uses these MarlinUI methods... + * - update + * - abort_print + * - pause_print + * - resume_print + * - poweroff (for PSU_CONTROL and HAS_MARLINUI_MENU) + * + * ...and implements these MarlinUI methods: + * - zoffset_overlay (if BABYSTEP_ZPROBE_GFX_OVERLAY or MESH_EDIT_GFX_OVERLAY are supported) + * - draw_kill_screen + * - kill_screen + * - draw_status_message + */ + #define HAS_DISPLAY 1 #endif -#if HOTENDS - #define HAS_HOTEND 1 - #ifndef HOTEND_OVERSHOOT - #define HOTEND_OVERSHOOT 15 - #endif - #if HOTENDS > 1 - #define HAS_MULTI_HOTEND 1 - #define HAS_HOTEND_OFFSET 1 - #endif -#else - #undef PID_PARAMS_PER_HOTEND +#if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT && !IS_DWIN_MARLINUI + #define HAS_LCDPRINT 1 #endif -// Helper macros for extruder and hotend arrays -#define _EXTRUDER_LOOP(E) for (int8_t E = 0; E < EXTRUDERS; E++) -#define EXTRUDER_LOOP() _EXTRUDER_LOOP(e) -#define _HOTEND_LOOP(H) for (int8_t H = 0; H < HOTENDS; H++) -#define HOTEND_LOOP() _HOTEND_LOOP(e) +#if HAS_DISPLAY || HAS_LCDPRINT + #define HAS_UTF8_UTILS 1 +#endif -#define ARRAY_BY_EXTRUDERS(V...) ARRAY_N(EXTRUDERS, V) -#define ARRAY_BY_EXTRUDERS1(v1) ARRAY_N_1(EXTRUDERS, v1) -#define ARRAY_BY_HOTENDS(V...) ARRAY_N(HOTENDS, V) -#define ARRAY_BY_HOTENDS1(v1) ARRAY_N_1(HOTENDS, v1) +#if ANY(HAS_DISPLAY, HAS_DWIN_E3V2) + #define HAS_STATUS_MESSAGE 1 +#endif -/** - * Default hotend offsets, if not defined - */ -#if HAS_HOTEND_OFFSET - #ifndef HOTEND_OFFSET_X - #define HOTEND_OFFSET_X { 0 } // X offsets for each extruder - #endif - #ifndef HOTEND_OFFSET_Y - #define HOTEND_OFFSET_Y { 0 } // Y offsets for each extruder +#if IS_ULTIPANEL && DISABLED(NO_LCD_MENUS) + #define HAS_MARLINUI_MENU 1 +#endif + +#if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, HAS_DWIN_E3V2) + #define HAS_MANUAL_MOVE_MENU 1 +#endif + +#if HAS_MARLINUI_U8GLIB + #ifndef LCD_PIXEL_WIDTH + #define LCD_PIXEL_WIDTH 128 #endif - #ifndef HOTEND_OFFSET_Z - #define HOTEND_OFFSET_Z { 0 } // Z offsets for each extruder + #ifndef LCD_PIXEL_HEIGHT + #define LCD_PIXEL_HEIGHT 64 #endif #endif @@ -1042,10 +1092,15 @@ #if DISABLED(SINGLENOZZLE) #undef SINGLENOZZLE_STANDBY_TEMP #endif -#if !BOTH(HAS_FAN, SINGLENOZZLE) +#if !ALL(HAS_FAN, SINGLENOZZLE) #undef SINGLENOZZLE_STANDBY_FAN #endif +// No inactive extruders with SWITCHING_NOZZLE or Průša MMU1 or just 1 E stepper exists +#if ENABLED(SWITCHING_NOZZLE) || HAS_PRUSA_MMU1 || E_STEPPERS < 2 + #undef DISABLE_INACTIVE_EXTRUDER +#endif + // Switching extruder has its own servo? #if ENABLED(SWITCHING_EXTRUDER) && (DISABLED(SWITCHING_NOZZLE) || SWITCHING_EXTRUDER_SERVO_NR != SWITCHING_NOZZLE_SERVO_NR) #define DO_SWITCH_EXTRUDER 1 @@ -1055,10 +1110,8 @@ * The BLTouch Probe emulates a servo probe * and uses "special" angles for its state. */ -#if ENABLED(BLTOUCH) - #ifndef Z_PROBE_SERVO_NR - #define Z_PROBE_SERVO_NR 0 - #endif +#if ENABLED(BLTOUCH) && !defined(Z_PROBE_SERVO_NR) + #define Z_PROBE_SERVO_NR 0 #endif /** @@ -1179,10 +1232,12 @@ #endif // FILAMENT_RUNOUT_SENSOR // Homing to Min or Max -#if X_HOME_DIR > 0 - #define X_HOME_TO_MAX 1 -#elif X_HOME_DIR < 0 - #define X_HOME_TO_MIN 1 +#if HAS_X_AXIS + #if X_HOME_DIR > 0 + #define X_HOME_TO_MAX 1 + #elif X_HOME_DIR < 0 + #define X_HOME_TO_MIN 1 + #endif #endif #if HAS_Y_AXIS #if Y_HOME_DIR > 0 @@ -1245,10 +1300,7 @@ * Conditionals based on the type of Bed Probe */ #if HAS_BED_PROBE - #if DISABLED(NOZZLE_AS_PROBE) - #define HAS_PROBE_XY_OFFSET 1 - #endif - #if BOTH(DELTA, SENSORLESS_PROBING) + #if ALL(DELTA, SENSORLESS_PROBING) #define HAS_DELTA_SENSORLESS_PROBING 1 #endif #if NONE(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, HAS_DELTA_SENSORLESS_PROBING) @@ -1257,12 +1309,18 @@ #if Z_HOME_TO_MIN && (DISABLED(USES_Z_MIN_PROBE_PIN) || ENABLED(USE_PROBE_FOR_Z_HOMING)) #define HOMING_Z_WITH_PROBE 1 #endif - #ifndef Z_PROBE_LOW_POINT - #define Z_PROBE_LOW_POINT -5 + #if DISABLED(NOZZLE_AS_PROBE) + #define HAS_PROBE_XY_OFFSET 1 #endif - #if EITHER(Z_PROBE_ALLEN_KEY, MAG_MOUNTED_PROBE) + #if ANY(Z_PROBE_ALLEN_KEY, MAG_MOUNTED_PROBE) #define PROBE_TRIGGERED_WHEN_STOWED_TEST 1 // Extra test for Allen Key Probe #endif + #ifndef Z_CLEARANCE_BETWEEN_PROBES + #define Z_CLEARANCE_BETWEEN_PROBES 5 + #endif + #ifndef Z_CLEARANCE_MULTI_PROBE + #define Z_CLEARANCE_MULTI_PROBE 5 + #endif #if MULTIPLE_PROBING > 1 #if EXTRA_PROBING > 0 #define TOTAL_PROBING (MULTIPLE_PROBING + EXTRA_PROBING) @@ -1275,6 +1333,30 @@ #undef Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN #undef USE_PROBE_FOR_Z_HOMING #undef Z_MIN_PROBE_REPEATABILITY_TEST + #undef HOMING_Z_WITH_PROBE + #undef Z_CLEARANCE_MULTI_PROBE + #undef MULTIPLE_PROBING + #undef EXTRA_PROBING + #undef PROBE_OFFSET_ZMIN + #undef PROBE_OFFSET_ZMAX + #undef PAUSE_BEFORE_DEPLOY_STOW + #undef PAUSE_PROBE_DEPLOY_WHEN_TRIGGERED + #undef PROBING_HEATERS_OFF + #undef WAIT_FOR_BED_HEATER + #undef WAIT_FOR_HOTEND + #undef PROBING_STEPPERS_OFF + #undef DELAY_BEFORE_PROBING + #undef PREHEAT_BEFORE_PROBING + #undef PROBING_NOZZLE_TEMP + #undef PROBING_BED_TEMP + #undef NOZZLE_TO_PROBE_OFFSET +#endif + +#ifndef Z_CLEARANCE_DEPLOY_PROBE + #define Z_CLEARANCE_DEPLOY_PROBE 10 +#endif +#ifndef Z_PROBE_LOW_POINT + #define Z_PROBE_LOW_POINT -5 #endif #if ENABLED(BELTPRINTER) && !defined(HOME_Y_BEFORE_X) @@ -1290,14 +1372,14 @@ */ #if ENABLED(AUTO_BED_LEVELING_UBL) #undef LCD_BED_LEVELING - #if EITHER(DELTA, SEGMENT_LEVELED_MOVES) + #if ANY(DELTA, SEGMENT_LEVELED_MOVES) #define UBL_SEGMENTED 1 #endif #endif -#if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) +#if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) #define ABL_PLANAR 1 #endif -#if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) +#if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) #define ABL_USES_GRID 1 #endif #if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_3POINT) @@ -1306,16 +1388,16 @@ #if ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL, MESH_BED_LEVELING) #define HAS_MESH 1 #endif -#if EITHER(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_3POINT) +#if ANY(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_3POINT) #define NEEDS_THREE_PROBE_POINTS 1 #endif -#if EITHER(HAS_ABL_NOT_UBL, AUTO_BED_LEVELING_UBL) +#if ANY(HAS_ABL_NOT_UBL, AUTO_BED_LEVELING_UBL) #define HAS_ABL_OR_UBL 1 #if DISABLED(PROBE_MANUALLY) #define HAS_AUTOLEVEL 1 #endif #endif -#if EITHER(HAS_ABL_OR_UBL, MESH_BED_LEVELING) +#if ANY(HAS_ABL_OR_UBL, MESH_BED_LEVELING) #define HAS_LEVELING 1 #if DISABLED(AUTO_BED_LEVELING_UBL) #define PLANNER_LEVELING 1 @@ -1326,7 +1408,7 @@ #undef ENABLE_LEVELING_AFTER_G28 #undef G29_RETRY_AND_RECOVER #endif -#if !HAS_LEVELING || EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) +#if !HAS_LEVELING || ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) #undef PROBE_MANUALLY #endif #if ANY(HAS_BED_PROBE, PROBE_MANUALLY, MESH_BED_LEVELING) @@ -1335,7 +1417,7 @@ #ifdef GRID_MAX_POINTS_X #define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y)) - #define GRID_LOOP(A,B) LOOP_L_N(A, GRID_MAX_POINTS_X) LOOP_L_N(B, GRID_MAX_POINTS_Y) + #define GRID_LOOP(A,B) for (uint8_t A = 0; A < GRID_MAX_POINTS_X; ++A) for (uint8_t B = 0; B < GRID_MAX_POINTS_Y; ++B) #endif // Slim menu optimizations @@ -1346,13 +1428,13 @@ /** * CoreXY, CoreXZ, and CoreYZ - and their reverse */ -#if EITHER(COREXY, COREYX) +#if ANY(COREXY, COREYX) #define CORE_IS_XY 1 #endif -#if EITHER(COREXZ, COREZX) +#if ANY(COREXZ, COREZX) #define CORE_IS_XZ 1 #endif -#if EITHER(COREYZ, COREZY) +#if ANY(COREYZ, COREZY) #define CORE_IS_YZ 1 #endif #if CORE_IS_XY || CORE_IS_XZ || CORE_IS_YZ @@ -1373,7 +1455,7 @@ #define CORE_AXIS_2 C_AXIS #endif #define CORESIGN(n) (ANY(COREYX, COREZX, COREZY) ? (-(n)) : (n)) -#elif EITHER(MARKFORGED_XY, MARKFORGED_YX) +#elif ANY(MARKFORGED_XY, MARKFORGED_YX) // Markforged kinematics #define CORE_AXIS_1 A_AXIS #define CORE_AXIS_2 B_AXIS @@ -1383,7 +1465,7 @@ #if ANY(MORGAN_SCARA, MP_SCARA, AXEL_TPARA) #define IS_SCARA 1 #define IS_KINEMATIC 1 -#elif EITHER(DELTA, POLARGRAPH) +#elif ANY(DELTA, POLARGRAPH) #define IS_KINEMATIC 1 #else #define IS_CARTESIAN 1 @@ -1396,20 +1478,6 @@ #undef DELTA_HOME_TO_SAFE_ZONE #endif -// This flag indicates some kind of jerk storage is needed -#if EITHER(CLASSIC_JERK, IS_KINEMATIC) - #define HAS_CLASSIC_JERK 1 -#endif - -#if DISABLED(CLASSIC_JERK) - #define HAS_JUNCTION_DEVIATION 1 -#endif - -// E jerk exists with JD disabled (of course) but also when Linear Advance is disabled on Delta/SCARA -#if HAS_EXTRUDERS && (ENABLED(CLASSIC_JERK) || (IS_KINEMATIC && DISABLED(LIN_ADVANCE))) - #define HAS_CLASSIC_E_JERK 1 -#endif - // // Serial Port Info // @@ -1457,12 +1525,12 @@ * - TFT_COLOR * - GRAPHICAL_TFT_UPSCALE */ -#if EITHER(MKS_TS35_V2_0, BTT_TFT35_SPI_V1_0) // ST7796 +#if ANY(MKS_TS35_V2_0, BTT_TFT35_SPI_V1_0) // ST7796 #define TFT_DEFAULT_DRIVER ST7796 #define TFT_DEFAULT_ORIENTATION TFT_EXCHANGE_XY #define TFT_RES_480x320 #define TFT_INTERFACE_SPI -#elif EITHER(LERDGE_TFT35, ANET_ET5_TFT35) // ST7796 +#elif ANY(LERDGE_TFT35, ANET_ET5_TFT35) // ST7796 #define TFT_DEFAULT_ORIENTATION TFT_EXCHANGE_XY #define TFT_RES_480x320 #define TFT_INTERFACE_FSMC @@ -1480,7 +1548,7 @@ #define TFT_DEFAULT_ORIENTATION 0 #define TFT_RES_480x272 #define TFT_INTERFACE_FSMC -#elif EITHER(MKS_ROBIN_TFT_V1_1R, LONGER_LK_TFT28) // ILI9328 or R61505 +#elif ANY(MKS_ROBIN_TFT_V1_1R, LONGER_LK_TFT28) // ILI9328 or R61505 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC @@ -1501,30 +1569,6 @@ #endif #endif -#if ENABLED(TFT_RES_320x240) - #define TFT_WIDTH 320 - #define TFT_HEIGHT 240 - #define GRAPHICAL_TFT_UPSCALE 2 -#elif ENABLED(TFT_RES_480x272) - #define TFT_WIDTH 480 - #define TFT_HEIGHT 272 - #define GRAPHICAL_TFT_UPSCALE 2 -#elif ENABLED(TFT_RES_480x320) - #define TFT_WIDTH 480 - #define TFT_HEIGHT 320 - #define GRAPHICAL_TFT_UPSCALE 3 -#elif ENABLED(TFT_RES_1024x600) - #define TFT_WIDTH 1024 - #define TFT_HEIGHT 600 - #if ENABLED(TOUCH_SCREEN) - #define GRAPHICAL_TFT_UPSCALE 6 - #define TFT_PIXEL_OFFSET_X 120 - #else - #define GRAPHICAL_TFT_UPSCALE 8 - #define TFT_PIXEL_OFFSET_X 0 - #endif -#endif - // FSMC/SPI TFT Panels using standard HAL/tft/tft_(fsmc|spi|ltdc).h #if ENABLED(TFT_INTERFACE_FSMC) #define HAS_FSMC_TFT 1 @@ -1549,14 +1593,52 @@ #endif #endif +#if ANY(HAS_SPI_TFT, HAS_FSMC_TFT, HAS_LTDC_TFT) + #include "../lcd/tft_io/tft_orientation.h" // for TFT_COLOR_UI_PORTRAIT +#endif + +#if ENABLED(TFT_RES_320x240) + #if ENABLED(TFT_COLOR_UI_PORTRAIT) + #define TFT_WIDTH 240 + #define TFT_HEIGHT 320 + #else + #define TFT_WIDTH 320 + #define TFT_HEIGHT 240 + #endif + #define GRAPHICAL_TFT_UPSCALE 2 +#elif ENABLED(TFT_RES_480x272) + #define TFT_WIDTH 480 + #define TFT_HEIGHT 272 + #define GRAPHICAL_TFT_UPSCALE 2 +#elif ENABLED(TFT_RES_480x320) + #if ENABLED(TFT_COLOR_UI_PORTRAIT) + #define TFT_WIDTH 320 + #define TFT_HEIGHT 480 + #else + #define TFT_WIDTH 480 + #define TFT_HEIGHT 320 + #endif + #define GRAPHICAL_TFT_UPSCALE 3 +#elif ENABLED(TFT_RES_1024x600) + #define TFT_WIDTH 1024 + #define TFT_HEIGHT 600 + #if ENABLED(TOUCH_SCREEN) + #define GRAPHICAL_TFT_UPSCALE 6 + #define TFT_PIXEL_OFFSET_X 120 + #else + #define GRAPHICAL_TFT_UPSCALE 8 + #define TFT_PIXEL_OFFSET_X 0 + #endif +#endif + #if ENABLED(TFT_COLOR_UI) - #if TFT_HEIGHT == 240 + #if (TFT_WIDTH == 320 && TFT_HEIGHT == 240) || (TFT_WIDTH == 240 && TFT_HEIGHT == 320) #if ENABLED(TFT_INTERFACE_SPI) #define TFT_320x240_SPI #elif ENABLED(TFT_INTERFACE_FSMC) #define TFT_320x240 #endif - #elif TFT_HEIGHT == 320 + #elif TFT_HEIGHT == 320 || (TFT_HEIGHT == 480 && ENABLED(TFT_COLOR_UI_PORTRAIT)) #if ENABLED(TFT_INTERFACE_SPI) #define TFT_480x320_SPI #elif ENABLED(TFT_INTERFACE_FSMC) @@ -1577,13 +1659,13 @@ #endif #endif -#if EITHER(TFT_320x240, TFT_320x240_SPI) +#if ANY(TFT_320x240, TFT_320x240_SPI) #define HAS_UI_320x240 1 -#elif EITHER(TFT_480x320, TFT_480x320_SPI) +#elif ANY(TFT_480x320, TFT_480x320_SPI) #define HAS_UI_480x320 1 -#elif EITHER(TFT_480x272, TFT_480x272_SPI) +#elif ANY(TFT_480x272, TFT_480x272_SPI) #define HAS_UI_480x272 1 -#elif EITHER(TFT_1024x600_LTDC, TFT_1024x600_SIM) +#elif ANY(TFT_1024x600_LTDC, TFT_1024x600_SIM) #define HAS_UI_1024x600 1 #endif #if ANY(HAS_UI_320x240, HAS_UI_480x320, HAS_UI_480x272) @@ -1617,18 +1699,7 @@ #endif #endif -// XPT2046_** Compatibility -#if !(defined(TOUCH_CALIBRATION_X) || defined(TOUCH_CALIBRATION_Y) || defined(TOUCH_OFFSET_X) || defined(TOUCH_OFFSET_Y) || defined(TOUCH_ORIENTATION)) - #if defined(XPT2046_X_CALIBRATION) && defined(XPT2046_Y_CALIBRATION) && defined(XPT2046_X_OFFSET) && defined(XPT2046_Y_OFFSET) - #define TOUCH_CALIBRATION_X XPT2046_X_CALIBRATION - #define TOUCH_CALIBRATION_Y XPT2046_Y_CALIBRATION - #define TOUCH_OFFSET_X XPT2046_X_OFFSET - #define TOUCH_OFFSET_Y XPT2046_Y_OFFSET - #define TOUCH_ORIENTATION TOUCH_LANDSCAPE - #endif -#endif - -#if X_HOME_DIR || (HAS_Y_AXIS && Y_HOME_DIR) || (HAS_Z_AXIS && Z_HOME_DIR) \ +#if (HAS_X_AXIS && 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) \ || (HAS_U_AXIS && U_HOME_DIR) || (HAS_V_AXIS && V_HOME_DIR) || (HAS_W_AXIS && W_HOME_DIR) #define HAS_ENDSTOPS 1 @@ -1643,3 +1714,7 @@ #if defined(NEOPIXEL_BKGD_INDEX_FIRST) && !defined(NEOPIXEL_BKGD_INDEX_LAST) #define NEOPIXEL_BKGD_INDEX_LAST NEOPIXEL_BKGD_INDEX_FIRST #endif + +#if ALL(SPI_FLASH, HAS_MEDIA, MARLIN_DEV_MODE) + #define SPI_FLASH_BACKUP 1 +#endif diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index faf882389179..ef404d271e64 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -37,19 +37,19 @@ // Determine NUM_SERVOS if none was supplied #ifndef NUM_SERVOS #define NUM_SERVOS 0 - #if ANY(HAS_Z_SERVO_PROBE, CHAMBER_VENT, SWITCHING_TOOLHEAD, SWITCHING_EXTRUDER, SWITCHING_NOZZLE, SPINDLE_SERVO) - #if NUM_SERVOS <= Z_PROBE_SERVO_NR - #undef NUM_SERVOS - #define NUM_SERVOS (Z_PROBE_SERVO_NR + 1) - #endif - #if NUM_SERVOS <= CHAMBER_VENT_SERVO_NR - #undef NUM_SERVOS - #define NUM_SERVOS (CHAMBER_VENT_SERVO_NR + 1) - #endif - #if NUM_SERVOS <= SWITCHING_TOOLHEAD_SERVO_NR - #undef NUM_SERVOS - #define NUM_SERVOS (SWITCHING_TOOLHEAD_SERVO_NR + 1) - #endif + #if HAS_Z_SERVO_PROBE && NUM_SERVOS <= Z_PROBE_SERVO_NR + #undef NUM_SERVOS + #define NUM_SERVOS (Z_PROBE_SERVO_NR + 1) + #endif + #if ENABLED(CHAMBER_VENT) && NUM_SERVOS <= CHAMBER_VENT_SERVO_NR + #undef NUM_SERVOS + #define NUM_SERVOS (CHAMBER_VENT_SERVO_NR + 1) + #endif + #if ENABLED(SWITCHING_TOOLHEAD) && NUM_SERVOS <= SWITCHING_TOOLHEAD_SERVO_NR + #undef NUM_SERVOS + #define NUM_SERVOS (SWITCHING_TOOLHEAD_SERVO_NR + 1) + #endif + #if ENABLED(SWITCHING_NOZZLE) #if NUM_SERVOS <= SWITCHING_NOZZLE_SERVO_NR #undef NUM_SERVOS #define NUM_SERVOS (SWITCHING_NOZZLE_SERVO_NR + 1) @@ -58,6 +58,8 @@ #undef NUM_SERVOS #define NUM_SERVOS (SWITCHING_NOZZLE_E1_SERVO_NR + 1) #endif + #endif + #if ENABLED(SWITCHING_EXTRUDER) #if NUM_SERVOS <= SWITCHING_EXTRUDER_SERVO_NR #undef NUM_SERVOS #define NUM_SERVOS (SWITCHING_EXTRUDER_SERVO_NR + 1) @@ -66,12 +68,12 @@ #undef NUM_SERVOS #define NUM_SERVOS (SWITCHING_EXTRUDER_E23_SERVO_NR + 1) #endif - #if NUM_SERVOS <= SPINDLE_SERVO_NR - #undef NUM_SERVOS - #define NUM_SERVOS (SPINDLE_SERVO_NR + 1) - #endif #endif -#endif + #if ENABLED(SPINDLE_SERVO) && NUM_SERVOS <= SPINDLE_SERVO_NR + #undef NUM_SERVOS + #define NUM_SERVOS (SPINDLE_SERVO_NR + 1) + #endif +#endif // !defined(NUM_SERVOS) // Convenience override for a BLTouch alone #if ENABLED(BLTOUCH) && NUM_SERVOS == 1 @@ -87,70 +89,197 @@ #endif // Some options are disallowed without required axes +#if !HAS_X_AXIS + //#define LCD_SHOW_E_TOTAL + #define NO_WORKSPACE_OFFSETS + #undef AUTOTEMP + #undef CALIBRATION_MEASURE_LEFT + #undef CALIBRATION_MEASURE_RIGHT + #undef DISABLE_IDLE_X + #undef INPUT_SHAPING_X + #undef SAFE_BED_LEVELING_START_X + #undef SHAPING_FREQ_X + #undef STEALTHCHOP_X + #undef INVERT_X_STEP_PIN +#endif + #if !HAS_Y_AXIS - #undef SAFE_BED_LEVELING_START_Y #undef ARC_SUPPORT + #undef CALIBRATION_MEASURE_BACK + #undef CALIBRATION_MEASURE_FRONT + #undef DISABLE_IDLE_Y + #undef HOME_Y_BEFORE_X #undef INPUT_SHAPING_Y + #undef QUICK_HOME + #undef SAFE_BED_LEVELING_START_Y #undef SHAPING_FREQ_Y - #undef SHAPING_BUFFER_Y + #undef STEALTHCHOP_Y + #undef INVERT_Y_STEP_PIN #endif + #if !HAS_Z_AXIS + #undef CNC_WORKSPACE_PLANES + #undef DISABLE_IDLE_Z + #undef ENABLE_LEVELING_FADE_HEIGHT + #undef HOME_Z_FIRST + #undef HOMING_Z_WITH_PROBE + #undef NUM_Z_STEPPERS #undef SAFE_BED_LEVELING_START_Z + #undef STEALTHCHOP_Z + #undef INVERT_Z_STEP_PIN + #undef Z_IDLE_HEIGHT + #undef Z_PROBE_SLED + #undef Z_SAFE_HOMING #endif + #if !HAS_I_AXIS + #undef CALIBRATION_MEASURE_IMAX + #undef CALIBRATION_MEASURE_IMIN + #undef DISABLE_IDLE_I #undef SAFE_BED_LEVELING_START_I + #undef STEALTHCHOP_I + #undef INVERT_I_STEP_PIN #endif + #if !HAS_J_AXIS + #undef CALIBRATION_MEASURE_JMAX + #undef CALIBRATION_MEASURE_JMIN + #undef DISABLE_IDLE_J #undef SAFE_BED_LEVELING_START_J + #undef STEALTHCHOP_J + #undef INVERT_J_STEP_PIN #endif + #if !HAS_K_AXIS + #undef CALIBRATION_MEASURE_KMAX + #undef CALIBRATION_MEASURE_KMIN + #undef DISABLE_IDLE_K #undef SAFE_BED_LEVELING_START_K + #undef STEALTHCHOP_K + #undef INVERT_K_STEP_PIN #endif + #if !HAS_U_AXIS + #undef CALIBRATION_MEASURE_UMAX + #undef CALIBRATION_MEASURE_UMIN + #undef DISABLE_IDLE_U #undef SAFE_BED_LEVELING_START_U + #undef STEALTHCHOP_U + #undef INVERT_U_STEP_PIN #endif + #if !HAS_V_AXIS + #undef CALIBRATION_MEASURE_VMAX + #undef CALIBRATION_MEASURE_VMIN + #undef DISABLE_IDLE_V #undef SAFE_BED_LEVELING_START_V + #undef STEALTHCHOP_V + #undef INVERT_V_STEP_PIN #endif + #if !HAS_W_AXIS + #undef CALIBRATION_MEASURE_WMAX + #undef CALIBRATION_MEASURE_WMIN + #undef DISABLE_IDLE_W #undef SAFE_BED_LEVELING_START_W + #undef STEALTHCHOP_W + #undef INVERT_W_STEP_PIN #endif // Disallowed with no extruders #if !HAS_EXTRUDERS #define NO_VOLUMETRICS - #undef FWRETRACT - #undef PIDTEMP - #undef AUTOTEMP - #undef PID_EXTRUSION_SCALING - #undef LIN_ADVANCE #undef ADVANCED_PAUSE_FEATURE - #undef FILAMENT_LOAD_UNLOAD_GCODES + #undef DISABLE_IDLE_E #undef EXTRUDER_RUNOUT_PREVENT - #undef THERMAL_PROTECTION_PERIOD - #undef WATCH_TEMP_PERIOD - #undef SHOW_TEMP_ADC_VALUES + #undef FILAMENT_LOAD_UNLOAD_GCODES + #undef FWRETRACT #undef LCD_SHOW_E_TOTAL + #undef LIN_ADVANCE #undef MANUAL_E_MOVES_RELATIVE + #undef PID_EXTRUSION_SCALING + #undef SHOW_TEMP_ADC_VALUES #undef STEALTHCHOP_E #endif -#if HOTENDS <= 7 +#if ENABLED(DISABLE_X) && !defined(DISABLE_IDLE_X) + #define DISABLE_IDLE_X +#endif +#if ENABLED(DISABLE_Y) && !defined(DISABLE_IDLE_Y) + #define DISABLE_IDLE_Y +#endif +#if ENABLED(DISABLE_Z) && !defined(DISABLE_IDLE_Z) + #define DISABLE_IDLE_Z +#endif +#if ENABLED(DISABLE_I) && !defined(DISABLE_IDLE_I) + #define DISABLE_IDLE_I +#endif +#if ENABLED(DISABLE_J) && !defined(DISABLE_IDLE_J) + #define DISABLE_IDLE_J +#endif +#if ENABLED(DISABLE_K) && !defined(DISABLE_IDLE_K) + #define DISABLE_IDLE_K +#endif +#if ENABLED(DISABLE_U) && !defined(DISABLE_IDLE_U) + #define DISABLE_IDLE_U +#endif +#if ENABLED(DISABLE_V) && !defined(DISABLE_IDLE_V) + #define DISABLE_IDLE_V +#endif +#if ENABLED(DISABLE_W) && !defined(DISABLE_IDLE_W) + #define DISABLE_IDLE_W +#endif +#if ENABLED(DISABLE_E) && !defined(DISABLE_IDLE_E) + #define DISABLE_IDLE_E +#endif + +#define _OR_HAS_DI(A) || ALL(HAS_##A##_AXIS, DISABLE_IDLE_##A) +#if ALL(HAS_EXTRUDERS, DISABLE_IDLE_E) MAP(_OR_HAS_DI, X, Y, Z, I, J, K, U, V, W) + #define HAS_DISABLE_IDLE_AXES 1 +#endif +#undef _OR_HAS_DI + +// Remove hotend-dependent settings +#if HOTENDS < 8 #undef E7_AUTO_FAN_PIN - #if HOTENDS <= 6 + #undef HEATER_7_MAXTEMP + #undef HEATER_7_MINTEMP + #if HOTENDS < 7 #undef E6_AUTO_FAN_PIN - #if HOTENDS <= 5 + #undef HEATER_6_MAXTEMP + #undef HEATER_6_MINTEMP + #if HOTENDS < 6 #undef E5_AUTO_FAN_PIN - #if HOTENDS <= 4 + #undef HEATER_5_MAXTEMP + #undef HEATER_5_MINTEMP + #if HOTENDS < 5 #undef E4_AUTO_FAN_PIN - #if HOTENDS <= 3 + #undef HEATER_4_MAXTEMP + #undef HEATER_4_MINTEMP + #if HOTENDS < 4 #undef E3_AUTO_FAN_PIN - #if HOTENDS <= 2 + #undef HEATER_3_MAXTEMP + #undef HEATER_3_MINTEMP + #if HOTENDS < 3 #undef E2_AUTO_FAN_PIN - #if HOTENDS <= 1 + #undef HEATER_2_MAXTEMP + #undef HEATER_2_MINTEMP + #if HOTENDS < 2 #undef E1_AUTO_FAN_PIN - #if HOTENDS == 0 + #undef HEATER_1_MAXTEMP + #undef HEATER_1_MINTEMP + #if HOTENDS < 1 + #undef AUTOTEMP #undef E0_AUTO_FAN_PIN + #undef HEATER_0_MAXTEMP + #undef HEATER_0_MINTEMP + #undef PID_PARAMS_PER_HOTEND + #undef PIDTEMP + #undef MPCTEMP + #undef PREVENT_COLD_EXTRUSION + #undef THERMAL_PROTECTION_HOTENDS + #undef THERMAL_PROTECTION_PERIOD + #undef WATCH_TEMP_PERIOD #endif #endif #endif @@ -160,11 +289,32 @@ #endif #endif +// This flag indicates some kind of jerk storage is needed +#if ANY(CLASSIC_JERK, IS_KINEMATIC) + #define HAS_CLASSIC_JERK 1 +#endif + +// Use Junction Deviation for motion if Jerk is disabled +#if DISABLED(CLASSIC_JERK) + #define HAS_JUNCTION_DEVIATION 1 +#endif + +// E jerk exists with JD disabled (of course) but also when Linear Advance is disabled on Delta/SCARA +#if HAS_EXTRUDERS && (ENABLED(CLASSIC_JERK) || (IS_KINEMATIC && DISABLED(LIN_ADVANCE))) + #define HAS_CLASSIC_E_JERK 1 +#endif + +// Linear advance uses Jerk since E is an isolated axis +#if ALL(HAS_JUNCTION_DEVIATION, LIN_ADVANCE) + #define HAS_LINEAR_E_JERK 1 +#endif + /** * Temperature Sensors; define what sensor(s) we have. */ // Temperature sensor IDs +#define HID_NONE -128 #define HID_REDUNDANT -6 #define HID_BOARD -5 #define HID_COOLER -4 @@ -183,9 +333,8 @@ #define _SENSOR_IS(I,N) || (TEMP_SENSOR(N) == I) #define _E_SENSOR_IS(I,N) _SENSOR_IS(N,I) #define ANY_E_SENSOR_IS(N) (0 REPEAT2(HOTENDS, _E_SENSOR_IS, N)) -#define ANY_THERMISTOR_IS(N) ( ANY_E_SENSOR_IS(N) \ - _SENSOR_IS(N,BED) _SENSOR_IS(N,PROBE) _SENSOR_IS(N,CHAMBER) \ - _SENSOR_IS(N,COOLER) _SENSOR_IS(N,BOARD) _SENSOR_IS(N,REDUNDANT) ) +#define ANY_THERMISTOR_IS(N) ( ANY_E_SENSOR_IS(N) _SENSOR_IS(N,REDUNDANT) \ + _SENSOR_IS(N,BED) _SENSOR_IS(N,PROBE) _SENSOR_IS(N,CHAMBER) _SENSOR_IS(N,COOLER) _SENSOR_IS(N,BOARD) ) #if ANY_THERMISTOR_IS(1000) #define HAS_USER_THERMISTORS 1 @@ -223,15 +372,13 @@ #define TEMP_SENSOR_0_IS_AD8495 1 #elif TEMP_SENSOR_0 == -1 #define TEMP_SENSOR_0_IS_AD595 1 -#elif TEMP_SENSOR_0 == 1000 - #define TEMP_SENSOR_0_IS_CUSTOM 1 -#elif TEMP_SENSOR_0 == 998 || TEMP_SENSOR_0 == 999 - #define TEMP_SENSOR_0_IS_DUMMY 1 #elif TEMP_SENSOR_0 > 0 #define TEMP_SENSOR_0_IS_THERMISTOR 1 -#else - #undef HEATER_0_MINTEMP - #undef HEATER_0_MAXTEMP + #if TEMP_SENSOR_0 == 1000 + #define TEMP_SENSOR_0_IS_CUSTOM 1 + #elif TEMP_SENSOR_0 == 998 || TEMP_SENSOR_0 == 999 + #define TEMP_SENSOR_0_IS_DUMMY 1 + #endif #endif #if TEMP_SENSOR_IS_MAX_TC(1) @@ -268,15 +415,13 @@ #define TEMP_SENSOR_1_IS_AD8495 1 #elif TEMP_SENSOR_1 == -1 #define TEMP_SENSOR_1_IS_AD595 1 -#elif TEMP_SENSOR_1 == 1000 - #define TEMP_SENSOR_1_IS_CUSTOM 1 -#elif TEMP_SENSOR_1 == 998 || TEMP_SENSOR_1 == 999 - #define TEMP_SENSOR_1_IS_DUMMY 1 #elif TEMP_SENSOR_1 > 0 #define TEMP_SENSOR_1_IS_THERMISTOR 1 -#else - #undef HEATER_1_MINTEMP - #undef HEATER_1_MAXTEMP + #if TEMP_SENSOR_1 == 1000 + #define TEMP_SENSOR_1_IS_CUSTOM 1 + #elif TEMP_SENSOR_1 == 998 || TEMP_SENSOR_1 == 999 + #define TEMP_SENSOR_1_IS_DUMMY 1 + #endif #endif #if TEMP_SENSOR_IS_MAX_TC(2) @@ -313,100 +458,90 @@ #define TEMP_SENSOR_2_IS_AD8495 1 #elif TEMP_SENSOR_2 == -1 #define TEMP_SENSOR_2_IS_AD595 1 -#elif TEMP_SENSOR_2 == 1000 - #define TEMP_SENSOR_2_IS_CUSTOM 1 -#elif TEMP_SENSOR_2 == 998 || TEMP_SENSOR_2 == 999 - #define TEMP_SENSOR_2_IS_DUMMY 1 #elif TEMP_SENSOR_2 > 0 #define TEMP_SENSOR_2_IS_THERMISTOR 1 -#else - #undef HEATER_2_MINTEMP - #undef HEATER_2_MAXTEMP + #if TEMP_SENSOR_2 == 1000 + #define TEMP_SENSOR_2_IS_CUSTOM 1 + #elif TEMP_SENSOR_2 == 998 || TEMP_SENSOR_2 == 999 + #define TEMP_SENSOR_2_IS_DUMMY 1 + #endif #endif -#if TEMP_SENSOR_3 == 1000 - #define TEMP_SENSOR_3_IS_CUSTOM 1 -#elif TEMP_SENSOR_3 == 998 || TEMP_SENSOR_3 == 999 - #define TEMP_SENSOR_3_IS_DUMMY 1 -#elif TEMP_SENSOR_3 > 0 +#if TEMP_SENSOR_3 > 0 #define TEMP_SENSOR_3_IS_THERMISTOR 1 -#elif !TEMP_SENSOR_3 - #undef HEATER_3_MINTEMP - #undef HEATER_3_MAXTEMP + #if TEMP_SENSOR_3 == 1000 + #define TEMP_SENSOR_3_IS_CUSTOM 1 + #elif TEMP_SENSOR_3 == 998 || TEMP_SENSOR_3 == 999 + #define TEMP_SENSOR_3_IS_DUMMY 1 + #endif #endif -#if TEMP_SENSOR_4 == 1000 - #define TEMP_SENSOR_4_IS_CUSTOM 1 -#elif TEMP_SENSOR_4 == 998 || TEMP_SENSOR_4 == 999 - #define TEMP_SENSOR_4_IS_DUMMY 1 -#elif TEMP_SENSOR_4 > 0 +#if TEMP_SENSOR_4 > 0 #define TEMP_SENSOR_4_IS_THERMISTOR 1 -#elif !TEMP_SENSOR_4 - #undef HEATER_4_MINTEMP - #undef HEATER_4_MAXTEMP + #if TEMP_SENSOR_4 == 1000 + #define TEMP_SENSOR_4_IS_CUSTOM 1 + #elif TEMP_SENSOR_4 == 998 || TEMP_SENSOR_4 == 999 + #define TEMP_SENSOR_4_IS_DUMMY 1 + #endif #endif -#if TEMP_SENSOR_5 == 1000 - #define TEMP_SENSOR_5_IS_CUSTOM 1 -#elif TEMP_SENSOR_5 == 998 || TEMP_SENSOR_5 == 999 - #define TEMP_SENSOR_5_IS_DUMMY 1 -#elif TEMP_SENSOR_5 > 0 +#if TEMP_SENSOR_5 > 0 #define TEMP_SENSOR_5_IS_THERMISTOR 1 -#elif !TEMP_SENSOR_5 - #undef HEATER_5_MINTEMP - #undef HEATER_5_MAXTEMP + #if TEMP_SENSOR_5 == 1000 + #define TEMP_SENSOR_5_IS_CUSTOM 1 + #elif TEMP_SENSOR_5 == 998 || TEMP_SENSOR_5 == 999 + #define TEMP_SENSOR_5_IS_DUMMY 1 + #endif #endif -#if TEMP_SENSOR_6 == 1000 - #define TEMP_SENSOR_6_IS_CUSTOM 1 -#elif TEMP_SENSOR_6 == 998 || TEMP_SENSOR_6 == 999 - #define TEMP_SENSOR_6_IS_DUMMY 1 -#elif TEMP_SENSOR_6 > 0 +#if TEMP_SENSOR_6 > 0 #define TEMP_SENSOR_6_IS_THERMISTOR 1 -#elif !TEMP_SENSOR_6 - #undef HEATER_6_MINTEMP - #undef HEATER_6_MAXTEMP + #if TEMP_SENSOR_6 == 1000 + #define TEMP_SENSOR_6_IS_CUSTOM 1 + #elif TEMP_SENSOR_6 == 998 || TEMP_SENSOR_6 == 999 + #define TEMP_SENSOR_6_IS_DUMMY 1 + #endif #endif -#if TEMP_SENSOR_7 == 1000 - #define TEMP_SENSOR_7_IS_CUSTOM 1 -#elif TEMP_SENSOR_7 == 998 || TEMP_SENSOR_7 == 999 - #define TEMP_SENSOR_7_IS_DUMMY 1 -#elif TEMP_SENSOR_7 > 0 +#if TEMP_SENSOR_7 > 0 #define TEMP_SENSOR_7_IS_THERMISTOR 1 -#elif !TEMP_SENSOR_7 - #undef HEATER_7_MINTEMP - #undef HEATER_7_MAXTEMP + #if TEMP_SENSOR_7 == 1000 + #define TEMP_SENSOR_7_IS_CUSTOM 1 + #elif TEMP_SENSOR_7 == 998 || TEMP_SENSOR_7 == 999 + #define TEMP_SENSOR_7_IS_DUMMY 1 + #endif #endif #if TEMP_SENSOR_IS_MAX_TC(REDUNDANT) + #define _REDUNDANT_E (REDUNDANT_TEMP_MATCH(SOURCE, E0) || REDUNDANT_TEMP_MATCH(SOURCE, E1) || REDUNDANT_TEMP_MATCH(SOURCE, E2)) #if TEMP_SENSOR_REDUNDANT == -5 - #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) && !REDUNDANT_TEMP_MATCH(SOURCE, E2) - #error "MAX31865 Thermocouples (-5) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 (0/1/2)." + #if !_REDUNDANT_E + #error "MAX31865 Thermocouples (-5) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_[0-2]." #endif #define TEMP_SENSOR_REDUNDANT_IS_MAX31865 1 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 #elif TEMP_SENSOR_REDUNDANT == -3 - #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) && !REDUNDANT_TEMP_MATCH(SOURCE, E2) - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 (0/1/2)." + #if !_REDUNDANT_E + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_[0-2]." #endif #define TEMP_SENSOR_REDUNDANT_IS_MAX31855 1 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN -270 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1800 #elif TEMP_SENSOR_REDUNDANT == -2 - #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) && !REDUNDANT_TEMP_MATCH(SOURCE, E2) - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 (0/1/2)." + #if !_REDUNDANT_E + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_[0-2]." #endif #define TEMP_SENSOR_REDUNDANT_IS_MAX6675 1 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 #endif + #undef _REDUNDANT_E - // mimic setting up the source TEMP_SENSOR + // Mimic setting up the source TEMP_SENSOR #if REDUNDANT_TEMP_MATCH(SOURCE, E0) #define TEMP_SENSOR_0_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN #define TEMP_SENSOR_0_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX @@ -429,36 +564,36 @@ #if (TEMP_SENSOR_IS_MAX_TC(0) && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_0) || (TEMP_SENSOR_IS_MAX_TC(1) && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_1) || (TEMP_SENSOR_IS_MAX_TC(2) && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_2) #if TEMP_SENSOR_REDUNDANT == -5 - #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 then TEMP_SENSOR_REDUNDANT must match." + #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_[0-2] then TEMP_SENSOR_REDUNDANT must match." #elif TEMP_SENSOR_REDUNDANT == -3 - #error "If MAX31855 Thermocouple (-3) is used for TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 then TEMP_SENSOR_REDUNDANT must match." + #error "If MAX31855 Thermocouple (-3) is used for TEMP_SENSOR_[0-2] then TEMP_SENSOR_REDUNDANT must match." #elif TEMP_SENSOR_REDUNDANT == -2 - #error "If MAX6675 Thermocouple (-2) is used for TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 then TEMP_SENSOR_REDUNDANT must match." + #error "If MAX6675 Thermocouple (-2) is used for TEMP_SENSOR_[0-2] then TEMP_SENSOR_REDUNDANT must match." #endif #endif #elif TEMP_SENSOR_REDUNDANT == -4 #define TEMP_SENSOR_REDUNDANT_IS_AD8495 1 #elif TEMP_SENSOR_REDUNDANT == -1 #define TEMP_SENSOR_REDUNDANT_IS_AD595 1 +#elif TEMP_SENSOR_REDUNDANT == 998 || TEMP_SENSOR_REDUNDANT == 999 + #error "Dummy sensors are not supported for TEMP_SENSOR_REDUNDANT." #elif TEMP_SENSOR_REDUNDANT > 0 #define TEMP_SENSOR_REDUNDANT_IS_THERMISTOR 1 #if TEMP_SENSOR_REDUNDANT == 1000 #define TEMP_SENSOR_REDUNDANT_IS_CUSTOM 1 - #elif TEMP_SENSOR_REDUNDANT == 998 || TEMP_SENSOR_REDUNDANT == 999 - #error "Dummy sensors are not supported for TEMP_SENSOR_REDUNDANT." #endif #endif -#if TEMP_SENSOR_IS_MAX_TC(0) || TEMP_SENSOR_IS_MAX_TC(1) || TEMP_SENSOR_IS_MAX_TC(2) || TEMP_SENSOR_IS_MAX_TC(REDUNDANT) +#if TEMP_SENSOR_IS_MAX_TC(0) || TEMP_SENSOR_IS_MAX_TC(1) || TEMP_SENSOR_IS_MAX_TC(2) || TEMP_SENSOR_IS_MAX_TC(BED) || TEMP_SENSOR_IS_MAX_TC(REDUNDANT) #define HAS_MAX_TC 1 #endif -#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_2_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675 +#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_2_IS_MAX6675 || TEMP_SENSOR_BED_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675 #define HAS_MAX6675 1 #endif -#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_2_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855 +#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_2_IS_MAX31855 || TEMP_SENSOR_BED_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855 #define HAS_MAX31855 1 #endif -#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_2_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865 +#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_2_IS_MAX31865 || TEMP_SENSOR_BED_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865 #define HAS_MAX31865 1 #endif @@ -470,16 +605,13 @@ #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_3." #elif TEMP_SENSOR_3 == -1 #define TEMP_SENSOR_3_IS_AD595 1 +#elif TEMP_SENSOR_3 == 998 || TEMP_SENSOR_3 == 999 + #define TEMP_SENSOR_3_IS_DUMMY 1 #elif TEMP_SENSOR_3 > 0 #define TEMP_SENSOR_3_IS_THERMISTOR 1 #if TEMP_SENSOR_3 == 1000 #define TEMP_SENSOR_3_IS_CUSTOM 1 - #elif TEMP_SENSOR_3 == 998 || TEMP_SENSOR_3 == 999 - #define TEMP_SENSOR_3_IS_DUMMY 1 #endif -#else - #undef HEATER_3_MINTEMP - #undef HEATER_3_MAXTEMP #endif #if TEMP_SENSOR_4 == -4 @@ -490,16 +622,13 @@ #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_4." #elif TEMP_SENSOR_4 == -1 #define TEMP_SENSOR_4_IS_AD595 1 +#elif TEMP_SENSOR_4 == 998 || TEMP_SENSOR_4 == 999 + #define TEMP_SENSOR_4_IS_DUMMY 1 #elif TEMP_SENSOR_4 > 0 #define TEMP_SENSOR_4_IS_THERMISTOR 1 #if TEMP_SENSOR_4 == 1000 #define TEMP_SENSOR_4_IS_CUSTOM 1 - #elif TEMP_SENSOR_4 == 998 || TEMP_SENSOR_4 == 999 - #define TEMP_SENSOR_4_IS_DUMMY 1 #endif -#else - #undef HEATER_4_MINTEMP - #undef HEATER_4_MAXTEMP #endif #if TEMP_SENSOR_5 == -4 @@ -510,16 +639,13 @@ #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_5." #elif TEMP_SENSOR_5 == -1 #define TEMP_SENSOR_5_IS_AD595 1 +#elif TEMP_SENSOR_5 == 998 || TEMP_SENSOR_5 == 999 + #define TEMP_SENSOR_5_IS_DUMMY 1 #elif TEMP_SENSOR_5 > 0 #define TEMP_SENSOR_5_IS_THERMISTOR 1 #if TEMP_SENSOR_5 == 1000 #define TEMP_SENSOR_5_IS_CUSTOM 1 - #elif TEMP_SENSOR_5 == 998 || TEMP_SENSOR_5 == 999 - #define TEMP_SENSOR_5_IS_DUMMY 1 #endif -#else - #undef HEATER_5_MINTEMP - #undef HEATER_5_MAXTEMP #endif #if TEMP_SENSOR_6 == -4 @@ -530,16 +656,13 @@ #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_6." #elif TEMP_SENSOR_6 == -1 #define TEMP_SENSOR_6_IS_AD595 1 +#elif TEMP_SENSOR_6 == 998 || TEMP_SENSOR_6 == 999 + #define TEMP_SENSOR_6_IS_DUMMY 1 #elif TEMP_SENSOR_6 > 0 #define TEMP_SENSOR_6_IS_THERMISTOR 1 #if TEMP_SENSOR_6 == 1000 #define TEMP_SENSOR_6_IS_CUSTOM 1 - #elif TEMP_SENSOR_6 == 998 || TEMP_SENSOR_6 == 999 - #define TEMP_SENSOR_6_IS_DUMMY 1 #endif -#else - #undef HEATER_6_MINTEMP - #undef HEATER_6_MAXTEMP #endif #if TEMP_SENSOR_7 == -4 @@ -550,24 +673,37 @@ #error "MAX7775 Thermocouples (-2) not supported for TEMP_SENSOR_7." #elif TEMP_SENSOR_7 == -1 #define TEMP_SENSOR_7_IS_AD595 1 +#elif TEMP_SENSOR_7 == 998 || TEMP_SENSOR_7 == 999 + #define TEMP_SENSOR_7_IS_DUMMY 1 #elif TEMP_SENSOR_7 > 0 #define TEMP_SENSOR_7_IS_THERMISTOR 1 #if TEMP_SENSOR_7 == 1000 #define TEMP_SENSOR_7_IS_CUSTOM 1 - #elif TEMP_SENSOR_7 == 998 || TEMP_SENSOR_7 == 999 - #define TEMP_SENSOR_7_IS_DUMMY 1 #endif -#else - #undef HEATER_7_MINTEMP - #undef HEATER_7_MAXTEMP #endif -#if TEMP_SENSOR_BED == -4 +#if TEMP_SENSOR_IS_MAX_TC(BED) + #if TEMP_SENSOR_BED == -5 + #define TEMP_SENSOR_BED_IS_MAX31865 1 + #define TEMP_SENSOR_BED_MAX_TC_TMIN 0 + #define TEMP_SENSOR_BED_MAX_TC_TMAX 1024 + #ifndef MAX31865_SENSOR_WIRES_BED + #define MAX31865_SENSOR_WIRES_BED 2 + #endif + #ifndef MAX31865_WIRE_OHMS_BED + #define MAX31865_WIRE_OHMS_BED 0.0f + #endif + #elif TEMP_SENSOR_BED == -3 + #define TEMP_SENSOR_BED_IS_MAX31855 1 + #define TEMP_SENSOR_BED_MAX_TC_TMIN -270 + #define TEMP_SENSOR_BED_MAX_TC_TMAX 1800 + #elif TEMP_SENSOR_BED == -2 + #define TEMP_SENSOR_BED_IS_MAX6675 1 + #define TEMP_SENSOR_BED_MAX_TC_TMIN 0 + #define TEMP_SENSOR_BED_MAX_TC_TMAX 1024 + #endif +#elif TEMP_SENSOR_BED == -4 #define TEMP_SENSOR_BED_IS_AD8495 1 -#elif TEMP_SENSOR_BED == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_BED." -#elif TEMP_SENSOR_BED == -2 - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_BED." #elif TEMP_SENSOR_BED == -1 #define TEMP_SENSOR_BED_IS_AD595 1 #elif TEMP_SENSOR_BED > 0 @@ -578,8 +714,6 @@ #define TEMP_SENSOR_BED_IS_DUMMY 1 #endif #else - #undef THERMAL_PROTECTION_BED - #undef THERMAL_PROTECTION_BED_PERIOD #undef BED_MINTEMP #undef BED_MAXTEMP #endif @@ -613,12 +747,12 @@ #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_COOLER." #elif TEMP_SENSOR_COOLER == -1 #define TEMP_SENSOR_COOLER_IS_AD595 1 +#elif TEMP_SENSOR_COOLER == 998 || TEMP_SENSOR_COOLER == 999 + #define TEMP_SENSOR_COOLER_IS_DUMMY 1 #elif TEMP_SENSOR_COOLER > 0 #define TEMP_SENSOR_COOLER_IS_THERMISTOR 1 #if TEMP_SENSOR_COOLER == 1000 #define TEMP_SENSOR_COOLER_IS_CUSTOM 1 - #elif TEMP_SENSOR_COOLER == 998 || TEMP_SENSOR_COOLER == 999 - #define TEMP_SENSOR_COOLER_IS_DUMMY 1 #endif #else #undef THERMAL_PROTECTION_COOLER @@ -660,11 +794,11 @@ #endif #endif -#if ENABLED(MIXING_EXTRUDER) && (ENABLED(RETRACT_SYNC_MIXING) || BOTH(FILAMENT_LOAD_UNLOAD_GCODES, FILAMENT_UNLOAD_ALL_EXTRUDERS)) +#if ENABLED(MIXING_EXTRUDER) && (ENABLED(RETRACT_SYNC_MIXING) || ALL(FILAMENT_LOAD_UNLOAD_GCODES, FILAMENT_UNLOAD_ALL_EXTRUDERS)) #define HAS_MIXER_SYNC_CHANNEL 1 #endif -#if EITHER(DUAL_X_CARRIAGE, MULTI_NOZZLE_DUPLICATION) +#if ANY(DUAL_X_CARRIAGE, MULTI_NOZZLE_DUPLICATION) #define HAS_DUPLICATION_MODE 1 #endif @@ -702,7 +836,7 @@ #undef MENU_ADDAUTOSTART #endif -#if EITHER(SDSUPPORT, SET_PROGRESS_MANUALLY) +#if ANY(HAS_MEDIA, SET_PROGRESS_MANUALLY) #define HAS_PRINT_PROGRESS 1 #endif @@ -720,11 +854,11 @@ #define HAS_STATUS_MESSAGE_TIMEOUT 1 #endif -#if ENABLED(SDSUPPORT) && SD_PROCEDURE_DEPTH +#if HAS_MEDIA && SD_PROCEDURE_DEPTH #define HAS_MEDIA_SUBCALLS 1 #endif -#if HAS_PRINT_PROGRESS && EITHER(PRINT_PROGRESS_SHOW_DECIMALS, SHOW_REMAINING_TIME) +#if HAS_PRINT_PROGRESS && ANY(PRINT_PROGRESS_SHOW_DECIMALS, SHOW_REMAINING_TIME) #define HAS_PRINT_PROGRESS_PERMYRIAD 1 #endif @@ -742,7 +876,7 @@ #if ANY(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS, Z_MULTI_ENDSTOPS) #define HAS_EXTRA_ENDSTOPS 1 #endif -#if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) +#if ANY(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) #define HAS_SOFTWARE_ENDSTOPS 1 #endif #if ANY(EXTENSIBLE_UI, IS_NEWPANEL, EMERGENCY_PARSER, HAS_ADC_BUTTONS, HAS_DWIN_E3V2) @@ -754,7 +888,7 @@ #else #undef LED_POWEROFF_TIMEOUT #endif -#if ALL(HAS_RESUME_CONTINUE, PRINTER_EVENT_LEDS, SDSUPPORT) +#if ALL(HAS_RESUME_CONTINUE, PRINTER_EVENT_LEDS, HAS_MEDIA) #define HAS_LEDS_OFF_FLAG 1 #endif #if DISPLAY_SLEEP_MINUTES || TOUCH_IDLE_SLEEP_MINS @@ -764,7 +898,7 @@ #define HAS_GCODE_M255 1 #endif -#if EITHER(DIGIPOT_MCP4018, DIGIPOT_MCP4451) +#if ANY(DIGIPOT_MCP4018, DIGIPOT_MCP4451) #define HAS_MOTOR_CURRENT_I2C 1 #endif @@ -779,6 +913,17 @@ #endif // Multiple Z steppers +#ifdef INVERT_Z_DIR + #if NUM_Z_STEPPERS >= 2 && !defined(INVERT_Z2_DIR) + #define INVERT_Z2_DIR INVERT_Z_DIR + #if NUM_Z_STEPPERS >= 3 && !defined(INVERT_Z3_DIR) + #define INVERT_Z3_DIR INVERT_Z_DIR + #if NUM_Z_STEPPERS >= 4 && !defined(INVERT_Z4_DIR) + #define INVERT_Z4_DIR INVERT_Z_DIR + #endif + #endif + #endif +#endif #if NUM_Z_STEPPERS < 4 #undef INVERT_Z4_VS_Z_DIR #if NUM_Z_STEPPERS < 3 @@ -797,7 +942,7 @@ // Spindle/Laser power display types // Defined here so sanity checks can use them // -#if EITHER(SPINDLE_FEATURE, LASER_FEATURE) +#if ANY(SPINDLE_FEATURE, LASER_FEATURE) #define HAS_CUTTER 1 #define _CUTTER_POWER_PWM255 1 #define _CUTTER_POWER_PERCENT 2 @@ -870,7 +1015,7 @@ #endif #endif -#if EITHER(FYSETC_MINI_12864_2_1, FYSETC_242_OLED_12864) +#if ANY(FYSETC_MINI_12864_2_1, FYSETC_242_OLED_12864) #ifndef LED_USER_PRESET_GREEN #define LED_USER_PRESET_GREEN 128 #endif @@ -905,7 +1050,7 @@ #endif #endif -#if BOTH(LED_CONTROL_MENU, NEOPIXEL2_SEPARATE) +#if ALL(LED_CONTROL_MENU, NEOPIXEL2_SEPARATE) #ifndef LED2_USER_PRESET_RED #define LED2_USER_PRESET_RED 255 #endif @@ -928,7 +1073,7 @@ #endif // Full Touch Screen needs 'tft/xpt2046' -#if EITHER(TFT_TOUCH_DEVICE_XPT2046, HAS_TFT_LVGL_UI) +#if ANY(TFT_TOUCH_DEVICE_XPT2046, HAS_TFT_LVGL_UI) #define HAS_TFT_XPT2046 1 #endif @@ -948,10 +1093,8 @@ #define POLL_JOG #endif -#if X2_HOME_DIR > 0 +#if ENABLED(DUAL_X_CARRIAGE) #define X2_HOME_TO_MAX 1 -#elif X2_HOME_DIR < 0 - #define X2_HOME_TO_MIN 1 #endif #ifndef HOMING_BUMP_MM @@ -1039,53 +1182,6 @@ #endif #endif -// Remove unused STEALTHCHOP flags -#if NUM_AXES < 9 - #undef STEALTHCHOP_W - #undef CALIBRATION_MEASURE_WMIN - #undef CALIBRATION_MEASURE_WMAX - #if NUM_AXES < 8 - #undef STEALTHCHOP_V - #undef CALIBRATION_MEASURE_VMIN - #undef CALIBRATION_MEASURE_VMAX - #if NUM_AXES < 7 - #undef STEALTHCHOP_U - #undef CALIBRATION_MEASURE_UMIN - #undef CALIBRATION_MEASURE_UMAX - #if NUM_AXES < 6 - #undef STEALTHCHOP_K - #undef CALIBRATION_MEASURE_KMIN - #undef CALIBRATION_MEASURE_KMAX - #if NUM_AXES < 5 - #undef STEALTHCHOP_J - #undef CALIBRATION_MEASURE_JMIN - #undef CALIBRATION_MEASURE_JMAX - #if NUM_AXES < 4 - #undef STEALTHCHOP_I - #undef CALIBRATION_MEASURE_IMIN - #undef CALIBRATION_MEASURE_IMAX - #if NUM_AXES < 3 - #undef STEALTHCHOP_Z - #undef Z_IDLE_HEIGHT - #undef Z_PROBE_SLED - #undef Z_SAFE_HOMING - #undef HOME_Z_FIRST - #undef HOMING_Z_WITH_PROBE - #undef ENABLE_LEVELING_FADE_HEIGHT - #undef NUM_Z_STEPPERS - #undef CNC_WORKSPACE_PLANES - #if NUM_AXES < 2 - #undef STEALTHCHOP_Y - #undef QUICK_HOME - #endif - #endif - #endif - #endif - #endif - #endif - #endif -#endif - #if defined(SAFE_BED_LEVELING_START_X) || defined(SAFE_BED_LEVELING_START_Y) || defined(SAFE_BED_LEVELING_START_Z) \ || defined(SAFE_BED_LEVELING_START_I) || defined(SAFE_BED_LEVELING_START_J) || defined(SAFE_BED_LEVELING_START_K) \ || defined(SAFE_BED_LEVELING_START_U) || defined(SAFE_BED_LEVELING_START_V) || defined(SAFE_BED_LEVELING_START_W) @@ -1096,7 +1192,7 @@ // SD Card connection methods // Defined here so pins and sanity checks can use them // -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #define _SDCARD_LCD 1 #define _SDCARD_ONBOARD 2 #define _SDCARD_CUSTOM_CABLE 3 @@ -1104,10 +1200,11 @@ #define SD_CONNECTION_IS(V) (_SDCARD_ID(SDCARD_CONNECTION) == _SDCARD_ID(V)) #else #define SD_CONNECTION_IS(...) 0 + #undef SD_ABORT_ON_ENDSTOP_HIT #endif // Power Monitor sensors -#if EITHER(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) +#if ANY(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) #define HAS_POWER_MONITOR 1 #if ENABLED(POWER_MONITOR_CURRENT) && (ENABLED(POWER_MONITOR_VOLTAGE) || defined(POWER_MONITOR_FIXED_VOLTAGE)) #define HAS_POWER_MONITOR_WATTS 1 @@ -1126,7 +1223,7 @@ // Flags for Case Light having a color property or a single pin #if ENABLED(CASE_LIGHT_ENABLE) - #if EITHER(CASE_LIGHT_USE_NEOPIXEL, CASE_LIGHT_USE_RGB_LED) + #if ANY(CASE_LIGHT_USE_NEOPIXEL, CASE_LIGHT_USE_RGB_LED) #define CASE_LIGHT_IS_COLOR_LED 1 #else #define NEED_CASE_LIGHT_PIN 1 @@ -1143,15 +1240,16 @@ #define NEED_LSF 1 #endif -#if BOTH(HAS_TFT_LVGL_UI, CUSTOM_MENU_MAIN) +#if ALL(HAS_TFT_LVGL_UI, CUSTOM_MENU_MAIN) #define _HAS_1(N) (defined(MAIN_MENU_ITEM_##N##_DESC) && defined(MAIN_MENU_ITEM_##N##_GCODE)) #define HAS_USER_ITEM(V...) DO(HAS,||,V) #else - #define HAS_USER_ITEM(N) 0 + #define HAS_USER_ITEM(...) 0 #endif /** - * LCD_SERIAL_PORT must be defined ahead of HAL.h + * LCD_SERIAL_PORT must be defined ahead of HAL.h and + * currently HAL.h must be included ahead of pins.h. */ #ifndef LCD_SERIAL_PORT #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI || HAS_DGUS_LCD @@ -1171,20 +1269,16 @@ #if !HAS_MULTI_SERIAL #undef MEATPACK_ON_SERIAL_PORT_2 #endif -#if EITHER(MEATPACK_ON_SERIAL_PORT_1, MEATPACK_ON_SERIAL_PORT_2) +#if ANY(MEATPACK_ON_SERIAL_PORT_1, MEATPACK_ON_SERIAL_PORT_2) #define HAS_MEATPACK 1 #endif // AVR are (usually) too limited in resources to store the configuration into the binary -#if ENABLED(CONFIGURATION_EMBEDDING) && !defined(FORCE_CONFIG_EMBED) && (defined(__AVR__) || DISABLED(SDSUPPORT) || EITHER(SDCARD_READONLY, DISABLE_M503)) +#if ENABLED(CONFIGURATION_EMBEDDING) && !defined(FORCE_CONFIG_EMBED) && (defined(__AVR__) || !HAS_MEDIA || ANY(SDCARD_READONLY, DISABLE_M503)) #undef CONFIGURATION_EMBEDDING #define CANNOT_EMBED_CONFIGURATION defined(__AVR__) #endif -#if ANY(DISABLE_INACTIVE_X, DISABLE_INACTIVE_Y, DISABLE_INACTIVE_Z, DISABLE_INACTIVE_I, DISABLE_INACTIVE_J, DISABLE_INACTIVE_K, DISABLE_INACTIVE_U, DISABLE_INACTIVE_V, DISABLE_INACTIVE_W, DISABLE_INACTIVE_E) - #define HAS_DISABLE_INACTIVE_AXIS 1 -#endif - // Fan Kickstart #if FAN_KICKSTART_TIME && !defined(FAN_KICKSTART_POWER) #define FAN_KICKSTART_POWER 180 @@ -1197,6 +1291,6 @@ #endif // Input shaping -#if EITHER(INPUT_SHAPING_X, INPUT_SHAPING_Y) - #define HAS_SHAPING 1 +#if ANY(INPUT_SHAPING_X, INPUT_SHAPING_Y) + #define HAS_ZV_SHAPING 1 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 3adfddd4620e..6794087ca42e 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -31,14 +31,14 @@ #endif // ADC -#ifdef BOARD_ADC_VREF - #define ADC_VREF BOARD_ADC_VREF +#ifdef BOARD_ADC_VREF_MV + #define ADC_VREF_MV BOARD_ADC_VREF_MV #else - #define ADC_VREF HAL_ADC_VREF + #define ADC_VREF_MV HAL_ADC_VREF_MV #endif // Linear advance uses Jerk since E is an isolated axis -#if BOTH(HAS_JUNCTION_DEVIATION, LIN_ADVANCE) +#if ALL(HAS_JUNCTION_DEVIATION, LIN_ADVANCE) #define HAS_LINEAR_E_JERK 1 #endif @@ -48,7 +48,7 @@ // Set additional flags to let HALs choose in their Conditionals_post.h #if ANY(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION, QSPI_EEPROM) #define USE_EMULATED_EEPROM 1 - #elif EITHER(I2C_EEPROM, SPI_EEPROM) + #elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_WIRED_EEPROM 1 #elif ENABLED(IIC_BL24CXX_EEPROM) // nothing @@ -65,6 +65,10 @@ #undef IIC_BL24CXX_EEPROM #endif +#if DISABLED(IIC_BL24CXX_EEPROM) + #undef OTA_FIRMWARE_UPDATE +#endif + #ifdef TEENSYDUINO #undef max #define max(a,b) ((a)>(b)?(a):(b)) @@ -101,7 +105,9 @@ #define HAS_ROTATIONAL_AXES 1 #endif -#define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS)) +#if HAS_X_AXIS + #define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS)) +#endif #if HAS_Y_AXIS #define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS)) #endif @@ -130,7 +136,7 @@ #endif // Defined only if the sanity-check is bypassed -#ifndef X_BED_SIZE +#if HAS_X_AXIS && !defined(X_BED_SIZE) #define X_BED_SIZE X_MAX_LENGTH #endif #if HAS_Y_AXIS && !defined(Y_BED_SIZE) @@ -161,7 +167,9 @@ #endif // Define center values for future use -#define _X_HALF_BED ((X_BED_SIZE) / 2) +#if HAS_X_AXIS + #define _X_HALF_BED ((X_BED_SIZE) / 2) +#endif #if HAS_Y_AXIS #define _Y_HALF_BED ((Y_BED_SIZE) / 2) #endif @@ -184,7 +192,9 @@ #define _W_HALF_WMAX ((W_BED_SIZE) / 2) #endif -#define X_CENTER TERN(BED_CENTER_AT_0_0, 0, _X_HALF_BED) +#if HAS_X_AXIS + #define X_CENTER TERN(BED_CENTER_AT_0_0, 0, _X_HALF_BED) +#endif #if HAS_Y_AXIS #define Y_CENTER TERN(BED_CENTER_AT_0_0, 0, _Y_HALF_BED) #define XY_CENTER { X_CENTER, Y_CENTER } @@ -209,8 +219,10 @@ #endif // Get the linear boundaries of the bed -#define X_MIN_BED (X_CENTER - _X_HALF_BED) -#define X_MAX_BED (X_MIN_BED + X_BED_SIZE) +#if HAS_X_AXIS + #define X_MIN_BED (X_CENTER - _X_HALF_BED) + #define X_MAX_BED (X_MIN_BED + X_BED_SIZE) +#endif #if HAS_Y_AXIS #define Y_MIN_BED (Y_CENTER - _Y_HALF_BED) #define Y_MAX_BED (Y_MIN_BED + Y_BED_SIZE) @@ -253,20 +265,23 @@ #endif // Calibration codes only for non-core axes -#if EITHER(BACKLASH_GCODE, CALIBRATION_GCODE) +#if ANY(BACKLASH_GCODE, CALIBRATION_GCODE) #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) - #define CAN_CALIBRATE(A,B) (_AXIS(A) == B) + #define CAN_CALIBRATE(A,B) TERN0(HAS_##A##_AXIS, (_AXIS(A) == B)) #else - #define CAN_CALIBRATE(A,B) true + #define CAN_CALIBRATE(A,B) ENABLED(HAS_##A##_AXIS) #endif + #define AXIS_CAN_CALIBRATE(A) CAN_CALIBRATE(A,NORMAL_AXIS) +#else + #define AXIS_CAN_CALIBRATE(A) false #endif -#define AXIS_CAN_CALIBRATE(A) CAN_CALIBRATE(A,NORMAL_AXIS) /** * No adjustable bed on non-cartesians */ #if IS_KINEMATIC #undef LCD_BED_TRAMMING + #undef SLOWDOWN #endif /** @@ -274,7 +289,6 @@ * Printable radius assumes joints can fully extend */ #if IS_SCARA - #undef SLOWDOWN #if ENABLED(AXEL_TPARA) #define SCARA_PRINTABLE_RADIUS (TPARA_LINKAGE_1 + TPARA_LINKAGE_2) #else @@ -286,14 +300,16 @@ /** * Set the home position based on settings or manual overrides */ -#ifdef MANUAL_X_HOME_POS - #define X_HOME_POS MANUAL_X_HOME_POS -#else - #define X_END_POS TERN(X_HOME_TO_MIN, X_MIN_POS, X_MAX_POS) - #if ENABLED(BED_CENTER_AT_0_0) - #define X_HOME_POS TERN(DELTA, 0, X_END_POS) +#if HAS_X_AXIS + #ifdef MANUAL_X_HOME_POS + #define X_HOME_POS MANUAL_X_HOME_POS #else - #define X_HOME_POS TERN(DELTA, X_MIN_POS + (X_BED_SIZE) * 0.5, X_END_POS) + #define X_END_POS TERN(X_HOME_TO_MIN, X_MIN_POS, X_MAX_POS) + #if ENABLED(BED_CENTER_AT_0_0) + #define X_HOME_POS TERN(DELTA, 0, X_END_POS) + #else + #define X_HOME_POS TERN(DELTA, X_MIN_POS + (X_BED_SIZE) * 0.5, X_END_POS) + #endif #endif #endif @@ -378,7 +394,6 @@ */ #if ENABLED(DELTA) #undef Z_SAFE_HOMING - #undef SLOWDOWN #endif #ifndef MESH_INSET @@ -451,14 +466,14 @@ #elif ENABLED(AZSMZ_12864) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 190 -#elif EITHER(MKS_LCD12864A, MKS_LCD12864B) +#elif ANY(MKS_LCD12864A, MKS_LCD12864B) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 205 -#elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) +#elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 195 -#elif EITHER(MKS_MINI_12864_V3, BTT_MINI_12864_V1) - #define _LCD_CONTRAST_MIN 255 +#elif ENABLED(FYSETC_MINI_12864_2_1) + #define _LCD_CONTRAST_MIN 230 #define _LCD_CONTRAST_INIT 255 #elif ENABLED(FYSETC_MINI_12864) #define _LCD_CONTRAST_MIN 180 @@ -509,7 +524,7 @@ * Override the SD_DETECT_STATE set in Configuration_adv.h * and enable sharing of onboard SD host drives (all platforms but AGCM4) */ -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #if HAS_SD_HOST_DRIVE && SD_CONNECTION_IS(ONBOARD) && DISABLED(KEEP_SD_DETECT) // @@ -543,8 +558,8 @@ #endif #endif - #if DISABLED(USB_FLASH_DRIVE_SUPPORT) || BOTH(MULTI_VOLUME, VOLUME_SD_ONBOARD) - #if ENABLED(SDIO_SUPPORT) + #if DISABLED(USB_FLASH_DRIVE_SUPPORT) || ALL(MULTI_VOLUME, VOLUME_SD_ONBOARD) + #if ENABLED(ONBOARD_SDIO) #define NEED_SD2CARD_SDIO 1 #else #define NEED_SD2CARD_SPI 1 @@ -555,7 +570,7 @@ #define REINIT_NOISY_LCD 1 // Have the LCD re-init on SD insertion #endif -#endif +#endif // HAS_MEDIA /** * Power Supply @@ -680,215 +695,43 @@ /** * Compatibility layer for MAX (SPI) temp boards */ -#if HAS_MAX_TC - // Translate old _SS, _CS, _SCK, _DO, _DI, _MISO, and _MOSI PIN defines. - #if TEMP_SENSOR_IS_MAX_TC(0) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1)) - - #if !PIN_EXISTS(TEMP_0_CS) // SS, CS - #if PIN_EXISTS(MAX6675_SS) - #define TEMP_0_CS_PIN MAX6675_SS_PIN - #elif PIN_EXISTS(MAX6675_CS) - #define TEMP_0_CS_PIN MAX6675_CS_PIN - #elif PIN_EXISTS(MAX31855_SS) - #define TEMP_0_CS_PIN MAX31855_SS_PIN - #elif PIN_EXISTS(MAX31855_CS) - #define TEMP_0_CS_PIN MAX31855_CS_PIN - #elif PIN_EXISTS(MAX31865_SS) - #define TEMP_0_CS_PIN MAX31865_SS_PIN - #elif PIN_EXISTS(MAX31865_CS) - #define TEMP_0_CS_PIN MAX31865_CS_PIN - #endif - #endif - - #if TEMP_SENSOR_0_IS_MAX6675 - #if !PIN_EXISTS(TEMP_0_MISO) // DO - #if PIN_EXISTS(MAX6675_MISO) - #define TEMP_0_MISO_PIN MAX6675_MISO_PIN - #elif PIN_EXISTS(MAX6675_DO) - #define TEMP_0_MISO_PIN MAX6675_DO_PIN - #endif - #endif - #if !PIN_EXISTS(TEMP_0_SCK) && PIN_EXISTS(MAX6675_SCK) - #define TEMP_0_SCK_PIN MAX6675_SCK_PIN - #endif - - #elif TEMP_SENSOR_0_IS_MAX31855 - #if !PIN_EXISTS(TEMP_0_MISO) // DO - #if PIN_EXISTS(MAX31855_MISO) - #define TEMP_0_MISO_PIN MAX31855_MISO_PIN - #elif PIN_EXISTS(MAX31855_DO) - #define TEMP_0_MISO_PIN MAX31855_DO_PIN - #endif - #endif - #if !PIN_EXISTS(TEMP_0_SCK) && PIN_EXISTS(MAX31855_SCK) - #define TEMP_0_SCK_PIN MAX31855_SCK_PIN - #endif +#define TEMP_SENSOR_IS_ANY_MAX_TC(n) (TEMP_SENSOR_IS_MAX_TC(n) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) - #elif TEMP_SENSOR_0_IS_MAX31865 - #if !PIN_EXISTS(TEMP_0_MISO) // DO - #if PIN_EXISTS(MAX31865_MISO) - #define TEMP_0_MISO_PIN MAX31865_MISO_PIN - #elif PIN_EXISTS(MAX31865_DO) - #define TEMP_0_MISO_PIN MAX31865_DO_PIN - #endif - #endif - #if !PIN_EXISTS(TEMP_0_SCK) && PIN_EXISTS(MAX31865_SCK) - #define TEMP_0_SCK_PIN MAX31865_SCK_PIN - #endif - #if !PIN_EXISTS(TEMP_0_MOSI) && PIN_EXISTS(MAX31865_MOSI) // MOSI for '65 only - #define TEMP_0_MOSI_PIN MAX31865_MOSI_PIN - #endif - #endif - - // Software SPI - enable if MISO/SCK are defined. - #if PIN_EXISTS(TEMP_0_MISO) && PIN_EXISTS(TEMP_0_SCK) && DISABLED(TEMP_SENSOR_0_FORCE_HW_SPI) - #if TEMP_SENSOR_0_IS_MAX31865 && !PIN_EXISTS(TEMP_0_MOSI) - #error "TEMP_SENSOR_0 MAX31865 requires TEMP_0_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_0_FORCE_HW_SPI." - #else - #define TEMP_SENSOR_0_HAS_SPI_PINS 1 - #endif - #endif - - #endif // TEMP_SENSOR_IS_MAX_TC(0) - - #if TEMP_SENSOR_IS_MAX_TC(1) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1)) - - #if !PIN_EXISTS(TEMP_1_CS) // SS2, CS2 - #if PIN_EXISTS(MAX6675_SS2) - #define TEMP_1_CS_PIN MAX6675_SS2_PIN - #elif PIN_EXISTS(MAX6675_CS) - #define TEMP_1_CS_PIN MAX6675_CS2_PIN - #elif PIN_EXISTS(MAX31855_SS2) - #define TEMP_1_CS_PIN MAX31855_SS2_PIN - #elif PIN_EXISTS(MAX31855_CS2) - #define TEMP_1_CS_PIN MAX31855_CS2_PIN - #elif PIN_EXISTS(MAX31865_SS2) - #define TEMP_1_CS_PIN MAX31865_SS2_PIN - #elif PIN_EXISTS(MAX31865_CS2) - #define TEMP_1_CS_PIN MAX31865_CS2_PIN - #endif - #endif - - #if TEMP_SENSOR_1_IS_MAX6675 - #if !PIN_EXISTS(TEMP_1_MISO) // DO - #if PIN_EXISTS(MAX6675_MISO) - #define TEMP_1_MISO_PIN MAX6675_MISO_PIN - #elif PIN_EXISTS(MAX6675_DO) - #define TEMP_1_MISO_PIN MAX6675_DO_PIN - #endif - #endif - #if !PIN_EXISTS(TEMP_1_SCK) && PIN_EXISTS(MAX6675_SCK) - #define TEMP_1_SCK_PIN MAX6675_SCK_PIN - #endif - - #elif TEMP_SENSOR_1_IS_MAX31855 - #if !PIN_EXISTS(TEMP_1_MISO) // DO - #if PIN_EXISTS(MAX31855_MISO) - #define TEMP_1_MISO_PIN MAX31855_MISO_PIN - #elif PIN_EXISTS(MAX31855_DO) - #define TEMP_1_MISO_PIN MAX31855_DO_PIN - #endif - #endif - #if !PIN_EXISTS(TEMP_1_SCK) && PIN_EXISTS(MAX31855_SCK) - #define TEMP_1_SCK_PIN MAX31855_SCK_PIN - #endif - - #elif TEMP_SENSOR_1_IS_MAX31865 - #if !PIN_EXISTS(TEMP_1_MISO) // DO - #if PIN_EXISTS(MAX31865_MISO) - #define TEMP_1_MISO_PIN MAX31865_MISO_PIN - #elif PIN_EXISTS(MAX31865_DO) - #define TEMP_1_MISO_PIN MAX31865_DO_PIN - #endif - #endif - #if !PIN_EXISTS(TEMP_1_SCK) && PIN_EXISTS(MAX31865_SCK) - #define TEMP_1_SCK_PIN MAX31865_SCK_PIN - #endif - #if !PIN_EXISTS(TEMP_1_MOSI) && PIN_EXISTS(MAX31865_MOSI) // MOSI for '65 only - #define TEMP_1_MOSI_PIN MAX31865_MOSI_PIN - #endif - #endif +#if HAS_MAX_TC - // Software SPI - enable if MISO/SCK are defined. - #if PIN_EXISTS(TEMP_1_MISO) && PIN_EXISTS(TEMP_1_SCK) && DISABLED(TEMP_SENSOR_1_FORCE_HW_SPI) - #if TEMP_SENSOR_1_IS_MAX31865 && !PIN_EXISTS(TEMP_1_MOSI) - #error "TEMP_SENSOR_1 MAX31865 requires TEMP_1_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_1_FORCE_HW_SPI." - #else - #define TEMP_SENSOR_1_HAS_SPI_PINS 1 - #endif + // Software SPI - enable if MISO/SCK are defined. + #if TEMP_SENSOR_IS_ANY_MAX_TC(0) && DISABLED(TEMP_SENSOR_0_FORCE_HW_SPI) && PINS_EXIST(TEMP_0_MISO, TEMP_0_SCK) + #if TEMP_SENSOR_0_IS_MAX31865 && !PIN_EXISTS(TEMP_0_MOSI) + #error "TEMP_SENSOR_0 MAX31865 requires TEMP_0_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_0_FORCE_HW_SPI." + #else + #define TEMP_SENSOR_0_HAS_SPI_PINS 1 #endif + #endif - #endif // TEMP_SENSOR_IS_MAX_TC(1) - - #if TEMP_SENSOR_IS_MAX_TC(2) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E2)) - - #if !PIN_EXISTS(TEMP_2_CS) // SS3, CS3 - #if PIN_EXISTS(MAX6675_SS3) - #define TEMP_2_CS_PIN MAX6675_SS3_PIN - #elif PIN_EXISTS(MAX6675_CS) - #define TEMP_2_CS_PIN MAX6675_CS3_PIN - #elif PIN_EXISTS(MAX31855_SS3) - #define TEMP_2_CS_PIN MAX31855_SS3_PIN - #elif PIN_EXISTS(MAX31855_CS3) - #define TEMP_2_CS_PIN MAX31855_CS3_PIN - #elif PIN_EXISTS(MAX31865_SS3) - #define TEMP_2_CS_PIN MAX31865_SS3_PIN - #elif PIN_EXISTS(MAX31865_CS3) - #define TEMP_2_CS_PIN MAX31865_CS3_PIN - #endif + #if TEMP_SENSOR_IS_ANY_MAX_TC(1) && DISABLED(TEMP_SENSOR_1_FORCE_HW_SPI) && PINS_EXIST(TEMP_1_MISO, TEMP_1_SCK) + #if TEMP_SENSOR_1_IS_MAX31865 && !PIN_EXISTS(TEMP_1_MOSI) + #error "TEMP_SENSOR_1 MAX31865 requires TEMP_1_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_1_FORCE_HW_SPI." + #else + #define TEMP_SENSOR_1_HAS_SPI_PINS 1 #endif + #endif - #if TEMP_SENSOR_2_IS_MAX6675 - #if !PIN_EXISTS(TEMP_2_MISO) // DO - #if PIN_EXISTS(MAX6675_MISO) - #define TEMP_2_MISO_PIN MAX6675_MISO_PIN - #elif PIN_EXISTS(MAX6675_DO) - #define TEMP_2_MISO_PIN MAX6675_DO_PIN - #endif - #endif - #if !PIN_EXISTS(TEMP_2_SCK) && PIN_EXISTS(MAX6675_SCK) - #define TEMP_2_SCK_PIN MAX6675_SCK_PIN - #endif - - #elif TEMP_SENSOR_2_IS_MAX31855 - #if !PIN_EXISTS(TEMP_2_MISO) // DO - #if PIN_EXISTS(MAX31855_MISO) - #define TEMP_2_MISO_PIN MAX31855_MISO_PIN - #elif PIN_EXISTS(MAX31855_DO) - #define TEMP_2_MISO_PIN MAX31855_DO_PIN - #endif - #endif - #if !PIN_EXISTS(TEMP_2_SCK) && PIN_EXISTS(MAX31855_SCK) - #define TEMP_2_SCK_PIN MAX31855_SCK_PIN - #endif - - #elif TEMP_SENSOR_2_IS_MAX31865 - #if !PIN_EXISTS(TEMP_2_MISO) // DO - #if PIN_EXISTS(MAX31865_MISO) - #define TEMP_2_MISO_PIN MAX31865_MISO_PIN - #elif PIN_EXISTS(MAX31865_DO) - #define TEMP_2_MISO_PIN MAX31865_DO_PIN - #endif - #endif - #if !PIN_EXISTS(TEMP_2_SCK) && PIN_EXISTS(MAX31865_SCK) - #define TEMP_2_SCK_PIN MAX31865_SCK_PIN - #endif - #if !PIN_EXISTS(TEMP_2_MOSI) && PIN_EXISTS(MAX31865_MOSI) // MOSI for '65 only - #define TEMP_2_MOSI_PIN MAX31865_MOSI_PIN - #endif + #if TEMP_SENSOR_IS_ANY_MAX_TC(2) && DISABLED(TEMP_SENSOR_2_FORCE_HW_SPI) && PINS_EXIST(TEMP_2_MISO, TEMP_2_SCK) + #if TEMP_SENSOR_2_IS_MAX31865 && !PIN_EXISTS(TEMP_2_MOSI) + #error "TEMP_SENSOR_2 MAX31865 requires TEMP_2_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_2_FORCE_HW_SPI." + #else + #define TEMP_SENSOR_2_HAS_SPI_PINS 1 #endif + #endif - // Software SPI - enable if MISO/SCK are defined. - #if PIN_EXISTS(TEMP_2_MISO) && PIN_EXISTS(TEMP_2_SCK) && DISABLED(TEMP_SENSOR_2_FORCE_HW_SPI) - #if TEMP_SENSOR_2_IS_MAX31865 && !PIN_EXISTS(TEMP_2_MOSI) - #error "TEMP_SENSOR_2 MAX31865 requires TEMP_2_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_2_FORCE_HW_SPI." - #else - #define TEMP_SENSOR_2_HAS_SPI_PINS 1 - #endif + #if (TEMP_SENSOR_IS_MAX_TC(BED)) && DISABLED(TEMP_SENSOR_BED_FORCE_HW_SPI) && PINS_EXIST(TEMP_BED_MISO, TEMP_BED_SCK) + #if TEMP_SENSOR_BED_IS_MAX31865 && !PIN_EXISTS(TEMP_BED_MOSI) + #error "TEMP_SENSOR_BED MAX31865 requires TEMP_BED_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_BED_FORCE_HW_SPI." + #else + #define TEMP_SENSOR_BED_HAS_SPI_PINS 1 #endif - - #endif // TEMP_SENSOR_IS_MAX_TC(2) + #endif // // User-defined thermocouple libraries @@ -896,13 +739,13 @@ // Add LIB_MAX6675 / LIB_MAX31855 / LIB_MAX31865 to the build_flags // to select a USER library for MAX6675, MAX31855, MAX31865 // - #if BOTH(HAS_MAX6675, LIB_MAX6675) + #if ALL(HAS_MAX6675, LIB_MAX6675) #define USE_LIB_MAX6675 1 #endif - #if BOTH(HAS_MAX31855, LIB_MAX31855) + #if ALL(HAS_MAX31855, LIB_MAX31855) #define USE_ADAFRUIT_MAX31855 1 #endif - #if BOTH(HAS_MAX31865, LIB_MAX31865) + #if ALL(HAS_MAX31865, LIB_MAX31865) #define USE_ADAFRUIT_MAX31865 1 #elif HAS_MAX31865 #define LIB_INTERNAL_MAX31865 1 @@ -1192,162 +1035,41 @@ #endif // Z_MULTI_ENDSTOPS /** - * Set ENDSTOPPULLUPS for active endstop switches + * Shorthand for pin tests, used wherever needed */ -#if ENABLED(ENDSTOPPULLUPS) - #if ENABLED(USE_XMAX_PLUG) - #define ENDSTOPPULLUP_XMAX - #endif - #if ENABLED(USE_YMAX_PLUG) - #define ENDSTOPPULLUP_YMAX - #endif - #if ENABLED(USE_ZMAX_PLUG) - #define ENDSTOPPULLUP_ZMAX - #endif - #if ENABLED(USE_IMAX_PLUG) - #define ENDSTOPPULLUP_IMAX - #endif - #if ENABLED(USE_JMAX_PLUG) - #define ENDSTOPPULLUP_JMAX - #endif - #if ENABLED(USE_KMAX_PLUG) - #define ENDSTOPPULLUP_KMAX - #endif - #if ENABLED(USE_UMAX_PLUG) - #define ENDSTOPPULLUP_UMAX - #endif - #if ENABLED(USE_VMAX_PLUG) - #define ENDSTOPPULLUP_VMAX - #endif - #if ENABLED(USE_WMAX_PLUG) - #define ENDSTOPPULLUP_WMAX - #endif - #if ENABLED(USE_XMIN_PLUG) - #define ENDSTOPPULLUP_XMIN - #endif - #if ENABLED(USE_YMIN_PLUG) - #define ENDSTOPPULLUP_YMIN - #endif - #if ENABLED(USE_ZMIN_PLUG) - #define ENDSTOPPULLUP_ZMIN - #endif - #if ENABLED(USE_IMIN_PLUG) - #define ENDSTOPPULLUP_IMIN - #endif - #if ENABLED(USE_JMIN_PLUG) - #define ENDSTOPPULLUP_JMIN - #endif - #if ENABLED(USE_KMIN_PLUG) - #define ENDSTOPPULLUP_KMIN - #endif - #if ENABLED(USE_UMIN_PLUG) - #define ENDSTOPPULLUP_UMIN - #endif - #if ENABLED(USE_VMIN_PLUG) - #define ENDSTOPPULLUP_VMIN - #endif - #if ENABLED(USE_WMIN_PLUG) - #define ENDSTOPPULLUP_WMIN - #endif -#endif -/** - * Set ENDSTOPPULLDOWNS for active endstop switches - */ -#if ENABLED(ENDSTOPPULLDOWNS) - #if ENABLED(USE_XMAX_PLUG) - #define ENDSTOPPULLDOWN_XMAX - #endif - #if ENABLED(USE_YMAX_PLUG) - #define ENDSTOPPULLDOWN_YMAX - #endif - #if ENABLED(USE_ZMAX_PLUG) - #define ENDSTOPPULLDOWN_ZMAX - #endif - #if ENABLED(USE_IMAX_PLUG) - #define ENDSTOPPULLDOWN_IMAX - #endif - #if ENABLED(USE_JMAX_PLUG) - #define ENDSTOPPULLDOWN_JMAX - #endif - #if ENABLED(USE_KMAX_PLUG) - #define ENDSTOPPULLDOWN_KMAX - #endif - #if ENABLED(USE_UMAX_PLUG) - #define ENDSTOPPULLDOWN_UMAX - #endif - #if ENABLED(USE_VMAX_PLUG) - #define ENDSTOPPULLDOWN_VMAX - #endif - #if ENABLED(USE_WMAX_PLUG) - #define ENDSTOPPULLDOWN_WMAX - #endif - #if ENABLED(USE_XMIN_PLUG) - #define ENDSTOPPULLDOWN_XMIN - #endif - #if ENABLED(USE_YMIN_PLUG) - #define ENDSTOPPULLDOWN_YMIN +// Steppers +#if HAS_X_AXIS + #if PIN_EXISTS(X_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X)) + #define HAS_X_ENABLE 1 #endif - #if ENABLED(USE_ZMIN_PLUG) - #define ENDSTOPPULLDOWN_ZMIN + #if PIN_EXISTS(X_DIR) + #define HAS_X_DIR 1 #endif - #if ENABLED(USE_IMIN_PLUG) - #define ENDSTOPPULLDOWN_IMIN + #if PIN_EXISTS(X_STEP) + #define HAS_X_STEP 1 #endif - #if ENABLED(USE_JMIN_PLUG) - #define ENDSTOPPULLDOWN_JMIN + #if PIN_EXISTS(X_MS1) + #define HAS_X_MS_PINS 1 #endif - #if ENABLED(USE_KMIN_PLUG) - #define ENDSTOPPULLDOWN_KMIN + + #if PIN_EXISTS(X2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X2)) + #define HAS_X2_ENABLE 1 #endif - #if ENABLED(USE_UMIN_PLUG) - #define ENDSTOPPULLDOWN_UMIN + #if PIN_EXISTS(X2_DIR) + #define HAS_X2_DIR 1 #endif - #if ENABLED(USE_VMIN_PLUG) - #define ENDSTOPPULLDOWN_VMIN + #if PIN_EXISTS(X2_STEP) + #define HAS_X2_STEP 1 #endif - #if ENABLED(USE_WMIN_PLUG) - #define ENDSTOPPULLDOWN_WMIN + #if PIN_EXISTS(X2_MS1) + #define HAS_X2_MS_PINS 1 #endif #endif -/** - * Shorthand for pin tests, used wherever needed - */ - -// Steppers -#if PIN_EXISTS(X_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X)) - #define HAS_X_ENABLE 1 -#endif -#if PIN_EXISTS(X_DIR) - #define HAS_X_DIR 1 -#endif -#if PIN_EXISTS(X_STEP) - #define HAS_X_STEP 1 -#endif -#if PIN_EXISTS(X_MS1) - #define HAS_X_MS_PINS 1 -#endif - -#if PIN_EXISTS(X2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X2)) - #define HAS_X2_ENABLE 1 -#endif -#if PIN_EXISTS(X2_DIR) - #define HAS_X2_DIR 1 -#endif -#if PIN_EXISTS(X2_STEP) - #define HAS_X2_STEP 1 -#endif -#if PIN_EXISTS(X2_MS1) - #define HAS_X2_MS_PINS 1 -#endif - /** * Set defaults for missing (newer) options */ -#if !defined(DISABLE_INACTIVE_X) && ENABLED(DISABLE_X) - #define DISABLE_INACTIVE_X 1 -#endif #if HAS_Y_AXIS #if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y)) @@ -1363,23 +1085,20 @@ #define HAS_Y_MS_PINS 1 #endif - #if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2)) - #define HAS_Y2_ENABLE 1 - #endif - #if PIN_EXISTS(Y2_DIR) - #define HAS_Y2_DIR 1 - #endif - #if PIN_EXISTS(Y2_STEP) - #define HAS_Y2_STEP 1 - #endif - #if PIN_EXISTS(Y2_MS1) - #define HAS_Y2_MS_PINS 1 - #endif - #if !defined(DISABLE_INACTIVE_Y) && ENABLED(DISABLE_Y) - #define DISABLE_INACTIVE_Y 1 + #ifdef Y2_DRIVER_TYPE + #if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2)) + #define HAS_Y2_ENABLE 1 + #endif + #if PIN_EXISTS(Y2_DIR) + #define HAS_Y2_DIR 1 + #endif + #if PIN_EXISTS(Y2_STEP) + #define HAS_Y2_STEP 1 + #endif + #if PIN_EXISTS(Y2_MS1) + #define HAS_Y2_MS_PINS 1 + #endif #endif -#else - #undef DISABLE_INACTIVE_Y #endif #if HAS_Z_AXIS @@ -1395,11 +1114,6 @@ #if PIN_EXISTS(Z_MS1) #define HAS_Z_MS_PINS 1 #endif - #if !defined(DISABLE_INACTIVE_Z) && ENABLED(DISABLE_Z) - #define DISABLE_INACTIVE_Z 1 - #endif -#else - #undef DISABLE_INACTIVE_Z #endif #if NUM_Z_STEPPERS >= 2 @@ -1460,11 +1174,6 @@ #if PIN_EXISTS(I_MS1) #define HAS_I_MS_PINS 1 #endif - #if !defined(DISABLE_INACTIVE_I) && ENABLED(DISABLE_I) - #define DISABLE_INACTIVE_I 1 - #endif -#else - #undef DISABLE_INACTIVE_I #endif #if HAS_J_AXIS @@ -1480,11 +1189,6 @@ #if PIN_EXISTS(J_MS1) #define HAS_J_MS_PINS 1 #endif - #if !defined(DISABLE_INACTIVE_J) && ENABLED(DISABLE_J) - #define DISABLE_INACTIVE_J 1 - #endif -#else - #undef DISABLE_INACTIVE_J #endif #if HAS_K_AXIS @@ -1500,11 +1204,6 @@ #if PIN_EXISTS(K_MS1) #define HAS_K_MS_PINS 1 #endif - #if !defined(DISABLE_INACTIVE_K) && ENABLED(DISABLE_K) - #define DISABLE_INACTIVE_K 1 - #endif -#else - #undef DISABLE_INACTIVE_K #endif #if HAS_U_AXIS @@ -1520,11 +1219,6 @@ #if PIN_EXISTS(U_MS1) #define HAS_U_MS_PINS 1 #endif - #if !defined(DISABLE_INACTIVE_U) && ENABLED(DISABLE_U) - #define DISABLE_INACTIVE_U 1 - #endif -#else - #undef DISABLE_INACTIVE_U #endif #if HAS_V_AXIS @@ -1540,11 +1234,6 @@ #if PIN_EXISTS(V_MS1) #define HAS_V_MS_PINS 1 #endif - #if !defined(DISABLE_INACTIVE_V) && ENABLED(DISABLE_V) - #define DISABLE_INACTIVE_V 1 - #endif -#else - #undef DISABLE_INACTIVE_V #endif #if HAS_W_AXIS @@ -1560,11 +1249,6 @@ #if PIN_EXISTS(W_MS1) #define HAS_W_MS_PINS 1 #endif - #if !defined(DISABLE_INACTIVE_W) && ENABLED(DISABLE_W) - #define DISABLE_INACTIVE_W 1 - #endif -#else - #undef DISABLE_INACTIVE_W #endif // Extruder steppers and solenoids @@ -1688,11 +1372,6 @@ #endif #endif - #if !defined(DISABLE_INACTIVE_E) && ENABLED(DISABLE_E) - #define DISABLE_INACTIVE_E 1 - #endif -#else - #undef DISABLE_INACTIVE_E #endif // HAS_EXTRUDERS /** @@ -1704,7 +1383,7 @@ * - Z_PROBE_SLED uses SOL1_PIN, when defined (unless EXT_SOLENOID is enabled) */ #if ANY(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL, PARKING_EXTRUDER, SOLENOID_PROBE, Z_PROBE_SLED) - #if PIN_EXISTS(SOL0) && (EITHER(MANUAL_SOLENOID_CONTROL, PARKING_EXTRUDER) || BOTH(EXT_SOLENOID, HAS_EXTRUDERS)) + #if PIN_EXISTS(SOL0) && (ANY(MANUAL_SOLENOID_CONTROL, PARKING_EXTRUDER) || ALL(EXT_SOLENOID, HAS_EXTRUDERS)) #define HAS_SOLENOID_0 1 #endif #if PIN_EXISTS(SOL1) && (ANY(MANUAL_SOLENOID_CONTROL, PARKING_EXTRUDER, SOLENOID_PROBE, Z_PROBE_SLED) || TERN0(EXT_SOLENOID, E_STEPPERS > 1)) @@ -1738,9 +1417,10 @@ #if ANY(STEALTHCHOP_E, STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_I, STEALTHCHOP_J, STEALTHCHOP_K, STEALTHCHOP_U, STEALTHCHOP_V, STEALTHCHOP_W) #define STEALTHCHOP_ENABLED 1 #endif - #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) + #if ANY(SENSORLESS_HOMING, SENSORLESS_PROBING) #define USE_SENSORLESS 1 #endif + // Disable Z axis sensorless homing if a probe is used to home the Z axis #if HOMING_Z_WITH_PROBE #undef Z_STALL_SENSITIVITY @@ -1752,13 +1432,13 @@ #if AXIS_IS_TMC(X) #if defined(X_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X) #define X_SENSORLESS 1 + #if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(X) + #define X_SPI_SENSORLESS 1 + #endif #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 @@ -1769,7 +1449,6 @@ #define X_SLAVE_ADDRESS 0 #endif #endif - #if AXIS_IS_TMC(X2) #if defined(X2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X2) #define X2_SENSORLESS 1 @@ -1791,13 +1470,13 @@ #if AXIS_IS_TMC(Y) #if defined(Y_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y) #define Y_SENSORLESS 1 + #if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(Y) + #define Y_SPI_SENSORLESS 1 + #endif #endif #if AXIS_HAS_STEALTHCHOP(Y) #define Y_HAS_STEALTHCHOP 1 #endif - #if ENABLED(SPI_ENDSTOPS) - #define Y_SPI_SENSORLESS Y_SENSORLESS - #endif #ifndef Y_INTERPOLATE #define Y_INTERPOLATE INTERPOLATE #endif @@ -1807,44 +1486,35 @@ #ifndef Y_SLAVE_ADDRESS #define Y_SLAVE_ADDRESS 0 #endif - #if HAS_DUAL_Y_STEPPERS - #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 + #if AXIS_IS_TMC(Y2) + #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 - #if HAS_U_AXIS - #define U_SPI_SENSORLESS U_SENSORLESS + #ifndef Y2_INTERPOLATE + #define Y2_INTERPOLATE Y_INTERPOLATE #endif - #if HAS_V_AXIS - #define V_SPI_SENSORLESS V_SENSORLESS + #ifndef Y2_HOLD_MULTIPLIER + #define Y2_HOLD_MULTIPLIER Y_HOLD_MULTIPLIER #endif - #if HAS_W_AXIS - #define W_SPI_SENSORLESS W_SENSORLESS + #ifndef Y2_SLAVE_ADDRESS + #define Y2_SLAVE_ADDRESS 0 #endif #endif #if AXIS_IS_TMC(Z) #if defined(Z_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z) #define Z_SENSORLESS 1 + #if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(Z) + #define Z_SPI_SENSORLESS 1 + #endif #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 @@ -1854,69 +1524,69 @@ #ifndef Z_SLAVE_ADDRESS #define Z_SLAVE_ADDRESS 0 #endif - #if NUM_Z_STEPPERS >= 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_STEPPERS >= 2 && AXIS_IS_TMC(Z2) + #if defined(Z2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z2) + #define Z2_SENSORLESS 1 #endif - #if NUM_Z_STEPPERS >= 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 + #if AXIS_HAS_STEALTHCHOP(Z2) + #define Z2_HAS_STEALTHCHOP 1 #endif - #if NUM_Z_STEPPERS >= 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 + #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_STEPPERS >= 3 && AXIS_IS_TMC(Z3) + #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_STEPPERS >= 4 && AXIS_IS_TMC(Z4) + #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 #if AXIS_IS_TMC(I) #if defined(I_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(I) #define I_SENSORLESS 1 + #if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(I) + #define I_SPI_SENSORLESS 1 + #endif #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 @@ -1931,13 +1601,13 @@ #if AXIS_IS_TMC(J) #if defined(J_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(J) #define J_SENSORLESS 1 + #if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(J) + #define J_SPI_SENSORLESS 1 + #endif #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 @@ -1952,13 +1622,13 @@ #if AXIS_IS_TMC(K) #if defined(K_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(K) #define K_SENSORLESS 1 + #if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(K) + #define K_SPI_SENSORLESS 1 + #endif #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 @@ -1973,13 +1643,13 @@ #if AXIS_IS_TMC(U) #if defined(U_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(U) #define U_SENSORLESS 1 + #if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(U) + #define U_SPI_SENSORLESS 1 + #endif #endif #if AXIS_HAS_STEALTHCHOP(U) #define U_HAS_STEALTHCHOP 1 #endif - #if ENABLED(SPI_ENDSTOPS) - #define U_SPI_SENSORLESS U_SENSORLESS - #endif #ifndef U_INTERPOLATE #define U_INTERPOLATE INTERPOLATE #endif @@ -1994,13 +1664,13 @@ #if AXIS_IS_TMC(V) #if defined(V_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(V) #define V_SENSORLESS 1 + #if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(V) + #define V_SPI_SENSORLESS 1 + #endif #endif #if AXIS_HAS_STEALTHCHOP(V) #define V_HAS_STEALTHCHOP 1 #endif - #if ENABLED(SPI_ENDSTOPS) - #define V_SPI_SENSORLESS V_SENSORLESS - #endif #ifndef V_INTERPOLATE #define V_INTERPOLATE INTERPOLATE #endif @@ -2015,13 +1685,13 @@ #if AXIS_IS_TMC(W) #if defined(W_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(W) #define W_SENSORLESS 1 + #if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(W) + #define W_SPI_SENSORLESS 1 + #endif #endif #if AXIS_HAS_STEALTHCHOP(W) #define W_HAS_STEALTHCHOP 1 #endif - #if ENABLED(SPI_ENDSTOPS) - #define W_SPI_SENSORLESS W_SENSORLESS - #endif #ifndef W_INTERPOLATE #define W_INTERPOLATE INTERPOLATE #endif @@ -2260,6 +1930,14 @@ #undef TMC_UART_IS #undef ANY_SERIAL_IS +#if defined(__AVR_ARCH__) && defined(TMC_SPI_MISO) && defined(TMC_SPI_MOSI) && defined(TMC_SPI_SCK) + // Check that the pins are the solitary supported SPI hardware pins of the (AVR) platform. + // Otherwise we are forced to enable software SPI. + #if TMC_SPI_MISO != MISO || TMC_SPI_MOSI != MOSI || TMC_SPI_SCK != SCK + #define TMC_USE_SW_SPI + #endif +#endif + // Clean up unused ESP_WIFI pins #ifdef ESP_WIFI_MODULE_COM #if !SERIAL_IN_USE(ESP_WIFI_MODULE_COM) @@ -2289,88 +1967,88 @@ #define _HAS_STOP(A,M) (HAS_##A##_AXIS && PIN_EXISTS(A##_##M) && !IS_PROBE_PIN(A,M) && !IS_X2_ENDSTOP(A,M) && !IS_Y2_ENDSTOP(A,M) && !IS_Z2_ENDSTOP(A,M) && !IS_Z3_ENDSTOP(A,M) && !IS_Z4_ENDSTOP(A,M)) #if _HAS_STOP(X,MIN) - #define HAS_X_MIN 1 + #define USE_X_MIN 1 #endif #if _HAS_STOP(X,MAX) - #define HAS_X_MAX 1 + #define USE_X_MAX 1 #endif #if _HAS_STOP(Y,MIN) - #define HAS_Y_MIN 1 + #define USE_Y_MIN 1 #endif #if _HAS_STOP(Y,MAX) - #define HAS_Y_MAX 1 + #define USE_Y_MAX 1 #endif #if _HAS_STOP(Z,MIN) - #define HAS_Z_MIN 1 + #define USE_Z_MIN 1 #endif #if _HAS_STOP(Z,MAX) - #define HAS_Z_MAX 1 + #define USE_Z_MAX 1 #endif #if _HAS_STOP(I,MIN) - #define HAS_I_MIN 1 + #define USE_I_MIN 1 #endif #if _HAS_STOP(I,MAX) - #define HAS_I_MAX 1 + #define USE_I_MAX 1 #endif #if _HAS_STOP(J,MIN) - #define HAS_J_MIN 1 + #define USE_J_MIN 1 #endif #if _HAS_STOP(J,MAX) - #define HAS_J_MAX 1 + #define USE_J_MAX 1 #endif #if _HAS_STOP(K,MIN) - #define HAS_K_MIN 1 + #define USE_K_MIN 1 #endif #if _HAS_STOP(K,MAX) - #define HAS_K_MAX 1 + #define USE_K_MAX 1 #endif #if _HAS_STOP(U,MIN) - #define HAS_U_MIN 1 + #define USE_U_MIN 1 #endif #if _HAS_STOP(U,MAX) - #define HAS_U_MAX 1 + #define USE_U_MAX 1 #endif #if _HAS_STOP(V,MIN) - #define HAS_V_MIN 1 + #define USE_V_MIN 1 #endif #if _HAS_STOP(V,MAX) - #define HAS_V_MAX 1 + #define USE_V_MAX 1 #endif #if _HAS_STOP(W,MIN) - #define HAS_W_MIN 1 + #define USE_W_MIN 1 #endif #if _HAS_STOP(W,MAX) - #define HAS_W_MAX 1 + #define USE_W_MAX 1 #endif #if PIN_EXISTS(X2_MIN) - #define HAS_X2_MIN 1 + #define USE_X2_MIN 1 #endif #if PIN_EXISTS(X2_MAX) - #define HAS_X2_MAX 1 + #define USE_X2_MAX 1 #endif #if PIN_EXISTS(Y2_MIN) - #define HAS_Y2_MIN 1 + #define USE_Y2_MIN 1 #endif #if PIN_EXISTS(Y2_MAX) - #define HAS_Y2_MAX 1 + #define USE_Y2_MAX 1 #endif #if PIN_EXISTS(Z2_MIN) - #define HAS_Z2_MIN 1 + #define USE_Z2_MIN 1 #endif #if PIN_EXISTS(Z2_MAX) - #define HAS_Z2_MAX 1 + #define USE_Z2_MAX 1 #endif #if PIN_EXISTS(Z3_MIN) - #define HAS_Z3_MIN 1 + #define USE_Z3_MIN 1 #endif #if PIN_EXISTS(Z3_MAX) - #define HAS_Z3_MAX 1 + #define USE_Z3_MAX 1 #endif #if PIN_EXISTS(Z4_MIN) - #define HAS_Z4_MIN 1 + #define USE_Z4_MIN 1 #endif #if PIN_EXISTS(Z4_MAX) - #define HAS_Z4_MAX 1 + #define USE_Z4_MAX 1 #endif #if HAS_BED_PROBE && PIN_EXISTS(Z_MIN_PROBE) @@ -2385,6 +2063,126 @@ #undef IS_Z3_ENDSTOP #undef IS_Z4_ENDSTOP +/** + * Set ENDSTOPPULLUPS for active endstop switches + */ +#if ENABLED(ENDSTOPPULLUPS) + #if USE_X_MIN + #define ENDSTOPPULLUP_XMIN + #endif + #if USE_X_MAX + #define ENDSTOPPULLUP_XMAX + #endif + #if USE_Y_MIN + #define ENDSTOPPULLUP_YMIN + #endif + #if USE_Y_MAX + #define ENDSTOPPULLUP_YMAX + #endif + #if USE_Z_MIN + #define ENDSTOPPULLUP_ZMIN + #endif + #if USE_Z_MAX + #define ENDSTOPPULLUP_ZMAX + #endif + #if USE_I_MIN + #define ENDSTOPPULLUP_IMIN + #endif + #if USE_I_MAX + #define ENDSTOPPULLUP_IMAX + #endif + #if USE_J_MIN + #define ENDSTOPPULLUP_JMIN + #endif + #if USE_J_MAX + #define ENDSTOPPULLUP_JMAX + #endif + #if USE_K_MIN + #define ENDSTOPPULLUP_KMIN + #endif + #if USE_K_MAX + #define ENDSTOPPULLUP_KMAX + #endif + #if USE_U_MIN + #define ENDSTOPPULLUP_UMIN + #endif + #if USE_U_MAX + #define ENDSTOPPULLUP_UMAX + #endif + #if USE_V_MIN + #define ENDSTOPPULLUP_VMIN + #endif + #if USE_V_MAX + #define ENDSTOPPULLUP_VMAX + #endif + #if USE_W_MIN + #define ENDSTOPPULLUP_WMIN + #endif + #if USE_W_MAX + #define ENDSTOPPULLUP_WMAX + #endif +#endif + +/** + * Set ENDSTOPPULLDOWNS for active endstop switches + */ +#if ENABLED(ENDSTOPPULLDOWNS) + #if USE_X_MIN + #define ENDSTOPPULLDOWN_XMIN + #endif + #if USE_X_MAX + #define ENDSTOPPULLDOWN_XMAX + #endif + #if USE_Y_MIN + #define ENDSTOPPULLDOWN_YMIN + #endif + #if USE_Y_MAX + #define ENDSTOPPULLDOWN_YMAX + #endif + #if USE_Z_MIN + #define ENDSTOPPULLDOWN_ZMIN + #endif + #if USE_Z_MAX + #define ENDSTOPPULLDOWN_ZMAX + #endif + #if USE_I_MIN + #define ENDSTOPPULLDOWN_IMIN + #endif + #if USE_I_MAX + #define ENDSTOPPULLDOWN_IMAX + #endif + #if USE_J_MIN + #define ENDSTOPPULLDOWN_JMIN + #endif + #if USE_J_MAX + #define ENDSTOPPULLDOWN_JMAX + #endif + #if USE_K_MIN + #define ENDSTOPPULLDOWN_KMIN + #endif + #if USE_K_MAX + #define ENDSTOPPULLDOWN_KMAX + #endif + #if USE_U_MIN + #define ENDSTOPPULLDOWN_UMIN + #endif + #if USE_U_MAX + #define ENDSTOPPULLDOWN_UMAX + #endif + #if USE_V_MIN + #define ENDSTOPPULLDOWN_VMIN + #endif + #if USE_V_MAX + #define ENDSTOPPULLDOWN_VMAX + #endif + #if USE_W_MIN + #define ENDSTOPPULLDOWN_WMIN + #endif + #if USE_W_MAX + #define ENDSTOPPULLDOWN_WMAX + #endif +#endif + // // ADC Temp Sensors (Thermistor or Thermocouple with amplifier ADC interface) // @@ -2413,8 +2211,11 @@ #if HOTENDS > 7 && HAS_ADC_TEST(7) #define HAS_TEMP_ADC_7 1 #endif -#if HAS_ADC_TEST(BED) - #define HAS_TEMP_ADC_BED 1 +#if TEMP_SENSOR_BED + #define HAS_HEATED_BED 1 + #if HAS_ADC_TEST(BED) + #define HAS_TEMP_ADC_BED 1 + #endif #endif #if HAS_ADC_TEST(PROBE) #define HAS_TEMP_ADC_PROBE 1 @@ -2432,7 +2233,7 @@ #define HAS_TEMP_ADC_REDUNDANT 1 #endif -#define HAS_TEMP(N) (TEMP_SENSOR_IS_MAX_TC(N) || EITHER(HAS_TEMP_ADC_##N, TEMP_SENSOR_##N##_IS_DUMMY)) +#define HAS_TEMP(N) (TEMP_SENSOR_IS_MAX_TC(N) || HAS_TEMP_ADC_##N || TEMP_SENSOR_##N##_IS_DUMMY) #if HAS_HOTEND && HAS_TEMP(0) #define HAS_TEMP_HOTEND 1 #endif @@ -2498,14 +2299,16 @@ #if PIN_EXISTS(HEATER_BED) #define HAS_HEATER_BED 1 #endif +#if PIN_EXISTS(HEATER_CHAMBER) + #define HAS_HEATER_CHAMBER 1 +#endif // Shorthand for common combinations -#if HAS_TEMP_BED && HAS_HEATER_BED - #define HAS_HEATED_BED 1 +#if HAS_HEATED_BED #ifndef BED_OVERSHOOT #define BED_OVERSHOOT 10 #endif - #define BED_MAX_TARGET (BED_MAXTEMP - (BED_OVERSHOOT)) + #define BED_MAX_TARGET ((BED_MAXTEMP) - (BED_OVERSHOOT)) #else #undef PIDTEMPBED #undef PREHEAT_BEFORE_LEVELING @@ -2528,12 +2331,12 @@ #define HAS_TEMP_SENSOR 1 #endif -#if HAS_TEMP_CHAMBER && PIN_EXISTS(HEATER_CHAMBER) +#if HAS_TEMP_CHAMBER && HAS_HEATER_CHAMBER #define HAS_HEATED_CHAMBER 1 #ifndef CHAMBER_OVERSHOOT #define CHAMBER_OVERSHOOT 10 #endif - #define CHAMBER_MAX_TARGET (CHAMBER_MAXTEMP - (CHAMBER_OVERSHOOT)) + #define CHAMBER_MAX_TARGET ((CHAMBER_MAXTEMP) - (CHAMBER_OVERSHOOT)) #else #undef PIDTEMPCHAMBER #endif @@ -2546,6 +2349,7 @@ // Thermal protection #if !HAS_HEATED_BED #undef THERMAL_PROTECTION_BED + #undef THERMAL_PROTECTION_BED_PERIOD #endif #if ENABLED(THERMAL_PROTECTION_HOTENDS) && WATCH_TEMP_PERIOD > 0 #define WATCH_HOTENDS 1 @@ -2553,10 +2357,10 @@ #if ENABLED(THERMAL_PROTECTION_BED) && WATCH_BED_TEMP_PERIOD > 0 #define WATCH_BED 1 #endif -#if BOTH(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) && WATCH_CHAMBER_TEMP_PERIOD > 0 +#if ALL(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) && WATCH_CHAMBER_TEMP_PERIOD > 0 #define WATCH_CHAMBER 1 #endif -#if BOTH(HAS_COOLER, THERMAL_PROTECTION_COOLER) && WATCH_COOLER_TEMP_PERIOD > 0 +#if ALL(HAS_COOLER, THERMAL_PROTECTION_COOLER) && WATCH_COOLER_TEMP_PERIOD > 0 #define WATCH_COOLER 1 #endif #if NONE(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER, THERMAL_PROTECTION_BED, THERMAL_PROTECTION_COOLER) @@ -2666,26 +2470,31 @@ #undef AUTO_POWER_COOLER_FAN #endif -// Print Cooling fans (limit) +/** + * Controller Fan Settings + */ +#if PIN_EXISTS(CONTROLLER_FAN) + #define HAS_CONTROLLER_FAN 1 +#endif + +/** + * Up to 12 PWM fans + */ #ifdef NUM_M106_FANS #define MAX_FANS NUM_M106_FANS #else - #define MAX_FANS 8 // Max supported fans -#endif - -#define _NOT_E_AUTO(N,F) (E##N##_AUTO_FAN_PIN != FAN##F##_PIN) -#define _HAS_FAN(F) (PIN_EXISTS(FAN##F) \ - && CONTROLLER_FAN_PIN != FAN##F##_PIN \ - && _NOT_E_AUTO(0,F) \ - && _NOT_E_AUTO(1,F) \ - && _NOT_E_AUTO(2,F) \ - && _NOT_E_AUTO(3,F) \ - && _NOT_E_AUTO(4,F) \ - && _NOT_E_AUTO(5,F) \ - && _NOT_E_AUTO(6,F) \ - && _NOT_E_AUTO(7,F) \ - && F < MAX_FANS) -#if PIN_EXISTS(FAN) + #define MAX_FANS 12 // Max supported fans +#endif + +#define _IS_E_AUTO(N,F) (PIN_EXISTS(E##N##_AUTO_FAN) && E##N##_AUTO_FAN_PIN == FAN##F##_PIN) +#define _HAS_FAN(F) (F < MAX_FANS && PIN_EXISTS(FAN##F) \ + && !(HAS_CONTROLLER_FAN && CONTROLLER_FAN_PIN == FAN##F##_PIN) \ + && !_IS_E_AUTO(0,F) && !_IS_E_AUTO(1,F) \ + && !_IS_E_AUTO(2,F) && !_IS_E_AUTO(3,F) \ + && !_IS_E_AUTO(4,F) && !_IS_E_AUTO(5,F) \ + && !_IS_E_AUTO(6,F) && !_IS_E_AUTO(7,F)) + +#if _HAS_FAN(0) #define HAS_FAN0 1 #endif #if _HAS_FAN(1) @@ -2709,21 +2518,34 @@ #if _HAS_FAN(7) #define HAS_FAN7 1 #endif -#undef _NOT_E_AUTO +#if _HAS_FAN(8) + #define HAS_FAN8 1 +#endif +#if _HAS_FAN(9) + #define HAS_FAN9 1 +#endif +#if _HAS_FAN(10) + #define HAS_FAN10 1 +#endif +#if _HAS_FAN(11) + #define HAS_FAN11 1 +#endif #undef _HAS_FAN +#undef _IS_E_AUTO #if BED_OR_CHAMBER || HAS_FAN0 #define BED_OR_CHAMBER_OR_FAN 1 #endif -/** - * Up to 3 PWM fans - */ -#ifndef FAN_INVERTING - #define FAN_INVERTING false -#endif - -#if HAS_FAN7 +#if HAS_FAN11 + #define FAN_COUNT 12 +#elif HAS_FAN10 + #define FAN_COUNT 11 +#elif HAS_FAN9 + #define FAN_COUNT 10 +#elif HAS_FAN8 + #define FAN_COUNT 9 +#elif HAS_FAN7 #define FAN_COUNT 8 #elif HAS_FAN6 #define FAN_COUNT 7 @@ -2747,11 +2569,8 @@ #define HAS_FAN 1 #endif -/** - * Part Cooling fan multipliexer - */ #if PIN_EXISTS(FANMUX0) - #define HAS_FANMUX 1 + #define HAS_FANMUX 1 // Part Cooling fan multipliexer #endif /** @@ -2814,8 +2633,28 @@ #if PIN_EXISTS(SERVO3) && NUM_SERVOS > 3 #define HAS_SERVO_3 1 #endif + +// Servos #if NUM_SERVOS > 0 #define HAS_SERVOS 1 + #if PIN_EXISTS(SERVO0) + #define HAS_SERVO_0 1 + #endif + #if PIN_EXISTS(SERVO1) && NUM_SERVOS > 1 + #define HAS_SERVO_1 1 + #endif + #if PIN_EXISTS(SERVO2) && NUM_SERVOS > 2 + #define HAS_SERVO_2 1 + #endif + #if PIN_EXISTS(SERVO3) && NUM_SERVOS > 3 + #define HAS_SERVO_3 1 + #endif + #if PIN_EXISTS(SERVO4) && NUM_SERVOS > 4 + #define HAS_SERVO_4 1 + #endif + #if PIN_EXISTS(SERVO5) && NUM_SERVOS > 5 + #define HAS_SERVO_5 1 + #endif #if defined(PAUSE_SERVO_OUTPUT) && defined(RESUME_SERVO_OUTPUT) #define HAS_PAUSE_SERVO_OUTPUT 1 #endif @@ -2871,54 +2710,24 @@ #define HAS_MICROSTEPS 1 #endif -/** - * Heater signal inversion defaults - */ - -#if HAS_HEATER_0 && !defined(HEATER_0_INVERTING) - #define HEATER_0_INVERTING false -#endif -#if HAS_HEATER_1 && !defined(HEATER_1_INVERTING) - #define HEATER_1_INVERTING false -#endif -#if HAS_HEATER_2 && !defined(HEATER_2_INVERTING) - #define HEATER_2_INVERTING false -#endif -#if HAS_HEATER_3 && !defined(HEATER_3_INVERTING) - #define HEATER_3_INVERTING false -#endif -#if HAS_HEATER_4 && !defined(HEATER_4_INVERTING) - #define HEATER_4_INVERTING false -#endif -#if HAS_HEATER_5 && !defined(HEATER_5_INVERTING) - #define HEATER_5_INVERTING false -#endif -#if HAS_HEATER_6 && !defined(HEATER_6_INVERTING) - #define HEATER_6_INVERTING false -#endif -#if HAS_HEATER_7 && !defined(HEATER_7_INVERTING) - #define HEATER_7_INVERTING false -#endif - /** * Helper Macros for heaters and extruder fan */ - -#define WRITE_HEATER_0P(v) WRITE(HEATER_0_PIN, (v) ^ HEATER_0_INVERTING) -#if EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) - #define WRITE_HEATER_1(v) WRITE(HEATER_1_PIN, (v) ^ HEATER_1_INVERTING) +#define WRITE_HEATER_0P(v) WRITE(HEATER_0_PIN, (v) ^ ENABLED(HEATER_0_INVERTING)) +#if ANY(HAS_MULTI_HOTEND, HEATERS_PARALLEL) + #define WRITE_HEATER_1(v) WRITE(HEATER_1_PIN, (v) ^ ENABLED(HEATER_1_INVERTING)) #if HOTENDS > 2 - #define WRITE_HEATER_2(v) WRITE(HEATER_2_PIN, (v) ^ HEATER_2_INVERTING) + #define WRITE_HEATER_2(v) WRITE(HEATER_2_PIN, (v) ^ ENABLED(HEATER_2_INVERTING)) #if HOTENDS > 3 - #define WRITE_HEATER_3(v) WRITE(HEATER_3_PIN, (v) ^ HEATER_3_INVERTING) + #define WRITE_HEATER_3(v) WRITE(HEATER_3_PIN, (v) ^ ENABLED(HEATER_3_INVERTING)) #if HOTENDS > 4 - #define WRITE_HEATER_4(v) WRITE(HEATER_4_PIN, (v) ^ HEATER_4_INVERTING) + #define WRITE_HEATER_4(v) WRITE(HEATER_4_PIN, (v) ^ ENABLED(HEATER_4_INVERTING)) #if HOTENDS > 5 - #define WRITE_HEATER_5(v) WRITE(HEATER_5_PIN, (v) ^ HEATER_5_INVERTING) + #define WRITE_HEATER_5(v) WRITE(HEATER_5_PIN, (v) ^ ENABLED(HEATER_5_INVERTING)) #if HOTENDS > 6 - #define WRITE_HEATER_6(v) WRITE(HEATER_6_PIN, (v) ^ HEATER_6_INVERTING) + #define WRITE_HEATER_6(v) WRITE(HEATER_6_PIN, (v) ^ ENABLED(HEATER_6_INVERTING)) #if HOTENDS > 7 - #define WRITE_HEATER_7(v) WRITE(HEATER_7_PIN, (v) ^ HEATER_7_INVERTING) + #define WRITE_HEATER_7(v) WRITE(HEATER_7_PIN, (v) ^ ENABLED(HEATER_7_INVERTING)) #endif // HOTENDS > 7 #endif // HOTENDS > 6 #endif // HOTENDS > 5 @@ -2946,10 +2755,7 @@ #ifndef MAX_BED_POWER #define MAX_BED_POWER 255 #endif - #ifndef HEATER_BED_INVERTING - #define HEATER_BED_INVERTING false - #endif - #define WRITE_HEATER_BED(v) WRITE(HEATER_BED_PIN, (v) ^ HEATER_BED_INVERTING) + #define WRITE_HEATER_BED(v) WRITE(HEATER_BED_PIN, (v) ^ ENABLED(HEATER_BED_INVERTING)) #endif /** @@ -2962,10 +2768,7 @@ #ifndef MAX_CHAMBER_POWER #define MAX_CHAMBER_POWER 255 #endif - #ifndef HEATER_CHAMBER_INVERTING - #define HEATER_CHAMBER_INVERTING false - #endif - #define WRITE_HEATER_CHAMBER(v) WRITE(HEATER_CHAMBER_PIN, (v) ^ HEATER_CHAMBER_INVERTING) + #define WRITE_HEATER_CHAMBER(v) WRITE(HEATER_CHAMBER_PIN, (v) ^ ENABLED(HEATER_CHAMBER_INVERTING)) #endif /** @@ -2975,10 +2778,7 @@ #ifndef MAX_COOLER_POWER #define MAX_COOLER_POWER 255 #endif - #ifndef COOLER_INVERTING - #define COOLER_INVERTING true - #endif - #define WRITE_HEATER_COOLER(v) WRITE(COOLER_PIN, (v) ^ COOLER_INVERTING) + #define WRITE_HEATER_COOLER(v) WRITE(COOLER_PIN, (v) ^ ENABLED(COOLER_INVERTING)) #endif #if HAS_HOTEND || HAS_HEATED_BED || HAS_HEATED_CHAMBER || HAS_COOLER @@ -3031,16 +2831,28 @@ /** * Bed Probe dependencies */ -#if EITHER(MESH_BED_LEVELING, HAS_BED_PROBE) - #ifndef Z_PROBE_OFFSET_RANGE_MIN - #define Z_PROBE_OFFSET_RANGE_MIN -20 +#if ANY(MESH_BED_LEVELING, HAS_BED_PROBE) + #ifndef PROBE_OFFSET_ZMIN + #define PROBE_OFFSET_ZMIN -20 #endif - #ifndef Z_PROBE_OFFSET_RANGE_MAX - #define Z_PROBE_OFFSET_RANGE_MAX 20 + #ifndef PROBE_OFFSET_ZMAX + #define PROBE_OFFSET_ZMAX 20 #endif #endif #if HAS_BED_PROBE - #if BOTH(ENDSTOPPULLUPS, HAS_Z_MIN_PROBE_PIN) + #ifndef PROBE_OFFSET_XMIN + #define PROBE_OFFSET_XMIN -50 + #endif + #ifndef PROBE_OFFSET_XMAX + #define PROBE_OFFSET_XMAX 50 + #endif + #ifndef PROBE_OFFSET_YMIN + #define PROBE_OFFSET_YMIN -50 + #endif + #ifndef PROBE_OFFSET_YMAX + #define PROBE_OFFSET_YMAX 50 + #endif + #if ALL(ENDSTOPPULLUPS, USE_Z_MIN_PROBE) #define ENDSTOPPULLUP_ZMIN_PROBE #endif #ifndef XY_PROBE_FEEDRATE @@ -3098,16 +2910,16 @@ #undef ADAPTIVE_FAN_SLOWING #undef NO_FAN_SLOWING_IN_PID_TUNING #endif -#if !BOTH(HAS_BED_PROBE, HAS_FAN) +#if !ALL(HAS_BED_PROBE, HAS_FAN) #undef PROBING_FANS_OFF #endif -#if !BOTH(HAS_BED_PROBE, HAS_EXTRUDERS) +#if !ALL(HAS_BED_PROBE, HAS_EXTRUDERS) #undef PROBING_ESTEPPERS_OFF #elif ENABLED(PROBING_STEPPERS_OFF) // PROBING_STEPPERS_OFF implies PROBING_ESTEPPERS_OFF, make sure it is defined #define PROBING_ESTEPPERS_OFF #endif -#if EITHER(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF) +#if ANY(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF) #define HEATER_IDLE_HANDLER 1 #endif #if HAS_BED_PROBE && (ANY(PROBING_HEATERS_OFF, PROBING_STEPPERS_OFF, PROBING_ESTEPPERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0) @@ -3118,7 +2930,7 @@ * Advanced Pause - Filament Change */ #if ENABLED(ADVANCED_PAUSE_FEATURE) - #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) + #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) || ALL(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) #define M600_PURGE_MORE_RESUMABLE 1 #endif #ifndef FILAMENT_CHANGE_SLOW_LOAD_LENGTH @@ -3201,19 +3013,19 @@ /** * Default mesh area is an area with an inset margin on the print area. */ -#if EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) +#if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) #if IS_KINEMATIC // Probing points may be verified at compile time within the radius // using static_assert(HYPOT2(X2-X1,Y2-Y1)<=sq(DELTA_PRINTABLE_RADIUS),"bad probe point!") // so that may be added to SanityCheck.h in the future. - #define _MESH_MIN_X (X_MIN_BED + MESH_INSET) - #define _MESH_MIN_Y (Y_MIN_BED + MESH_INSET) + #define _MESH_MIN_X (X_MIN_BED + (MESH_INSET)) + #define _MESH_MIN_Y (Y_MIN_BED + (MESH_INSET)) #define _MESH_MAX_X (X_MAX_BED - (MESH_INSET)) #define _MESH_MAX_Y (Y_MAX_BED - (MESH_INSET)) #else // Boundaries for Cartesian probing based on set limits - #define _MESH_MIN_X (_MAX(X_MIN_BED + MESH_INSET, X_MIN_POS)) // UBL is careful not to probe off the bed. It does not - #define _MESH_MIN_Y (_MAX(Y_MIN_BED + MESH_INSET, Y_MIN_POS)) // need NOZZLE_TO_PROBE_OFFSET in the mesh dimensions + #define _MESH_MIN_X (_MAX(X_MIN_BED + (MESH_INSET), X_MIN_POS)) // UBL is careful not to probe off the bed. It doesn't + #define _MESH_MIN_Y (_MAX(Y_MIN_BED + (MESH_INSET), Y_MIN_POS)) // need NOZZLE_TO_PROBE_OFFSET in the mesh dimensions. #define _MESH_MAX_X (_MIN(X_MAX_BED - (MESH_INSET), X_MAX_POS)) #define _MESH_MAX_Y (_MIN(Y_MAX_BED - (MESH_INSET), Y_MAX_POS)) #endif @@ -3255,7 +3067,7 @@ #if ANY(IS_TFTGLCD_PANEL, PCA9632_BUZZER, LCD_USE_I2C_BUZZER) #define USE_MARLINUI_BUZZER 1 #endif -#if EITHER(HAS_BEEPER, USE_MARLINUI_BUZZER) +#if ANY(HAS_BEEPER, USE_MARLINUI_BUZZER) #define HAS_SOUND 1 #endif @@ -3326,7 +3138,7 @@ // Define a starting height for measuring manual probe points #ifndef MANUAL_PROBE_START_Z - #if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) + #if ANY(MESH_BED_LEVELING, PROBE_MANUALLY) // Leave MANUAL_PROBE_START_Z undefined so the prior Z height will be used. // Note: If Z_CLEARANCE_BETWEEN_MANUAL_PROBES is 0 there will be no raise between points #elif ENABLED(AUTO_BED_LEVELING_UBL) && defined(Z_CLEARANCE_BETWEEN_PROBES) @@ -3340,7 +3152,7 @@ #undef MOTOR_CURRENT #endif -// Updated G92 behavior shifts the workspace +// G92 shifts the workspace #if DISABLED(NO_WORKSPACE_OFFSETS) #define HAS_POSITION_SHIFT 1 #if IS_CARTESIAN @@ -3352,7 +3164,7 @@ #endif #endif -#if EITHER(HAS_MARLINUI_MENU, TOUCH_UI_FTDI_EVE) +#if ANY(HAS_MARLINUI_MENU, TOUCH_UI_FTDI_EVE) // LCD timeout to status screen default is 15s #ifndef LCD_TIMEOUT_TO_STATUS #define LCD_TIMEOUT_TO_STATUS 15000 @@ -3377,15 +3189,35 @@ #endif #endif +// Touch Calibration +#if ANY(HAS_SPI_TFT, HAS_FSMC_TFT, HAS_LTDC_TFT) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X 0 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 0 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 0 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y 0 + #endif + #ifndef TOUCH_ORIENTATION + #define TOUCH_ORIENTATION TOUCH_LANDSCAPE + #endif +#endif + // Number of VFAT entries used. Each entry has 13 UTF-16 characters -#if EITHER(SCROLL_LONG_FILENAMES, HAS_DWIN_E3V2) - #define MAX_VFAT_ENTRIES (5) +#if ANY(SCROLL_LONG_FILENAMES, HAS_DWIN_E3V2, TFT_COLOR_UI) + #define VFAT_ENTRIES_LIMIT 5 #else - #define MAX_VFAT_ENTRIES (2) + #define VFAT_ENTRIES_LIMIT 2 #endif +#define MAX_VFAT_ENTRIES 20 // by VFAT specs to fit LFN of length 255 // Nozzle park for Delta -#if BOTH(NOZZLE_PARK_FEATURE, DELTA) +#if ALL(NOZZLE_PARK_FEATURE, DELTA) #undef NOZZLE_PARK_Z_FEEDRATE #define NOZZLE_PARK_Z_FEEDRATE NOZZLE_PARK_XY_FEEDRATE #endif @@ -3396,16 +3228,19 @@ #if defined(TARGET_LPC1768) && IS_RRD_FG_SC && (SD_SCK_PIN == LCD_PINS_D4) #define SDCARD_SORT_ALPHA // Keep one directory level in RAM. Changing directory levels // may still glitch the screen, but LCD updates clean it up. - #undef SDSORT_LIMIT - #undef SDSORT_USES_RAM - #undef SDSORT_USES_STACK - #undef SDSORT_CACHE_NAMES - #define SDSORT_LIMIT 64 - #define SDSORT_USES_RAM true - #define SDSORT_USES_STACK false - #define SDSORT_CACHE_NAMES true - #ifndef FOLDER_SORTING - #define FOLDER_SORTING -1 + #if SDSORT_LIMIT > 64 || !SDSORT_USES_RAM || SDSORT_USES_STACK || !SDSORT_CACHE_NAMES + #undef SDSORT_LIMIT + #undef SDSORT_USES_RAM + #undef SDSORT_USES_STACK + #undef SDSORT_CACHE_NAMES + #define SDSORT_LIMIT 64 + #define SDSORT_USES_RAM true + #define SDSORT_USES_STACK false + #define SDSORT_CACHE_NAMES true + #define SDSORT_CACHE_LPC1768_WARNING 1 + #endif + #ifndef SDSORT_FOLDERS + #define SDSORT_FOLDERS -1 #endif #ifndef SDSORT_GCODE #define SDSORT_GCODE false @@ -3419,7 +3254,7 @@ #endif // Fallback SPI Speed for SD -#if ENABLED(SDSUPPORT) && !defined(SD_SPI_SPEED) +#if HAS_MEDIA && !defined(SD_SPI_SPEED) #define SD_SPI_SPEED SPI_FULL_SPEED #endif diff --git a/Marlin/src/inc/MarlinConfig.h b/Marlin/src/inc/MarlinConfig.h index c8584be1c727..dda1480e02a9 100644 --- a/Marlin/src/inc/MarlinConfig.h +++ b/Marlin/src/inc/MarlinConfig.h @@ -27,7 +27,9 @@ #include "MarlinConfigPre.h" -#ifndef __MARLIN_DEPS__ +#ifdef __MARLIN_DEPS__ + #include "../HAL/shared/fauxpins.h" +#else #include "../HAL/HAL.h" #endif @@ -46,6 +48,7 @@ #include "../core/types.h" // Ahead of sanity-checks + #include "Changes.h" #include "SanityCheck.h" #include HAL_PATH(.., inc/SanityCheck.h) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ca47353fa3b8..7a9c8aef6251 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -46,8 +46,8 @@ #if ENABLED(TEST0) || !ENABLED(TEST2) || ENABLED(TEST3) || !ENABLED(TEST1, TEST2, TEST4) #error "ENABLED is borked!" #endif -#if BOTH(TEST0, TEST1) - #error "BOTH is borked!" +#if ALL(TEST0, TEST1) + #error "ALL is borked!" #endif #if DISABLED(TEST1) || !DISABLED(TEST3) || DISABLED(TEST4) || DISABLED(TEST0, TEST1, TEST2, TEST4) || !DISABLED(TEST0, TEST3) #error "DISABLED is borked!" @@ -91,593 +91,28 @@ #error "MOTHERBOARD is required. You must '#define MOTHERBOARD BOARD_MYNAME' (not just '#define BOARD_MYNAME')." #elif !defined(X_BED_SIZE) || !defined(Y_BED_SIZE) #error "X_BED_SIZE and Y_BED_SIZE are now required!" -#elif WATCH_TEMP_PERIOD > 500 - #error "WATCH_TEMP_PERIOD now uses seconds instead of milliseconds." -#elif DISABLED(THERMAL_PROTECTION_HOTENDS) && (defined(WATCH_TEMP_PERIOD) || defined(THERMAL_PROTECTION_PERIOD)) - #error "Thermal Runaway Protection for hotends is now enabled with THERMAL_PROTECTION_HOTENDS." -#elif DISABLED(THERMAL_PROTECTION_BED) && defined(THERMAL_PROTECTION_BED_PERIOD) - #error "Thermal Runaway Protection for the bed is now enabled with THERMAL_PROTECTION_BED." -#elif (CORE_IS_XZ || CORE_IS_YZ) && ENABLED(Z_LATE_ENABLE) - #error "Z_LATE_ENABLE can't be used with COREXZ, COREZX, COREYZ, or COREZY." -#elif defined(X_HOME_RETRACT_MM) - #error "[XYZ]_HOME_RETRACT_MM settings have been renamed [XYZ]_HOME_BUMP_MM." -#elif defined(SDCARDDETECTINVERTED) - #error "SDCARDDETECTINVERTED is now SD_DETECT_STATE (HIGH)." -#elif defined(SD_DETECT_INVERTED) - #error "SD_DETECT_INVERTED is now SD_DETECT_STATE (HIGH)." -#elif defined(BTENABLED) - #error "BTENABLED is now BLUETOOTH." -#elif defined(CUSTOM_MENDEL_NAME) - #error "CUSTOM_MENDEL_NAME is now CUSTOM_MACHINE_NAME." -#elif defined(HAS_AUTOMATIC_VERSIONING) - #error "HAS_AUTOMATIC_VERSIONING is now CUSTOM_VERSION_FILE." -#elif defined(USE_AUTOMATIC_VERSIONING) - #error "USE_AUTOMATIC_VERSIONING is now CUSTOM_VERSION_FILE." -#elif defined(SDSLOW) - #error "SDSLOW deprecated. Set SD_SPI_SPEED to SPI_HALF_SPEED instead." -#elif defined(SDEXTRASLOW) - #error "SDEXTRASLOW deprecated. Set SD_SPI_SPEED to SPI_QUARTER_SPEED instead." -#elif defined(FILAMENT_SENSOR) - #error "FILAMENT_SENSOR is now FILAMENT_WIDTH_SENSOR." -#elif defined(ENDSTOPPULLUP_FIL_RUNOUT) - #error "ENDSTOPPULLUP_FIL_RUNOUT is now FIL_RUNOUT_PULLUP." -#elif defined(DISABLE_MAX_ENDSTOPS) || defined(DISABLE_MIN_ENDSTOPS) - #error "DISABLE_MAX_ENDSTOPS and DISABLE_MIN_ENDSTOPS deprecated. Use individual USE_*_PLUG options instead." -#elif defined(LANGUAGE_INCLUDE) - #error "LANGUAGE_INCLUDE has been replaced by LCD_LANGUAGE." -#elif defined(EXTRUDER_OFFSET_X) || defined(EXTRUDER_OFFSET_Y) - #error "EXTRUDER_OFFSET_[XY] is deprecated. Use HOTEND_OFFSET_[XY] instead." -#elif defined(PID_PARAMS_PER_EXTRUDER) - #error "PID_PARAMS_PER_EXTRUDER is deprecated. Use PID_PARAMS_PER_HOTEND instead." -#elif defined(EXTRUDER_WATTS) || defined(BED_WATTS) - #error "EXTRUDER_WATTS and BED_WATTS are deprecated and should be removed." -#elif defined(SERVO_ENDSTOP_ANGLES) - #error "SERVO_ENDSTOP_ANGLES is deprecated. Use Z_SERVO_ANGLES instead." -#elif defined(X_ENDSTOP_SERVO_NR) || defined(Y_ENDSTOP_SERVO_NR) - #error "X_ENDSTOP_SERVO_NR and Y_ENDSTOP_SERVO_NR are deprecated and should be removed." -#elif defined(Z_ENDSTOP_SERVO_NR) - #error "Z_ENDSTOP_SERVO_NR is now Z_PROBE_SERVO_NR." -#elif defined(DEFAULT_XYJERK) - #error "DEFAULT_XYJERK is deprecated. Use DEFAULT_XJERK and DEFAULT_YJERK instead." -#elif defined(XY_TRAVEL_SPEED) - #error "XY_TRAVEL_SPEED is now XY_PROBE_FEEDRATE." -#elif defined(XY_PROBE_SPEED) - #error "XY_PROBE_SPEED is now XY_PROBE_FEEDRATE." -#elif defined(Z_PROBE_SPEED_FAST) - #error "Z_PROBE_SPEED_FAST is now Z_PROBE_FEEDRATE_FAST." -#elif defined(Z_PROBE_SPEED_SLOW) - #error "Z_PROBE_SPEED_SLOW is now Z_PROBE_FEEDRATE_SLOW." -#elif defined(PROBE_SERVO_DEACTIVATION_DELAY) - #error "PROBE_SERVO_DEACTIVATION_DELAY is deprecated. Use DEACTIVATE_SERVOS_AFTER_MOVE instead." -#elif defined(SERVO_DEACTIVATION_DELAY) - #error "SERVO_DEACTIVATION_DELAY is now SERVO_DELAY." -#elif ENABLED(FILAMENTCHANGEENABLE) - #error "FILAMENTCHANGEENABLE is now ADVANCED_PAUSE_FEATURE." -#elif ENABLED(FILAMENT_CHANGE_FEATURE) - #error "FILAMENT_CHANGE_FEATURE is now ADVANCED_PAUSE_FEATURE." -#elif defined(FILAMENT_CHANGE_X_POS) || defined(FILAMENT_CHANGE_Y_POS) - #error "FILAMENT_CHANGE_[XY]_POS is now set with NOZZLE_PARK_POINT." -#elif defined(FILAMENT_CHANGE_Z_ADD) - #error "FILAMENT_CHANGE_Z_ADD is now set with NOZZLE_PARK_POINT." -#elif defined(FILAMENT_CHANGE_XY_FEEDRATE) - #error "FILAMENT_CHANGE_XY_FEEDRATE is now NOZZLE_PARK_XY_FEEDRATE." -#elif defined(FILAMENT_CHANGE_Z_FEEDRATE) - #error "FILAMENT_CHANGE_Z_FEEDRATE is now NOZZLE_PARK_Z_FEEDRATE." -#elif defined(PAUSE_PARK_X_POS) || defined(PAUSE_PARK_Y_POS) - #error "PAUSE_PARK_[XY]_POS is now set with NOZZLE_PARK_POINT." -#elif defined(PAUSE_PARK_Z_ADD) - #error "PAUSE_PARK_Z_ADD is now set with NOZZLE_PARK_POINT." -#elif defined(PAUSE_PARK_XY_FEEDRATE) - #error "PAUSE_PARK_XY_FEEDRATE is now NOZZLE_PARK_XY_FEEDRATE." -#elif defined(PAUSE_PARK_Z_FEEDRATE) - #error "PAUSE_PARK_Z_FEEDRATE is now NOZZLE_PARK_Z_FEEDRATE." -#elif defined(FILAMENT_CHANGE_RETRACT_FEEDRATE) - #error "FILAMENT_CHANGE_RETRACT_FEEDRATE is now PAUSE_PARK_RETRACT_FEEDRATE." -#elif defined(FILAMENT_CHANGE_RETRACT_LENGTH) - #error "FILAMENT_CHANGE_RETRACT_LENGTH is now PAUSE_PARK_RETRACT_LENGTH." -#elif defined(FILAMENT_CHANGE_EXTRUDE_FEEDRATE) - #error "FILAMENT_CHANGE_EXTRUDE_FEEDRATE is now ADVANCED_PAUSE_PURGE_FEEDRATE." -#elif defined(ADVANCED_PAUSE_EXTRUDE_FEEDRATE) - #error "ADVANCED_PAUSE_EXTRUDE_FEEDRATE is now ADVANCED_PAUSE_PURGE_FEEDRATE." -#elif defined(FILAMENT_CHANGE_EXTRUDE_LENGTH) - #error "FILAMENT_CHANGE_EXTRUDE_LENGTH is now ADVANCED_PAUSE_PURGE_LENGTH." -#elif defined(ADVANCED_PAUSE_EXTRUDE_LENGTH) - #error "ADVANCED_PAUSE_EXTRUDE_LENGTH is now ADVANCED_PAUSE_PURGE_LENGTH." -#elif defined(FILAMENT_CHANGE_NOZZLE_TIMEOUT) - #error "FILAMENT_CHANGE_NOZZLE_TIMEOUT is now PAUSE_PARK_NOZZLE_TIMEOUT." -#elif defined(FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS) - #error "FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS is now FILAMENT_CHANGE_ALERT_BEEPS." -#elif defined(FILAMENT_CHANGE_NO_STEPPER_TIMEOUT) - #error "FILAMENT_CHANGE_NO_STEPPER_TIMEOUT is now PAUSE_PARK_NO_STEPPER_TIMEOUT." -#elif defined(PLA_PREHEAT_HOTEND_TEMP) - #error "PLA_PREHEAT_HOTEND_TEMP is now PREHEAT_1_TEMP_HOTEND." -#elif defined(PLA_PREHEAT_HPB_TEMP) - #error "PLA_PREHEAT_HPB_TEMP is now PREHEAT_1_TEMP_BED." -#elif defined(PLA_PREHEAT_FAN_SPEED) - #error "PLA_PREHEAT_FAN_SPEED is now PREHEAT_1_FAN_SPEED." -#elif defined(ABS_PREHEAT_HOTEND_TEMP) - #error "ABS_PREHEAT_HOTEND_TEMP is now PREHEAT_2_TEMP_HOTEND." -#elif defined(ABS_PREHEAT_HPB_TEMP) - #error "ABS_PREHEAT_HPB_TEMP is now PREHEAT_2_TEMP_BED." -#elif defined(ABS_PREHEAT_FAN_SPEED) - #error "ABS_PREHEAT_FAN_SPEED is now PREHEAT_2_FAN_SPEED." -#elif defined(ENDSTOPS_ONLY_FOR_HOMING) - #error "ENDSTOPS_ONLY_FOR_HOMING is deprecated. Use (disable) ENDSTOPS_ALWAYS_ON_DEFAULT instead." -#elif defined(HOMING_FEEDRATE) - #error "HOMING_FEEDRATE is now set using the HOMING_FEEDRATE_MM_M array instead." -#elif (defined(HOMING_FEEDRATE_XY) || defined(HOMING_FEEDRATE_Z)) && !defined(HOMING_FEEDRATE_MM_M) - #error "HOMING_FEEDRATE_XY and HOMING_FEEDRATE_Z are now set using the HOMING_FEEDRATE_MM_M array instead." -#elif defined(MANUAL_HOME_POSITIONS) - #error "MANUAL_HOME_POSITIONS is deprecated. Set MANUAL_[XYZ]_HOME_POS as-needed instead." -#elif defined(PID_ADD_EXTRUSION_RATE) - #error "PID_ADD_EXTRUSION_RATE is now PID_EXTRUSION_SCALING and is DISABLED by default." -#elif defined(Z_RAISE_BEFORE_HOMING) - #error "Z_RAISE_BEFORE_HOMING is now Z_HOMING_HEIGHT." -#elif defined(MIN_Z_HEIGHT_FOR_HOMING) - #error "MIN_Z_HEIGHT_FOR_HOMING is now Z_HOMING_HEIGHT." -#elif defined(Z_RAISE_BEFORE_PROBING) || defined(Z_RAISE_AFTER_PROBING) - #error "Z_RAISE_(BEFORE|AFTER)_PROBING are deprecated. Use Z_CLEARANCE_DEPLOY_PROBE and Z_AFTER_PROBING instead." -#elif defined(Z_RAISE_PROBE_DEPLOY_STOW) || defined(Z_RAISE_BETWEEN_PROBINGS) - #error "Z_RAISE_PROBE_DEPLOY_STOW and Z_RAISE_BETWEEN_PROBINGS are now Z_CLEARANCE_DEPLOY_PROBE and Z_CLEARANCE_BETWEEN_PROBES." -#elif defined(Z_PROBE_DEPLOY_HEIGHT) || defined(Z_PROBE_TRAVEL_HEIGHT) - #error "Z_PROBE_DEPLOY_HEIGHT and Z_PROBE_TRAVEL_HEIGHT are now Z_CLEARANCE_DEPLOY_PROBE and Z_CLEARANCE_BETWEEN_PROBES." -#elif defined(MANUAL_BED_LEVELING) - #error "MANUAL_BED_LEVELING is now LCD_BED_LEVELING." -#elif defined(MESH_HOME_SEARCH_Z) - #error "MESH_HOME_SEARCH_Z is now LCD_PROBE_Z_RANGE." -#elif defined(MANUAL_PROBE_Z_RANGE) - #error "MANUAL_PROBE_Z_RANGE is now LCD_PROBE_Z_RANGE." -#elif !defined(MIN_STEPS_PER_SEGMENT) - #error "Please replace 'const int dropsegments' with '#define MIN_STEPS_PER_SEGMENT' (and increase by 1)." -#elif MIN_STEPS_PER_SEGMENT <= 0 - #error "MIN_STEPS_PER_SEGMENT must be at least 1." -#elif defined(PREVENT_DANGEROUS_EXTRUDE) - #error "PREVENT_DANGEROUS_EXTRUDE is now PREVENT_COLD_EXTRUSION." -#elif defined(SCARA) - #error "SCARA is now MORGAN_SCARA." -#elif defined(ENABLE_AUTO_BED_LEVELING) - #error "ENABLE_AUTO_BED_LEVELING is deprecated. Specify AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_3POINT." -#elif defined(AUTO_BED_LEVELING_FEATURE) - #error "AUTO_BED_LEVELING_FEATURE is deprecated. Specify AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_3POINT." -#elif defined(ABL_GRID_POINTS) - #error "ABL_GRID_POINTS is now GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y." -#elif defined(ABL_GRID_POINTS_X) || defined(ABL_GRID_POINTS_Y) - #error "ABL_GRID_POINTS_[XY] is now GRID_MAX_POINTS_[XY]." -#elif defined(ABL_GRID_MAX_POINTS_X) || defined(ABL_GRID_MAX_POINTS_Y) - #error "ABL_GRID_MAX_POINTS_[XY] is now GRID_MAX_POINTS_[XY]." -#elif defined(MESH_NUM_X_POINTS) || defined(MESH_NUM_Y_POINTS) - #error "MESH_NUM_[XY]_POINTS is now GRID_MAX_POINTS_[XY]." -#elif defined(UBL_MESH_NUM_X_POINTS) || defined(UBL_MESH_NUM_Y_POINTS) - #error "UBL_MESH_NUM_[XY]_POINTS is now GRID_MAX_POINTS_[XY]." -#elif defined(UBL_G26_MESH_VALIDATION) - #error "UBL_G26_MESH_VALIDATION is now G26_MESH_VALIDATION." -#elif defined(UBL_MESH_EDIT_ENABLED) - #error "UBL_MESH_EDIT_ENABLED is now G26_MESH_VALIDATION." -#elif defined(UBL_MESH_EDITING) - #error "UBL_MESH_EDITING is now G26_MESH_VALIDATION." -#elif defined(BLTOUCH_HEATERS_OFF) - #error "BLTOUCH_HEATERS_OFF is now PROBING_HEATERS_OFF." -#elif defined(BLTOUCH_V3) - #error "BLTOUCH_V3 is obsolete." -#elif defined(BLTOUCH_FORCE_OPEN_DRAIN_MODE) - #error "BLTOUCH_FORCE_OPEN_DRAIN_MODE is obsolete." -#elif defined(BEEPER) - #error "BEEPER is now BEEPER_PIN." -#elif defined(SDCARDDETECT) - #error "SDCARDDETECT is now SD_DETECT_PIN." -#elif defined(STAT_LED_RED) || defined(STAT_LED_BLUE) - #error "STAT_LED_RED/STAT_LED_BLUE are now STAT_LED_RED_PIN/STAT_LED_BLUE_PIN." -#elif defined(LCD_PIN_BL) - #error "LCD_PIN_BL is now LCD_BACKLIGHT_PIN." -#elif defined(LCD_PIN_RESET) - #error "LCD_PIN_RESET is now LCD_RESET_PIN." -#elif defined(EXTRUDER_0_AUTO_FAN_PIN) || defined(EXTRUDER_1_AUTO_FAN_PIN) || defined(EXTRUDER_2_AUTO_FAN_PIN) || defined(EXTRUDER_3_AUTO_FAN_PIN) - #error "EXTRUDER_[0123]_AUTO_FAN_PIN is now E[0123]_AUTO_FAN_PIN." -#elif defined(PID_FAN_SCALING) && !HAS_FAN - #error "PID_FAN_SCALING needs at least one fan enabled." -#elif defined(min_software_endstops) || defined(max_software_endstops) - #error "(min|max)_software_endstops are now (MIN|MAX)_SOFTWARE_ENDSTOPS." -#elif ENABLED(Z_PROBE_SLED) && defined(SLED_PIN) - #error "Replace SLED_PIN with SOL1_PIN (applies to both Z_PROBE_SLED and SOLENOID_PROBE)." -#elif defined(CONTROLLERFAN_PIN) - #error "CONTROLLERFAN_PIN is now CONTROLLER_FAN_PIN, enabled with USE_CONTROLLER_FAN." -#elif defined(CONTROLLERFAN_SPEED) - #error "CONTROLLERFAN_SPEED is now CONTROLLERFAN_SPEED_ACTIVE." -#elif defined(CONTROLLERFAN_SECS) - #error "CONTROLLERFAN_SECS is now CONTROLLERFAN_IDLE_TIME." -#elif defined(MIN_RETRACT) - #error "MIN_RETRACT is now MIN_AUTORETRACT and MAX_AUTORETRACT." -#elif defined(ADVANCE) - #error "ADVANCE is now LIN_ADVANCE." -#elif defined(LIN_ADVANCE_E_D_RATIO) - #error "LIN_ADVANCE (1.5) no longer uses LIN_ADVANCE_E_D_RATIO." -#elif defined(NEOPIXEL_RGBW_LED) - #error "NEOPIXEL_RGBW_LED is now NEOPIXEL_LED." -#elif ENABLED(DELTA) && defined(DELTA_PROBEABLE_RADIUS) - #error "Remove DELTA_PROBEABLE_RADIUS and use PROBING_MARGIN to inset the probe area instead." -#elif ENABLED(DELTA) && defined(DELTA_CALIBRATION_RADIUS) - #error "Remove DELTA_CALIBRATION_RADIUS and use PROBING_MARGIN to inset the probe area instead." -#elif defined(UBL_MESH_INSET) - #error "UBL_MESH_INSET is now just MESH_INSET." -#elif defined(UBL_MESH_MIN_X) || defined(UBL_MESH_MIN_Y) || defined(UBL_MESH_MAX_X) || defined(UBL_MESH_MAX_Y) - #error "UBL_MESH_(MIN|MAX)_[XY] is now just MESH_(MIN|MAX)_[XY]." -#elif defined(ABL_PROBE_PT_1_X) || defined(ABL_PROBE_PT_1_Y) || defined(ABL_PROBE_PT_2_X) || defined(ABL_PROBE_PT_2_Y) || defined(ABL_PROBE_PT_3_X) || defined(ABL_PROBE_PT_3_Y) - #error "ABL_PROBE_PT_[123]_[XY] is no longer required. Please remove it." -#elif defined(UBL_PROBE_PT_1_X) || defined(UBL_PROBE_PT_1_Y) || defined(UBL_PROBE_PT_2_X) || defined(UBL_PROBE_PT_2_Y) || defined(UBL_PROBE_PT_3_X) || defined(UBL_PROBE_PT_3_Y) - #error "UBL_PROBE_PT_[123]_[XY] is no longer required. Please remove it." -#elif defined(MIN_PROBE_EDGE) - #error "MIN_PROBE_EDGE is now called PROBING_MARGIN." -#elif defined(MIN_PROBE_EDGE_LEFT) - #error "MIN_PROBE_EDGE_LEFT is now called PROBING_MARGIN_LEFT." -#elif defined(MIN_PROBE_EDGE_RIGHT) - #error "MIN_PROBE_EDGE_RIGHT is now called PROBING_MARGIN_RIGHT." -#elif defined(MIN_PROBE_EDGE_FRONT) - #error "MIN_PROBE_EDGE_FRONT is now called PROBING_MARGIN_FRONT." -#elif defined(MIN_PROBE_EDGE_BACK) - #error "MIN_PROBE_EDGE_BACK is now called PROBING_MARGIN_BACK." -#elif defined(LEFT_PROBE_BED_POSITION) - #error "LEFT_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_LEFT instead." -#elif defined(RIGHT_PROBE_BED_POSITION) - #error "RIGHT_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_RIGHT instead." -#elif defined(FRONT_PROBE_BED_POSITION) - #error "FRONT_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_FRONT instead." -#elif defined(BACK_PROBE_BED_POSITION) - #error "BACK_PROBE_BED_POSITION is obsolete. Set a margin with PROBING_MARGIN or PROBING_MARGIN_BACK instead." -#elif defined(ENABLE_MESH_EDIT_GFX_OVERLAY) - #error "ENABLE_MESH_EDIT_GFX_OVERLAY is now MESH_EDIT_GFX_OVERLAY." -#elif defined(BABYSTEP_ZPROBE_GFX_REVERSE) - #error "BABYSTEP_ZPROBE_GFX_REVERSE is now set by OVERLAY_GFX_REVERSE." -#elif defined(UBL_GRANULAR_SEGMENTATION_FOR_CARTESIAN) - #error "UBL_GRANULAR_SEGMENTATION_FOR_CARTESIAN is now SEGMENT_LEVELED_MOVES." -#elif HAS_PID_HEATING && (defined(K1) || !defined(PID_K1)) - #error "K1 is now PID_K1." -#elif defined(PROBE_DOUBLE_TOUCH) - #error "PROBE_DOUBLE_TOUCH is now MULTIPLE_PROBING." -#elif defined(ANET_KEYPAD_LCD) - #error "ANET_KEYPAD_LCD is now ZONESTAR_LCD." -#elif defined(LCD_I2C_SAINSMART_YWROBOT) - #error "LCD_I2C_SAINSMART_YWROBOT is now LCD_SAINSMART_I2C_(1602|2004)." -#elif defined(MEASURED_LOWER_LIMIT) || defined(MEASURED_UPPER_LIMIT) - #error "MEASURED_(UPPER|LOWER)_LIMIT is now FILWIDTH_ERROR_MARGIN." -#elif defined(HAVE_TMCDRIVER) - #error "HAVE_TMCDRIVER is now [AXIS]_DRIVER_TYPE TMC26X." -#elif defined(STEALTHCHOP) - #error "STEALTHCHOP is now STEALTHCHOP_(XY|Z|E)." -#elif defined(HAVE_TMC26X) - #error "HAVE_TMC26X is now [AXIS]_DRIVER_TYPE TMC26X." -#elif defined(HAVE_TMC2130) - #error "HAVE_TMC2130 is now [AXIS]_DRIVER_TYPE TMC2130." -#elif defined(HAVE_TMC2208) - #error "HAVE_TMC2208 is now [AXIS]_DRIVER_TYPE TMC2208." -#elif defined(HAVE_L6470DRIVER) - #error "HAVE_L6470DRIVER is obsolete. L64xx stepper drivers are no longer supported in Marlin." -#elif defined(X_IS_TMC) || defined(X2_IS_TMC) || defined(Y_IS_TMC) || defined(Y2_IS_TMC) || defined(Z_IS_TMC) || defined(Z2_IS_TMC) || defined(Z3_IS_TMC) \ - || defined(E0_IS_TMC) || defined(E1_IS_TMC) || defined(E2_IS_TMC) || defined(E3_IS_TMC) || defined(E4_IS_TMC) || defined(E5_IS_TMC) || defined(E6_IS_TMC) || defined(E7_IS_TMC) - #error "[AXIS]_IS_TMC is now [AXIS]_DRIVER_TYPE TMC26X." -#elif defined(X_IS_TMC26X) || defined(X2_IS_TMC26X) || defined(Y_IS_TMC26X) || defined(Y2_IS_TMC26X) || defined(Z_IS_TMC26X) || defined(Z2_IS_TMC26X) || defined(Z3_IS_TMC26X) \ - || defined(E0_IS_TMC26X) || defined(E1_IS_TMC26X) || defined(E2_IS_TMC26X) || defined(E3_IS_TMC26X) || defined(E4_IS_TMC26X) || defined(E5_IS_TMC26X) || defined(E6_IS_TMC26X) || defined(E7_IS_TMC26X) - #error "[AXIS]_IS_TMC26X is now [AXIS]_DRIVER_TYPE TMC26X." -#elif defined(X_IS_TMC2130) || defined(X2_IS_TMC2130) || defined(Y_IS_TMC2130) || defined(Y2_IS_TMC2130) || defined(Z_IS_TMC2130) || defined(Z2_IS_TMC2130) || defined(Z3_IS_TMC2130) \ - || defined(E0_IS_TMC2130) || defined(E1_IS_TMC2130) || defined(E2_IS_TMC2130) || defined(E3_IS_TMC2130) || defined(E4_IS_TMC2130) || defined(E5_IS_TMC2130) || defined(E6_IS_TMC2130) || defined(E7_IS_TMC2130) - #error "[AXIS]_IS_TMC2130 is now [AXIS]_DRIVER_TYPE TMC2130." -#elif defined(X_IS_TMC2208) || defined(X2_IS_TMC2208) || defined(Y_IS_TMC2208) || defined(Y2_IS_TMC2208) || defined(Z_IS_TMC2208) || defined(Z2_IS_TMC2208) || defined(Z3_IS_TMC2208) \ - || defined(E0_IS_TMC2208) || defined(E1_IS_TMC2208) || defined(E2_IS_TMC2208) || defined(E3_IS_TMC2208) || defined(E4_IS_TMC2208) || defined(E5_IS_TMC2208) || defined(E6_IS_TMC2208) || defined(E7_IS_TMC2208) - #error "[AXIS]_IS_TMC2208 is now [AXIS]_DRIVER_TYPE TMC2208." -#elif defined(AUTOMATIC_CURRENT_CONTROL) - #error "AUTOMATIC_CURRENT_CONTROL is now MONITOR_DRIVER_STATUS." -#elif defined(FILAMENT_CHANGE_LOAD_LENGTH) - #error "FILAMENT_CHANGE_LOAD_LENGTH is now FILAMENT_CHANGE_FAST_LOAD_LENGTH." -#elif defined(LEVEL_CORNERS_INSET) - #error "LEVEL_CORNERS_INSET is now BED_TRAMMING_INSET_LFRB." -#elif defined(BEZIER_JERK_CONTROL) - #error "BEZIER_JERK_CONTROL is now S_CURVE_ACCELERATION." -#elif HAS_JUNCTION_DEVIATION && defined(JUNCTION_DEVIATION_FACTOR) - #error "JUNCTION_DEVIATION_FACTOR is now JUNCTION_DEVIATION_MM." -#elif defined(JUNCTION_ACCELERATION_FACTOR) - #error "JUNCTION_ACCELERATION_FACTOR is obsolete. Delete it from Configuration_adv.h." -#elif defined(JUNCTION_ACCELERATION) - #error "JUNCTION_ACCELERATION is obsolete. Delete it from Configuration_adv.h." -#elif defined(MAX7219_DEBUG_STEPPER_HEAD) - #error "MAX7219_DEBUG_STEPPER_HEAD is now MAX7219_DEBUG_PLANNER_HEAD." -#elif defined(MAX7219_DEBUG_STEPPER_TAIL) - #error "MAX7219_DEBUG_STEPPER_TAIL is now MAX7219_DEBUG_PLANNER_TAIL." -#elif defined(MAX7219_DEBUG_STEPPER_QUEUE) - #error "MAX7219_DEBUG_STEPPER_QUEUE is now MAX7219_DEBUG_PLANNER_QUEUE." -#elif defined(ENDSTOP_NOISE_FILTER) - #error "ENDSTOP_NOISE_FILTER is now ENDSTOP_NOISE_THRESHOLD [2-7]." -#elif defined(RETRACT_ZLIFT) - #error "RETRACT_ZLIFT is now RETRACT_ZRAISE." -#elif defined(TOOLCHANGE_FS_INIT_BEFORE_SWAP) - #error "TOOLCHANGE_FS_INIT_BEFORE_SWAP is now TOOLCHANGE_FS_SLOW_FIRST_PRIME." -#elif defined(TOOLCHANGE_PARK_ZLIFT) || defined(TOOLCHANGE_UNPARK_ZLIFT) - #error "TOOLCHANGE_PARK_ZLIFT and TOOLCHANGE_UNPARK_ZLIFT are now TOOLCHANGE_ZRAISE." -#elif defined(SINGLENOZZLE_TOOLCHANGE_ZRAISE) - #error "SINGLENOZZLE_TOOLCHANGE_ZRAISE is now TOOLCHANGE_ZRAISE." -#elif defined(SINGLENOZZLE_SWAP_LENGTH) - #error "SINGLENOZZLE_SWAP_LENGTH is now TOOLCHANGE_FIL_SWAP_LENGTH." -#elif defined(SINGLENOZZLE_SWAP_RETRACT_SPEED) - #error "SINGLENOZZLE_SWAP_RETRACT_SPEED is now TOOLCHANGE_FIL_SWAP_RETRACT_SPEED." -#elif defined(SINGLENOZZLE_SWAP_PRIME_SPEED) - #error "SINGLENOZZLE_SWAP_PRIME_SPEED is now TOOLCHANGE_FIL_SWAP_PRIME_SPEED." -#elif defined(SINGLENOZZLE_SWAP_PARK) - #error "SINGLENOZZLE_SWAP_PARK is now TOOLCHANGE_PARK." -#elif defined(SINGLENOZZLE_TOOLCHANGE_XY) - #error "SINGLENOZZLE_TOOLCHANGE_XY is now TOOLCHANGE_PARK_XY." -#elif defined(SINGLENOZZLE_PARK_XY_FEEDRATE) - #error "SINGLENOZZLE_PARK_XY_FEEDRATE is now TOOLCHANGE_PARK_XY_FEEDRATE." -#elif defined(PARKING_EXTRUDER_SECURITY_RAISE) - #error "PARKING_EXTRUDER_SECURITY_RAISE is now TOOLCHANGE_ZRAISE." -#elif defined(SWITCHING_TOOLHEAD_SECURITY_RAISE) - #error "SWITCHING_TOOLHEAD_SECURITY_RAISE is now TOOLCHANGE_ZRAISE." -#elif defined(G0_FEEDRATE) && G0_FEEDRATE == 0 - #error "G0_FEEDRATE is now used to set the G0 feedrate." -#elif defined(MBL_Z_STEP) - #error "MBL_Z_STEP is now MESH_EDIT_Z_STEP." -#elif defined(CHDK) - #error "CHDK is now CHDK_PIN." -#elif ANY_PIN( \ - MAX6675_SS, MAX6675_SS2, MAX6675_SS3, MAX6675_CS, MAX6675_CS2, MAX6675_CS3,\ - MAX31855_SS, MAX31855_SS2, MAX31855_SS3, MAX31855_CS, MAX31855_CS2, MAX31855_CS3, \ - MAX31865_SS, MAX31865_SS2, MAX31865_SS3, MAX31865_CS, MAX31865_CS2, MAX31865_CS3) - #warning "MAX*_SS_PIN, MAX*_SS2_PIN, MAX*_SS3_PIN, MAX*_CS_PIN, MAX*_CS2_PIN, and MAX*_CS3_PIN, are deprecated and will be removed in a future version. Please use TEMP_0_CS_PIN/TEMP_1_CS_PIN/TEMP_2_CS_PIN instead." -#elif ANY_PIN(MAX6675_SCK, MAX31855_SCK, MAX31865_SCK) - #warning "MAX*_SCK_PIN is deprecated and will be removed in a future version. Please use TEMP_0_SCK_PIN/TEMP_1_SCK_PIN/TEMP_2_SCK_PIN instead." -#elif ANY_PIN(MAX6675_MISO, MAX6675_DO, MAX31855_MISO, MAX31855_DO, MAX31865_MISO, MAX31865_DO) - #warning "MAX*_MISO_PIN and MAX*_DO_PIN are deprecated and will be removed in a future version. Please use TEMP_0_MISO_PIN/TEMP_1_MISO_PIN/TEMP_2_MISO_PIN instead." -#elif PIN_EXISTS(MAX31865_MOSI) - #warning "MAX31865_MOSI_PIN is deprecated and will be removed in a future version. Please use TEMP_0_MOSI_PIN/TEMP_1_MOSI_PIN/TEMP_2_MOSI_PIN instead." -#elif ANY_PIN(THERMO_CS1_PIN, THERMO_CS2_PIN, THERMO_CS3_PIN, THERMO_DO_PIN, THERMO_SCK_PIN) - #error "THERMO_*_PIN is now TEMP_n_CS_PIN, TEMP_n_SCK_PIN, TEMP_n_MOSI_PIN, TEMP_n_MISO_PIN." -#elif defined(MAX31865_SENSOR_OHMS) - #error "MAX31865_SENSOR_OHMS is now MAX31865_SENSOR_OHMS_0." -#elif defined(MAX31865_CALIBRATION_OHMS) - #error "MAX31865_CALIBRATION_OHMS is now MAX31865_CALIBRATION_OHMS_0." -#elif defined(SPINDLE_LASER_ENABLE) - #error "SPINDLE_LASER_ENABLE is now SPINDLE_FEATURE or LASER_FEATURE." -#elif defined(SPINDLE_LASER_ENABLE_PIN) - #error "SPINDLE_LASER_ENABLE_PIN is now SPINDLE_LASER_ENA_PIN." -#elif defined(SPINDLE_DIR_CHANGE) - #error "SPINDLE_DIR_CHANGE is now SPINDLE_CHANGE_DIR." -#elif defined(SPINDLE_STOP_ON_DIR_CHANGE) - #error "SPINDLE_STOP_ON_DIR_CHANGE is now SPINDLE_CHANGE_DIR_STOP." -#elif defined(SPINDLE_LASER_ACTIVE_HIGH) - #error "SPINDLE_LASER_ACTIVE_HIGH is now SPINDLE_LASER_ACTIVE_STATE." -#elif defined(SPINDLE_LASER_ENABLE_INVERT) - #error "SPINDLE_LASER_ENABLE_INVERT is now SPINDLE_LASER_ACTIVE_STATE." -#elif defined(LASER_POWER_INLINE) - #error "LASER_POWER_INLINE is not required, inline mode is enabled with 'M3 I' and disabled with 'M5 I'." -#elif defined(LASER_POWER_INLINE_TRAPEZOID) - #error "LASER_POWER_INLINE_TRAPEZOID is now LASER_POWER_TRAP." -#elif defined(LASER_POWER_INLINE_TRAPEZOID_CONT) - #error "LASER_POWER_INLINE_TRAPEZOID_CONT is replaced with LASER_POWER_TRAP." -#elif defined(LASER_POWER_INLINE_TRAPEZOID_PER) - #error "LASER_POWER_INLINE_TRAPEZOID_CONT_PER replaced with LASER_POWER_TRAP." -#elif defined(LASER_POWER_INLINE_CONTINUOUS) - #error "LASER_POWER_INLINE_CONTINUOUS is not required, inline mode is enabled with 'M3 I' and disabled with 'M5 I'." -#elif defined(CUTTER_POWER_DISPLAY) - #error "CUTTER_POWER_DISPLAY is now CUTTER_POWER_UNIT." -#elif defined(CHAMBER_HEATER_PIN) - #error "CHAMBER_HEATER_PIN is now HEATER_CHAMBER_PIN." -#elif defined(TMC_Z_CALIBRATION) - #error "TMC_Z_CALIBRATION has been deprecated in favor of MECHANICAL_GANTRY_CALIBRATION." -#elif defined(Z_MIN_PROBE_ENDSTOP) - #error "Z_MIN_PROBE_ENDSTOP is no longer required. Please remove it." -#elif defined(DUAL_NOZZLE_DUPLICATION_MODE) - #error "DUAL_NOZZLE_DUPLICATION_MODE is now MULTI_NOZZLE_DUPLICATION." -#elif defined(MENU_ITEM_CASE_LIGHT) - #error "MENU_ITEM_CASE_LIGHT is now CASE_LIGHT_MENU." -#elif defined(CASE_LIGHT_NEOPIXEL_COLOR) - #error "CASE_LIGHT_NEOPIXEL_COLOR is now CASE_LIGHT_DEFAULT_COLOR." -#elif defined(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) - #error "ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED is now SD_ABORT_ON_ENDSTOP_HIT." -#elif defined(LPC_SD_LCD) || defined(LPC_SD_ONBOARD) || defined(LPC_SD_CUSTOM_CABLE) - #error "LPC_SD_(LCD|ONBOARD|CUSTOM_CABLE) are now SDCARD_CONNECTION." -#elif defined(USB_SD_DISABLED) - #error "USB_SD_DISABLED is now NO_SD_HOST_DRIVE." -#elif defined(USB_SD_ONBOARD) - #error "USB_SD_ONBOARD is obsolete. Disable NO_SD_HOST_DRIVE instead." -#elif defined(PSU_ACTIVE_HIGH) - #error "PSU_ACTIVE_HIGH is now PSU_ACTIVE_STATE." -#elif POWER_SUPPLY == 1 - #error "Replace POWER_SUPPLY 1 by enabling PSU_CONTROL and setting PSU_ACTIVE_STATE to 'LOW'." -#elif POWER_SUPPLY == 2 - #error "Replace POWER_SUPPLY 2 by enabling PSU_CONTROL and setting PSU_ACTIVE_STATE to 'HIGH'." -#elif defined(POWER_SUPPLY) - #error "POWER_SUPPLY is now obsolete. Please remove it." -#elif defined(MKS_ROBIN_TFT) - #error "MKS_ROBIN_TFT is now FSMC_GRAPHICAL_TFT." -#elif defined(SDPOWER) - #error "SDPOWER is now SDPOWER_PIN." -#elif defined(STRING_SPLASH_LINE1) || defined(STRING_SPLASH_LINE2) - #error "STRING_SPLASH_LINE[12] are now obsolete. Please remove them." -#elif defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_X) || defined(Z_PROBE_ALLEN_KEY_STOW_1_X) - #error "Z_PROBE_ALLEN_KEY_(DEPLOY|STOW) coordinates are now a single setting." -#elif defined(X_PROBE_OFFSET_FROM_EXTRUDER) || defined(Y_PROBE_OFFSET_FROM_EXTRUDER) || defined(Z_PROBE_OFFSET_FROM_EXTRUDER) - #error "[XYZ]_PROBE_OFFSET_FROM_EXTRUDER is now NOZZLE_TO_PROBE_OFFSET." -#elif defined(MIN_PROBE_X) || defined(MIN_PROBE_Y) || defined(MAX_PROBE_X) || defined(MAX_PROBE_Y) - #error "(MIN|MAX)_PROBE_[XY] are now calculated at runtime. Please remove them." -#elif defined(Z_STEPPER_ALIGN_X) || defined(Z_STEPPER_ALIGN_X) - #error "Z_STEPPER_ALIGN_X and Z_STEPPER_ALIGN_Y are now combined as Z_STEPPER_ALIGN_XY." -#elif defined(JUNCTION_DEVIATION) - #error "JUNCTION_DEVIATION is no longer required. (See CLASSIC_JERK). Please remove it." -#elif defined(BABYSTEP_MULTIPLICATOR) - #error "BABYSTEP_MULTIPLICATOR is now BABYSTEP_MULTIPLICATOR_[XY|Z]." -#elif defined(LULZBOT_TOUCH_UI) - #error "LULZBOT_TOUCH_UI is now TOUCH_UI_FTDI_EVE." -#elif defined(PS_DEFAULT_OFF) - #error "PS_DEFAULT_OFF is now PSU_DEFAULT_OFF." -#elif defined(FILAMENT_UNLOAD_RETRACT_LENGTH) - #error "FILAMENT_UNLOAD_RETRACT_LENGTH is now FILAMENT_UNLOAD_PURGE_RETRACT." -#elif defined(FILAMENT_UNLOAD_DELAY) - #error "FILAMENT_UNLOAD_DELAY is now FILAMENT_UNLOAD_PURGE_DELAY." -#elif defined(HOME_USING_SPREADCYCLE) - #error "HOME_USING_SPREADCYCLE is now obsolete. Please remove it." -#elif defined(DGUS_LCD) - #error "DGUS_LCD is now DGUS_LCD_UI_(ORIGIN|FYSETC|HIPRECY)." -#elif defined(DGUS_SERIAL_PORT) - #error "DGUS_SERIAL_PORT is now LCD_SERIAL_PORT." -#elif defined(DGUS_BAUDRATE) - #error "DGUS_BAUDRATE is now LCD_BAUDRATE." -#elif defined(DGUS_STATS_RX_BUFFER_OVERRUNS) - #error "DGUS_STATS_RX_BUFFER_OVERRUNS is now STATS_RX_BUFFER_OVERRUNS." -#elif defined(ANYCUBIC_LCD_SERIAL_PORT) - #error "ANYCUBIC_LCD_SERIAL_PORT is now LCD_SERIAL_PORT." -#elif defined(INTERNAL_SERIAL_PORT) - #error "INTERNAL_SERIAL_PORT is now MMU2_SERIAL_PORT." -#elif defined(X_DUAL_ENDSTOPS_ADJUSTMENT) || defined(Y_DUAL_ENDSTOPS_ADJUSTMENT) || defined(Z_DUAL_ENDSTOPS_ADJUSTMENT) - #error "[XYZ]_DUAL_ENDSTOPS_ADJUSTMENT is now [XYZ]2_ENDSTOP_ADJUSTMENT." -#elif defined(Z_TRIPLE_ENDSTOPS_ADJUSTMENT2) || defined(Z_TRIPLE_ENDSTOPS_ADJUSTMENT3) - #error "Z_TRIPLE_ENDSTOPS_ADJUSTMENT[23] is now Z[23]_ENDSTOP_ADJUSTMENT." -#elif defined(Z_QUAD_ENDSTOPS_ADJUSTMENT2) || defined(Z_QUAD_ENDSTOPS_ADJUSTMENT3) || defined(Z_QUAD_ENDSTOPS_ADJUSTMENT4) - #error "Z_QUAD_ENDSTOPS_ADJUSTMENT[234] is now Z[234]_ENDSTOP_ADJUSTMENT." -#elif defined(Z_DUAL_STEPPER_DRIVERS) - #error "Z_DUAL_STEPPER_DRIVERS is no longer needed and should be removed." -#elif defined(Z_TRIPLE_STEPPER_DRIVERS) - #error "Z_TRIPLE_STEPPER_DRIVERS is no longer needed and should be removed." -#elif defined(Z_QUAD_STEPPER_DRIVERS) - #error "Z_QUAD_STEPPER_DRIVERS is no longer needed and should be removed." -#elif defined(Z_DUAL_ENDSTOPS) || defined(Z_TRIPLE_ENDSTOPS) || defined(Z_QUAD_ENDSTOPS) - #error "Z_(DUAL|TRIPLE|QUAD)_ENDSTOPS is now Z_MULTI_ENDSTOPS." -#elif defined(DUGS_UI_MOVE_DIS_OPTION) - #error "DUGS_UI_MOVE_DIS_OPTION is spelled DGUS_UI_MOVE_DIS_OPTION." -#elif defined(ORIG_E0_AUTO_FAN_PIN) || defined(ORIG_E1_AUTO_FAN_PIN) || defined(ORIG_E2_AUTO_FAN_PIN) || defined(ORIG_E3_AUTO_FAN_PIN) || defined(ORIG_E4_AUTO_FAN_PIN) || defined(ORIG_E5_AUTO_FAN_PIN) || defined(ORIG_E6_AUTO_FAN_PIN) || defined(ORIG_E7_AUTO_FAN_PIN) - #error "ORIG_Ex_AUTO_FAN_PIN is now just Ex_AUTO_FAN_PIN." -#elif defined(ORIG_CHAMBER_AUTO_FAN_PIN) - #error "ORIG_CHAMBER_AUTO_FAN_PIN is now just CHAMBER_AUTO_FAN_PIN." -#elif defined(HOMING_BACKOFF_MM) - #error "HOMING_BACKOFF_MM is now HOMING_BACKOFF_POST_MM." -#elif defined(X_HOME_BUMP_MM) || defined(Y_HOME_BUMP_MM) || defined(Z_HOME_BUMP_MM) - #error "[XYZ]_HOME_BUMP_MM is now HOMING_BUMP_MM." -#elif defined(DIGIPOT_I2C) - #error "DIGIPOT_I2C is now DIGIPOT_MCP4451 (or DIGIPOT_MCP4018)." -#elif defined(TOUCH_BUTTONS) - #error "TOUCH_BUTTONS is now TOUCH_SCREEN." -#elif defined(LCD_FULL_PIXEL_HEIGHT) || defined(LCD_FULL_PIXEL_WIDTH) - #error "LCD_FULL_PIXEL_(WIDTH|HEIGHT) is deprecated and should be removed." -#elif defined(FSMC_UPSCALE) - #error "FSMC_UPSCALE is now GRAPHICAL_TFT_UPSCALE." -#elif defined(ANYCUBIC_TFT_MODEL) - #error "ANYCUBIC_TFT_MODEL is now ANYCUBIC_LCD_I3MEGA." -#elif defined(EVENT_GCODE_SD_STOP) - #error "EVENT_GCODE_SD_STOP is now EVENT_GCODE_SD_ABORT." -#elif defined(GRAPHICAL_TFT_ROTATE_180) - #error "GRAPHICAL_TFT_ROTATE_180 is now TFT_ROTATION set to TFT_ROTATE_180." -#elif defined(PROBE_OFFSET_START) - #error "PROBE_OFFSET_START is now PROBE_OFFSET_WIZARD_START_Z." -#elif defined(POWER_LOSS_PULL) - #error "POWER_LOSS_PULL is now specifically POWER_LOSS_PULL(UP|DOWN)." -#elif defined(SHORT_MANUAL_Z_MOVE) - #error "SHORT_MANUAL_Z_MOVE is now FINE_MANUAL_MOVE, applying to Z on most printers." -#elif defined(FIL_RUNOUT_INVERTING) - #if FIL_RUNOUT_INVERTING - #error "FIL_RUNOUT_INVERTING true is now FIL_RUNOUT_STATE HIGH." - #else - #error "FIL_RUNOUT_INVERTING false is now FIL_RUNOUT_STATE LOW." - #endif -#elif defined(ASSISTED_TRAMMING_MENU_ITEM) - #error "ASSISTED_TRAMMING_MENU_ITEM is deprecated and should be removed." -#elif defined(UNKNOWN_Z_NO_RAISE) - #error "UNKNOWN_Z_NO_RAISE is replaced by setting Z_IDLE_HEIGHT to Z_MAX_POS." -#elif defined(Z_AFTER_DEACTIVATE) - #error "Z_AFTER_DEACTIVATE is replaced by Z_IDLE_HEIGHT." -#elif defined(MEATPACK) - #error "MEATPACK is now enabled with MEATPACK_ON_SERIAL_PORT_1, MEATPACK_ON_SERIAL_PORT_2, etc." -#elif defined(CUSTOM_USER_MENUS) - #error "CUSTOM_USER_MENUS has been replaced by CUSTOM_MENU_MAIN and CUSTOM_MENU_CONFIG." -#elif defined(MKS_LCD12864) - #error "MKS_LCD12864 is now MKS_LCD12864A or MKS_LCD12864B." -#elif defined(DOGM_SD_PERCENT) - #error "DOGM_SD_PERCENT is now SHOW_PROGRESS_PERCENT." -#elif defined(NEOPIXEL_BKGD_LED_INDEX) - #error "NEOPIXEL_BKGD_LED_INDEX is now NEOPIXEL_BKGD_INDEX_FIRST." -#elif defined(TEMP_SENSOR_1_AS_REDUNDANT) - #error "TEMP_SENSOR_1_AS_REDUNDANT is now TEMP_SENSOR_REDUNDANT, with associated TEMP_SENSOR_REDUNDANT_* config." -#elif defined(MAX_REDUNDANT_TEMP_SENSOR_DIFF) - #error "MAX_REDUNDANT_TEMP_SENSOR_DIFF is now TEMP_SENSOR_REDUNDANT_MAX_DIFF" -#elif defined(LCD_ALEPHOBJECTS_CLCD_UI) - #error "LCD_ALEPHOBJECTS_CLCD_UI is now LCD_LULZBOT_CLCD_UI." -#elif defined(MIN_ARC_SEGMENTS) - #error "MIN_ARC_SEGMENTS is now MIN_CIRCLE_SEGMENTS." -#elif defined(ARC_SEGMENTS_PER_R) - #error "ARC_SUPPORT no longer uses ARC_SEGMENTS_PER_R." -#elif ENABLED(ARC_SUPPORT) && (!defined(MIN_ARC_SEGMENT_MM) || !defined(MAX_ARC_SEGMENT_MM)) - #error "ARC_SUPPORT now requires MIN_ARC_SEGMENT_MM and MAX_ARC_SEGMENT_MM." -#elif defined(LASER_POWER_INLINE) - #error "LASER_POWER_INLINE is obsolete." -#elif defined(SPINDLE_LASER_PWM) - #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." -#elif defined(LCD_SCREEN_ROT_90) - #error "LCD_SCREEN_ROT_90 is now LCD_SCREEN_ROTATE with a value of 90." -#elif defined(LCD_SCREEN_ROT_180) - #error "LCD_SCREEN_ROT_180 is now LCD_SCREEN_ROTATE with a value of 180." -#elif defined(LCD_SCREEN_ROT_270) - #error "LCD_SCREEN_ROT_270 is now LCD_SCREEN_ROTATE with a value of 270." -#elif defined(DEFAULT_LCD_BRIGHTNESS) - #error "DEFAULT_LCD_BRIGHTNESS is now LCD_BRIGHTNESS_DEFAULT." -#elif defined(NOZZLE_PARK_X_ONLY) - #error "NOZZLE_PARK_X_ONLY is now NOZZLE_PARK_MOVE 1." -#elif defined(NOZZLE_PARK_Y_ONLY) - #error "NOZZLE_PARK_Y_ONLY is now NOZZLE_PARK_MOVE 2." -#elif defined(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - #error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS is now just Z_STEPPER_ALIGN_STEPPER_XY." -#elif defined(DWIN_CREALITY_LCD_ENHANCED) - #error "DWIN_CREALITY_LCD_ENHANCED is now DWIN_LCD_PROUI." -#elif defined(LINEAR_AXES) - #error "LINEAR_AXES is now NUM_AXES (to account for rotational axes)." -#elif defined(X_DUAL_STEPPER_DRIVERS) - #error "X_DUAL_STEPPER_DRIVERS is no longer needed and should be removed." -#elif defined(Y_DUAL_STEPPER_DRIVERS) - #error "Y_DUAL_STEPPER_DRIVERS is no longer needed and should be removed." -#elif defined(NUM_Z_STEPPER_DRIVERS) - #error "NUM_Z_STEPPER_DRIVERS is no longer needed and should be removed." -#elif defined(LEVEL_BED_CORNERS) - #error "LEVEL_BED_CORNERS is now LCD_BED_TRAMMING." -#elif defined(LEVEL_CORNERS_INSET_LFRB) || defined(LEVEL_CORNERS_HEIGHT) || defined(LEVEL_CORNERS_Z_HOP) || defined(LEVEL_CORNERS_USE_PROBE) || defined(LEVEL_CORNERS_PROBE_TOLERANCE) || defined(LEVEL_CORNERS_VERIFY_RAISED) || defined(LEVEL_CORNERS_AUDIO_FEEDBACK) - #error "LEVEL_CORNERS_* settings have been renamed BED_TRAMMING_*." -#elif defined(LEVEL_CENTER_TOO) - #error "LEVEL_CENTER_TOO is now BED_TRAMMING_INCLUDE_CENTER." -#elif defined(TOUCH_IDLE_SLEEP) - #error "TOUCH_IDLE_SLEEP (seconds) is now TOUCH_IDLE_SLEEP_MINS (minutes)." -#elif defined(LCD_BACKLIGHT_TIMEOUT) - #error "LCD_BACKLIGHT_TIMEOUT (seconds) is now LCD_BACKLIGHT_TIMEOUT_MINS (minutes)." -#elif defined(LCD_SET_PROGRESS_MANUALLY) - #error "LCD_SET_PROGRESS_MANUALLY is now SET_PROGRESS_MANUALLY." -#elif defined(USE_M73_REMAINING_TIME) - #error "USE_M73_REMAINING_TIME is now SET_REMAINING_TIME." -#elif defined(SHOW_SD_PERCENT) - #error "SHOW_SD_PERCENT is now SHOW_PROGRESS_PERCENT." -#elif defined(LIN_ADVANCE_K) - #error "LIN_ADVANCE_K is now ADVANCE_K." -#elif defined(EXTRA_LIN_ADVANCE_K) - #error "EXTRA_LIN_ADVANCE_K is now ADVANCE_K_EXTRA." -#elif defined(POLAR_SEGMENTS_PER_SECOND) || defined(DELTA_SEGMENTS_PER_SECOND) || defined(SCARA_SEGMENTS_PER_SECOND) || defined(TPARA_SEGMENTS_PER_SECOND) - #error "(POLAR|DELTA|SCARA|TPARA)_SEGMENTS_PER_SECOND is now DEFAULT_SEGMENTS_PER_SECOND." -#endif - -// L64xx stepper drivers have been removed -#define _L6470 0x6470 -#define _L6474 0x6474 -#define _L6480 0x6480 -#define _POWERSTEP01 0xF00D -#if HAS_DRIVER(L6470) - #error "L6470 stepper drivers are no longer supported in Marlin." -#elif HAS_DRIVER(L6474) - #error "L6474 stepper drivers are no longer supported in Marlin." -#elif HAS_DRIVER(L6480) - #error "L6480 stepper drivers are no longer supported in Marlin." -#elif HAS_DRIVER(POWERSTEP01) - #error "POWERSTEP01 stepper drivers are no longer supported in Marlin." -#endif -#undef _L6470 -#undef _L6474 -#undef _L6480 -#undef _POWERSTEP01 +#endif + +/** + * Required Version defines + */ +#ifndef SHORT_BUILD_VERSION + #error "SHORT_BUILD_VERSION must be specified." +#elif !defined(DETAILED_BUILD_VERSION) + #error "BUILD_VERSION must be specified." +#elif !defined(STRING_DISTRIBUTION_DATE) + #error "STRING_DISTRIBUTION_DATE must be specified." +#elif !defined(PROTOCOL_VERSION) + #error "PROTOCOL_VERSION must be specified." +#elif !defined(MACHINE_NAME) + #error "MACHINE_NAME must be specified." +#elif !defined(SOURCE_CODE_URL) + #error "SOURCE_CODE_URL must be specified." +#elif !defined(DEFAULT_MACHINE_UUID) + #error "DEFAULT_MACHINE_UUID must be specified." +#elif !defined(WEBSITE_URL) + #error "WEBSITE_URL must be specified." +#endif // Check AXIS_RELATIVE_MODES constexpr float arm[] = AXIS_RELATIVE_MODES; @@ -694,6 +129,13 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #undef _ISMAX_1 #undef _ISSNS_1 +/** + * RADDS is forbidden for non-DUE boards, for now. + */ +#if ENABLED(RADDS_DISPLAY) && !defined(__SAM3X8E__) + #error "RADDS_DISPLAY is currently only incompatible with DUE boards." +#endif + /** * Probe temp compensation requirements */ @@ -834,11 +276,17 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #endif /** - * Validate that the bed size fits + * Validate bed size */ -static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS) are too narrow to contain X_BED_SIZE."); -#if HAS_Y_AXIS - static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS) are too narrow to contain Y_BED_SIZE."); +#if !defined(X_BED_SIZE) || !defined(Y_BED_SIZE) + #error "X_BED_SIZE and Y_BED_SIZE are required!" +#else + #if HAS_X_AXIS + static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS) are too narrow to contain X_BED_SIZE."); + #endif + #if HAS_Y_AXIS + static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS) are too narrow to contain Y_BED_SIZE."); + #endif #endif /** @@ -860,45 +308,45 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #endif #endif -#if BOTH(ENDSTOPPULLUPS, ENDSTOPPULLDOWNS) +#if ALL(ENDSTOPPULLUPS, ENDSTOPPULLDOWNS) #error "Enable only one of ENDSTOPPULLUPS or ENDSTOPPULLDOWNS." -#elif BOTH(FIL_RUNOUT_PULLUP, FIL_RUNOUT_PULLDOWN) +#elif ALL(FIL_RUNOUT_PULLUP, FIL_RUNOUT_PULLDOWN) #error "Enable only one of FIL_RUNOUT_PULLUP or FIL_RUNOUT_PULLDOWN." -#elif BOTH(ENDSTOPPULLUP_XMAX, ENDSTOPPULLDOWN_XMAX) +#elif ALL(ENDSTOPPULLUP_XMAX, ENDSTOPPULLDOWN_XMAX) #error "Enable only one of ENDSTOPPULLUP_X_MAX or ENDSTOPPULLDOWN_X_MAX." -#elif BOTH(ENDSTOPPULLUP_YMAX, ENDSTOPPULLDOWN_YMAX) +#elif ALL(ENDSTOPPULLUP_YMAX, ENDSTOPPULLDOWN_YMAX) #error "Enable only one of ENDSTOPPULLUP_Y_MAX or ENDSTOPPULLDOWN_Y_MAX." -#elif BOTH(ENDSTOPPULLUP_ZMAX, ENDSTOPPULLDOWN_ZMAX) +#elif ALL(ENDSTOPPULLUP_ZMAX, ENDSTOPPULLDOWN_ZMAX) #error "Enable only one of ENDSTOPPULLUP_Z_MAX or ENDSTOPPULLDOWN_Z_MAX." -#elif BOTH(ENDSTOPPULLUP_IMAX, ENDSTOPPULLDOWN_IMAX) +#elif ALL(ENDSTOPPULLUP_IMAX, ENDSTOPPULLDOWN_IMAX) #error "Enable only one of ENDSTOPPULLUP_I_MAX or ENDSTOPPULLDOWN_I_MAX." -#elif BOTH(ENDSTOPPULLUP_JMAX, ENDSTOPPULLDOWN_JMAX) +#elif ALL(ENDSTOPPULLUP_JMAX, ENDSTOPPULLDOWN_JMAX) #error "Enable only one of ENDSTOPPULLUP_J_MAX or ENDSTOPPULLDOWN_J_MAX." -#elif BOTH(ENDSTOPPULLUP_KMAX, ENDSTOPPULLDOWN_KMAX) +#elif ALL(ENDSTOPPULLUP_KMAX, ENDSTOPPULLDOWN_KMAX) #error "Enable only one of ENDSTOPPULLUP_K_MAX or ENDSTOPPULLDOWN_K_MAX." -#elif BOTH(ENDSTOPPULLUP_UMAX, ENDSTOPPULLDOWN_UMAX) +#elif ALL(ENDSTOPPULLUP_UMAX, ENDSTOPPULLDOWN_UMAX) #error "Enable only one of ENDSTOPPULLUP_U_MAX or ENDSTOPPULLDOWN_U_MAX." -#elif BOTH(ENDSTOPPULLUP_VMAX, ENDSTOPPULLDOWN_VMAX) +#elif ALL(ENDSTOPPULLUP_VMAX, ENDSTOPPULLDOWN_VMAX) #error "Enable only one of ENDSTOPPULLUP_V_MAX or ENDSTOPPULLDOWN_V_MAX." -#elif BOTH(ENDSTOPPULLUP_WMAX, ENDSTOPPULLDOWN_WMAX) +#elif ALL(ENDSTOPPULLUP_WMAX, ENDSTOPPULLDOWN_WMAX) #error "Enable only one of ENDSTOPPULLUP_W_MAX or ENDSTOPPULLDOWN_W_MAX." -#elif BOTH(ENDSTOPPULLUP_XMIN, ENDSTOPPULLDOWN_XMIN) +#elif ALL(ENDSTOPPULLUP_XMIN, ENDSTOPPULLDOWN_XMIN) #error "Enable only one of ENDSTOPPULLUP_X_MIN or ENDSTOPPULLDOWN_X_MIN." -#elif BOTH(ENDSTOPPULLUP_YMIN, ENDSTOPPULLDOWN_YMIN) +#elif ALL(ENDSTOPPULLUP_YMIN, ENDSTOPPULLDOWN_YMIN) #error "Enable only one of ENDSTOPPULLUP_Y_MIN or ENDSTOPPULLDOWN_Y_MIN." -#elif BOTH(ENDSTOPPULLUP_ZMIN, ENDSTOPPULLDOWN_ZMIN) +#elif ALL(ENDSTOPPULLUP_ZMIN, ENDSTOPPULLDOWN_ZMIN) #error "Enable only one of ENDSTOPPULLUP_Z_MIN or ENDSTOPPULLDOWN_Z_MIN." -#elif BOTH(ENDSTOPPULLUP_IMIN, ENDSTOPPULLDOWN_IMIN) +#elif ALL(ENDSTOPPULLUP_IMIN, ENDSTOPPULLDOWN_IMIN) #error "Enable only one of ENDSTOPPULLUP_I_MIN or ENDSTOPPULLDOWN_I_MIN." -#elif BOTH(ENDSTOPPULLUP_JMIN, ENDSTOPPULLDOWN_JMIN) +#elif ALL(ENDSTOPPULLUP_JMIN, ENDSTOPPULLDOWN_JMIN) #error "Enable only one of ENDSTOPPULLUP_J_MIN or ENDSTOPPULLDOWN_J_MIN." -#elif BOTH(ENDSTOPPULLUP_KMIN, ENDSTOPPULLDOWN_KMIN) +#elif ALL(ENDSTOPPULLUP_KMIN, ENDSTOPPULLDOWN_KMIN) #error "Enable only one of ENDSTOPPULLUP_K_MIN or ENDSTOPPULLDOWN_K_MIN." -#elif BOTH(ENDSTOPPULLUP_UMIN, ENDSTOPPULLDOWN_UMIN) +#elif ALL(ENDSTOPPULLUP_UMIN, ENDSTOPPULLDOWN_UMIN) #error "Enable only one of ENDSTOPPULLUP_U_MIN or ENDSTOPPULLDOWN_U_MIN." -#elif BOTH(ENDSTOPPULLUP_VMIN, ENDSTOPPULLDOWN_VMIN) +#elif ALL(ENDSTOPPULLUP_VMIN, ENDSTOPPULLDOWN_VMIN) #error "Enable only one of ENDSTOPPULLUP_V_MIN or ENDSTOPPULLDOWN_V_MIN." -#elif BOTH(ENDSTOPPULLUP_WMIN, ENDSTOPPULLDOWN_WMIN) +#elif ALL(ENDSTOPPULLUP_WMIN, ENDSTOPPULLDOWN_WMIN) #error "Enable only one of ENDSTOPPULLUP_W_MIN or ENDSTOPPULLDOWN_W_MIN." #endif @@ -994,11 +442,14 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #elif SDSORT_CACHE_VFATS > MAX_VFAT_ENTRIES #undef SDSORT_CACHE_VFATS #define SDSORT_CACHE_VFATS MAX_VFAT_ENTRIES - #warning "SDSORT_CACHE_VFATS was reduced to MAX_VFAT_ENTRIES!" + #define SDSORT_CACHE_VFATS_WARNING 1 #endif #endif #endif +/** + * Custom Event G-code + */ #if defined(EVENT_GCODE_SD_ABORT) && DISABLED(NOZZLE_PARK_FEATURE) static_assert(nullptr == strstr(EVENT_GCODE_SD_ABORT, "G27"), "NOZZLE_PARK_FEATURE is required to use G27 in EVENT_GCODE_SD_ABORT."); #endif @@ -1007,7 +458,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS * I2C Position Encoders */ #if ENABLED(I2C_POSITION_ENCODERS) - #if !BOTH(BABYSTEPPING, BABYSTEP_XY) + #if !ALL(BABYSTEPPING, BABYSTEP_XY) #error "I2C_POSITION_ENCODERS requires BABYSTEPPING and BABYSTEP_XY." #elif !WITHIN(I2CPE_ENCODER_CNT, 1, 5) #error "I2CPE_ENCODER_CNT must be between 1 and 5." @@ -1020,11 +471,11 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #if ENABLED(BABYSTEPPING) #if ENABLED(SCARA) #error "BABYSTEPPING is not implemented for SCARA yet." - #elif ENABLED(BABYSTEP_XY) && EITHER(MARKFORGED_XY, MARKFORGED_YX) + #elif ENABLED(BABYSTEP_XY) && ANY(MARKFORGED_XY, MARKFORGED_YX) #error "BABYSTEPPING only implemented for Z axis on MarkForged." - #elif BOTH(DELTA, BABYSTEP_XY) + #elif ALL(DELTA, BABYSTEP_XY) #error "BABYSTEPPING only implemented for Z axis on deltabots." - #elif BOTH(BABYSTEP_ZPROBE_OFFSET, MESH_BED_LEVELING) + #elif ALL(BABYSTEP_ZPROBE_OFFSET, MESH_BED_LEVELING) #error "MESH_BED_LEVELING and BABYSTEP_ZPROBE_OFFSET is not a valid combination" #elif ENABLED(BABYSTEP_ZPROBE_OFFSET) && !HAS_BED_PROBE #error "BABYSTEP_ZPROBE_OFFSET requires a probe." @@ -1034,7 +485,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "BABYSTEP_ZPROBE_GFX_OVERLAY requires a BABYSTEP_ZPROBE_OFFSET." #elif ENABLED(BABYSTEP_HOTEND_Z_OFFSET) && !HAS_HOTEND_OFFSET #error "BABYSTEP_HOTEND_Z_OFFSET requires 2 or more HOTENDS." - #elif BOTH(BABYSTEP_ALWAYS_AVAILABLE, MOVE_Z_WHEN_IDLE) + #elif ALL(BABYSTEP_ALWAYS_AVAILABLE, MOVE_Z_WHEN_IDLE) #error "BABYSTEP_ALWAYS_AVAILABLE and MOVE_Z_WHEN_IDLE are incompatible." #elif !defined(BABYSTEP_MULTIPLICATOR_Z) #error "BABYSTEPPING requires BABYSTEP_MULTIPLICATOR_Z." @@ -1072,25 +523,25 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "FIL_RUNOUT3_PIN is required with NUM_RUNOUT_SENSORS >= 3." #elif NUM_RUNOUT_SENSORS >= 2 && !PIN_EXISTS(FIL_RUNOUT2) #error "FIL_RUNOUT2_PIN is required with NUM_RUNOUT_SENSORS >= 2." - #elif BOTH(FIL_RUNOUT1_PULLUP, FIL_RUNOUT1_PULLDOWN) + #elif ALL(FIL_RUNOUT1_PULLUP, FIL_RUNOUT1_PULLDOWN) #error "You can't enable FIL_RUNOUT1_PULLUP and FIL_RUNOUT1_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT2_PULLUP, FIL_RUNOUT2_PULLDOWN) + #elif ALL(FIL_RUNOUT2_PULLUP, FIL_RUNOUT2_PULLDOWN) #error "You can't enable FIL_RUNOUT2_PULLUP and FIL_RUNOUT2_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT3_PULLUP, FIL_RUNOUT3_PULLDOWN) + #elif ALL(FIL_RUNOUT3_PULLUP, FIL_RUNOUT3_PULLDOWN) #error "You can't enable FIL_RUNOUT3_PULLUP and FIL_RUNOUT3_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT4_PULLUP, FIL_RUNOUT4_PULLDOWN) + #elif ALL(FIL_RUNOUT4_PULLUP, FIL_RUNOUT4_PULLDOWN) #error "You can't enable FIL_RUNOUT4_PULLUP and FIL_RUNOUT4_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT5_PULLUP, FIL_RUNOUT5_PULLDOWN) + #elif ALL(FIL_RUNOUT5_PULLUP, FIL_RUNOUT5_PULLDOWN) #error "You can't enable FIL_RUNOUT5_PULLUP and FIL_RUNOUT5_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT6_PULLUP, FIL_RUNOUT6_PULLDOWN) + #elif ALL(FIL_RUNOUT6_PULLUP, FIL_RUNOUT6_PULLDOWN) #error "You can't enable FIL_RUNOUT6_PULLUP and FIL_RUNOUT6_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT7_PULLUP, FIL_RUNOUT7_PULLDOWN) + #elif ALL(FIL_RUNOUT7_PULLUP, FIL_RUNOUT7_PULLDOWN) #error "You can't enable FIL_RUNOUT7_PULLUP and FIL_RUNOUT7_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT8_PULLUP, FIL_RUNOUT8_PULLDOWN) + #elif ALL(FIL_RUNOUT8_PULLUP, FIL_RUNOUT8_PULLDOWN) #error "You can't enable FIL_RUNOUT8_PULLUP and FIL_RUNOUT8_PULLDOWN at the same time." #elif FILAMENT_RUNOUT_DISTANCE_MM < 0 #error "FILAMENT_RUNOUT_DISTANCE_MM must be greater than or equal to zero." - #elif DISABLED(ADVANCED_PAUSE_FEATURE) + #elif DISABLED(ADVANCED_PAUSE_FEATURE) && defined(FILAMENT_RUNOUT_SCRIPT) static_assert(nullptr == strstr(FILAMENT_RUNOUT_SCRIPT, "M600"), "ADVANCED_PAUSE_FEATURE is required to use M600 with FILAMENT_RUNOUT_SENSOR."); #endif #endif @@ -1122,11 +573,11 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #if ENABLED(NOZZLE_PARK_FEATURE) constexpr float npp[] = NOZZLE_PARK_POINT; - static_assert(COUNT(npp) == XYZ, "NOZZLE_PARK_POINT requires X, Y, and Z values."); + static_assert(COUNT(npp) == _MIN(NUM_AXES, XYZ), "NOZZLE_PARK_POINT requires coordinates for enabled axes, but only up to X,Y,Z."); constexpr xyz_pos_t npp_xyz = NOZZLE_PARK_POINT; static_assert(WITHIN(npp_xyz.x, X_MIN_POS, X_MAX_POS), "NOZZLE_PARK_POINT.X is out of bounds (X_MIN_POS, X_MAX_POS)."); - static_assert(WITHIN(npp_xyz.y, Y_MIN_POS, Y_MAX_POS), "NOZZLE_PARK_POINT.Y is out of bounds (Y_MIN_POS, Y_MAX_POS)."); - static_assert(WITHIN(npp_xyz.z, Z_MIN_POS, Z_MAX_POS), "NOZZLE_PARK_POINT.Z is out of bounds (Z_MIN_POS, Z_MAX_POS)."); + static_assert(TERN1(HAS_Y_AXIS, WITHIN(npp_xyz.y, Y_MIN_POS, Y_MAX_POS)), "NOZZLE_PARK_POINT.Y is out of bounds (Y_MIN_POS, Y_MAX_POS)."); + static_assert(TERN1(HAS_Z_AXIS, WITHIN(npp_xyz.z, Z_MIN_POS, Z_MAX_POS)), "NOZZLE_PARK_POINT.Z is out of bounds (Z_MIN_POS, Z_MAX_POS)."); #endif /** @@ -1139,7 +590,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * Individual axis homing is useless for DELTAS */ -#if BOTH(INDIVIDUAL_AXIS_HOMING_MENU, DELTA) +#if ALL(INDIVIDUAL_AXIS_HOMING_MENU, DELTA) #error "INDIVIDUAL_AXIS_HOMING_MENU is incompatible with DELTA kinematics." #endif @@ -1189,10 +640,12 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS */ #if HAS_MULTI_EXTRUDER - #if HAS_EXTENDABLE_MMU - #define MAX_EXTRUDERS 15 - #else - #define MAX_EXTRUDERS 8 + #ifndef MAX_EXTRUDERS + #if HAS_EXTENDABLE_MMU + #define MAX_EXTRUDERS 15 + #else + #define MAX_EXTRUDERS 8 + #endif #endif static_assert(EXTRUDERS <= MAX_EXTRUDERS, "Marlin supports a maximum of " STRINGIFY(MAX_EXTRUDERS) " EXTRUDERS."); #undef MAX_EXTRUDERS @@ -1267,7 +720,6 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #elif SWITCHING_NOZZLE_SERVO_NR == 3 && !PIN_EXISTS(SERVO3) #error "SERVO3_PIN must be defined for your SWITCHING_NOZZLE." #endif - #ifdef SWITCHING_NOZZLE_E1_SERVO_NR #if SWITCHING_NOZZLE_E1_SERVO_NR == SWITCHING_NOZZLE_SERVO_NR #error "SWITCHING_NOZZLE_E1_SERVO_NR must be different from SWITCHING_NOZZLE_SERVO_NR." @@ -1281,7 +733,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "SERVO3_PIN must be defined for your SWITCHING_NOZZLE." #endif #endif -#endif +#endif // SWITCHING_NOZZLE /** * Single Stepper Dual Extruder with switching servo @@ -1289,6 +741,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #if ENABLED(SWITCHING_EXTRUDER) #if NUM_SERVOS < 1 #error "SWITCHING_EXTRUDER requires NUM_SERVOS >= 1." + #elif !defined(SWITCHING_EXTRUDER_SERVO_NR) + #error "SWITCHING_EXTRUDER requires SWITCHING_EXTRUDER_SERVO_NR." #elif SWITCHING_EXTRUDER_SERVO_NR == 0 && !PIN_EXISTS(SERVO0) #error "SERVO0_PIN must be defined for your SWITCHING_EXTRUDER." #elif SWITCHING_EXTRUDER_SERVO_NR == 1 && !PIN_EXISTS(SERVO1) @@ -1312,8 +766,10 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #elif SWITCHING_EXTRUDER_E23_SERVO_NR == SWITCHING_EXTRUDER_SERVO_NR #error "SWITCHING_EXTRUDER_E23_SERVO_NR should be a different extruder from SWITCHING_EXTRUDER_SERVO_NR." #endif + #elif EXTRUDERS < 2 + #error "SWITCHING_EXTRUDER requires EXTRUDERS >= 2." #endif -#endif +#endif // SWITCHING_EXTRUDER /** * Mixing Extruder requirements @@ -1329,8 +785,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "Please select either MIXING_EXTRUDER or SWITCHING_EXTRUDER, not both." #elif ENABLED(SINGLENOZZLE) #error "MIXING_EXTRUDER is incompatible with SINGLENOZZLE." - #elif ENABLED(DISABLE_INACTIVE_EXTRUDER) - #error "MIXING_EXTRUDER is incompatible with DISABLE_INACTIVE_EXTRUDER." + #elif ENABLED(DISABLE_OTHER_EXTRUDERS) + #error "MIXING_EXTRUDER is incompatible with DISABLE_OTHER_EXTRUDERS." #elif HAS_FILAMENT_RUNOUT_DISTANCE #error "MIXING_EXTRUDER is incompatible with FILAMENT_RUNOUT_DISTANCE_MM." #endif @@ -1362,10 +818,9 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #else static_assert(WITHIN(ADVANCE_K, 0, 10), "ADVANCE_K must be from 0 to 10 (Changed in LIN_ADVANCE v1.5, Marlin 1.1.9)."); #endif - #if ENABLED(S_CURVE_ACCELERATION) && DISABLED(EXPERIMENTAL_SCURVE) - #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." + + #if ENABLED(DIRECT_STEPPING) + #error "DIRECT_STEPPING is incompatible with LIN_ADVANCE. (Extrusion is controlled externally by the Step Daemon.)" #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 @@ -1381,7 +836,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * (Magnetic) Parking Extruder requirements */ -#if EITHER(PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER) +#if ANY(PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER) #if ENABLED(EXT_SOLENOID) #error "(MAGNETIC_)PARKING_EXTRUDER and EXT_SOLENOID are incompatible. (Pins are used twice.)" #elif EXTRUDERS != 2 @@ -1439,7 +894,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * Magnetic / Electromagnetic Switching Toolhead requirements */ -#if EITHER(MAGNETIC_SWITCHING_TOOLHEAD, ELECTROMAGNETIC_SWITCHING_TOOLHEAD) +#if ANY(MAGNETIC_SWITCHING_TOOLHEAD, ELECTROMAGNETIC_SWITCHING_TOOLHEAD) #ifndef SWITCHING_TOOLHEAD_Y_POS #error "(ELECTRO)?MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_POS" #elif !defined(SWITCHING_TOOLHEAD_X_POS) @@ -1465,14 +920,19 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * Part-Cooling Fan Multiplexer requirements */ -#if PIN_EXISTS(FANMUX1) - #if !HAS_FANMUX - #error "FANMUX0_PIN must be set before FANMUX1_PIN can be set." - #endif -#elif PIN_EXISTS(FANMUX2) +#if HAS_FANMUX && !HAS_FAN0 + #error "FAN0_PIN must be defined to use Fan Multiplexing." +#elif PIN_EXISTS(FANMUX1) && !PIN_EXISTS(FANMUX0) + #error "FANMUX0_PIN must be set before FANMUX1_PIN can be set." +#elif PIN_EXISTS(FANMUX2) && !PINS_EXIST(FANMUX0, FANMUX1) #error "FANMUX0_PIN and FANMUX1_PIN must be set before FANMUX2_PIN can be set." #endif +// PID Fan Scaling requires a fan +#if defined(PID_FAN_SCALING) && !HAS_FAN + #error "PID_FAN_SCALING needs at least one fan enabled." +#endif + /** * Limited user-controlled fans */ @@ -1504,12 +964,15 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * Extruder temperature control algorithm - There can be only one! */ -#if BOTH(PIDTEMP, MPCTEMP) +#if ALL(PIDTEMP, MPCTEMP) #error "Only enable PIDTEMP or MPCTEMP, but not both." + #undef MPCTEMP + #undef MPC_EDIT_MENU + #undef MPC_AUTOTUNE_MENU #endif #if ENABLED(MPC_INCLUDE_FAN) - #if FAN_COUNT < 1 + #if !HAS_FAN #error "MPC_INCLUDE_FAN requires at least one fan." #endif #if FAN_COUNT < HOTENDS @@ -1524,12 +987,12 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * Bed Heating Options - PID vs Limit Switching */ -#if BOTH(PIDTEMPBED, BED_LIMIT_SWITCHING) +#if ALL(PIDTEMPBED, BED_LIMIT_SWITCHING) #error "To use BED_LIMIT_SWITCHING you must disable PIDTEMPBED." #endif -// Fan Kickstart -#if FAN_KICKSTART_TIME && defined(FAN_KICKSTART_POWER) && !WITHIN(FAN_KICKSTART_POWER, 64, 255) +// Fan Kickstart power +#if FAN_KICKSTART_TIME && !WITHIN(FAN_KICKSTART_POWER, 64, 255) #error "FAN_KICKSTART_POWER must be an integer from 64 to 255." #endif @@ -1547,7 +1010,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * Chamber Heating Options - PID vs Limit Switching */ -#if BOTH(PIDTEMPCHAMBER, CHAMBER_LIMIT_SWITCHING) +#if ALL(PIDTEMPCHAMBER, CHAMBER_LIMIT_SWITCHING) #error "To use CHAMBER_LIMIT_SWITCHING you must disable PIDTEMPCHAMBER." #endif @@ -1698,7 +1161,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * Some things should not be used on Belt Printers */ -#if BOTH(BELTPRINTER, HAS_LEVELING) +#if ALL(BELTPRINTER, HAS_LEVELING) #error "Bed Leveling is not compatible with BELTPRINTER." #endif @@ -1720,7 +1183,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * Z_PROBE_SLED is incompatible with DELTA */ - #if BOTH(Z_PROBE_SLED, DELTA) + #if ALL(Z_PROBE_SLED, DELTA) #error "You cannot use Z_PROBE_SLED with DELTA." #endif @@ -1857,7 +1320,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * Mag mounted probe requirements */ - #if BOTH(MAG_MOUNTED_PROBE, USE_PROBE_FOR_Z_HOMING) && DISABLED(Z_SAFE_HOMING) + #if ALL(MAG_MOUNTED_PROBE, USE_PROBE_FOR_Z_HOMING) && DISABLED(Z_SAFE_HOMING) #error "MAG_MOUNTED_PROBE requires Z_SAFE_HOMING if it's being used to home Z." #endif @@ -1886,7 +1349,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #elif ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) #if DISABLED(USE_ZMIN_PLUG) #error "Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN requires USE_ZMIN_PLUG to be enabled." - #elif !HAS_Z_MIN + #elif !USE_Z_MIN #error "Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN requires the Z_MIN_PIN to be defined." #elif Z_MIN_PROBE_ENDSTOP_INVERTING != Z_MIN_ENDSTOP_INVERTING #error "Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN requires Z_MIN_ENDSTOP_INVERTING to match Z_MIN_PROBE_ENDSTOP_INVERTING." @@ -1988,7 +1451,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS * Allow only one bed leveling option to be defined */ #if MANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL, MESH_BED_LEVELING) - #error "Select only one of: MESH_BED_LEVELING, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." + #error "Select only one of: MESH_BED_LEVELING, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL." #endif /** @@ -2070,11 +1533,11 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #elif !(ENABLED(MESH_BED_LEVELING) || HAS_ABL_NOT_UBL) #error "LCD_BED_LEVELING requires MESH_BED_LEVELING or AUTO_BED_LEVELING." #elif ENABLED(MESH_EDIT_MENU) && !HAS_MESH - #error "MESH_EDIT_MENU requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." + #error "MESH_EDIT_MENU requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL." #endif #endif -#if BOTH(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) +#if ALL(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) #error "Disable PREHEAT_BEFORE_LEVELING when using PREHEAT_BEFORE_PROBING." #endif @@ -2191,10 +1654,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * Make sure DISABLE_[XYZ] compatible with selected homing options */ -#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K, DISABLE_U, DISABLE_V, DISABLE_W) - #if EITHER(HOME_AFTER_DEACTIVATE, Z_SAFE_HOMING) - #error "DISABLE_[XYZIJKUVW] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING." - #endif +#if HAS_DISABLE_MAIN_AXES && ANY(HOME_AFTER_DEACTIVATE, Z_SAFE_HOMING) + #error "DISABLE_[XYZIJKUVW] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING." #endif /** @@ -2215,7 +1676,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "POWER_MONITOR_CURRENT requires a valid POWER_MONITOR_CURRENT_PIN." #elif ENABLED(POWER_MONITOR_VOLTAGE) && !PIN_EXISTS(POWER_MONITOR_VOLTAGE) #error "POWER_MONITOR_VOLTAGE requires POWER_MONITOR_VOLTAGE_PIN to be defined." -#elif BOTH(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) && POWER_MONITOR_CURRENT_PIN == POWER_MONITOR_VOLTAGE_PIN +#elif ALL(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) && POWER_MONITOR_CURRENT_PIN == POWER_MONITOR_VOLTAGE_PIN #error "POWER_MONITOR_CURRENT_PIN and POWER_MONITOR_VOLTAGE_PIN must be different." #endif @@ -2247,7 +1708,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #if ENABLED(SAV_3DGLCD) #if NONE(U8GLIB_SSD1306, U8GLIB_SH1106) #error "Enable a SAV_3DGLCD display type: U8GLIB_SSD1306 or U8GLIB_SH1106." - #elif BOTH(U8GLIB_SSD1306, U8GLIB_SH1106) + #elif ALL(U8GLIB_SSD1306, U8GLIB_SH1106) #error "Only enable one SAV_3DGLCD display type: U8GLIB_SSD1306 or U8GLIB_SH1106." #endif #endif @@ -2270,12 +1731,12 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #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 + #elif !USE_X_MAX #error "DUAL_X_CARRIAGE requires USE_XMAX_PLUG and an X Max Endstop." #elif !defined(X2_HOME_POS) || !defined(X2_MIN_POS) || !defined(X2_MAX_POS) #error "DUAL_X_CARRIAGE requires X2_HOME_POS, X2_MIN_POS, and X2_MAX_POS." #elif X_HOME_TO_MAX || X2_HOME_TO_MIN - #error "DUAL_X_CARRIAGE requires X_HOME_DIR -1 and X2_HOME_DIR 1." + #error "DUAL_X_CARRIAGE requires X_HOME_DIR -1." #endif #endif @@ -2286,21 +1747,21 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS */ #if HAS_AUTO_FAN #if HAS_FAN0 - #if PIN_EXISTS(E0_AUTO_FAN) && E0_AUTO_FAN_PIN == FAN_PIN - #error "You cannot set E0_AUTO_FAN_PIN equal to FAN_PIN." - #elif PIN_EXISTS(E1_AUTO_FAN) && E1_AUTO_FAN_PIN == FAN_PIN - #error "You cannot set E1_AUTO_FAN_PIN equal to FAN_PIN." - #elif PIN_EXISTS(E2_AUTO_FAN) && E2_AUTO_FAN_PIN == FAN_PIN - #error "You cannot set E2_AUTO_FAN_PIN equal to FAN_PIN." - #elif PIN_EXISTS(E3_AUTO_FAN) && E3_AUTO_FAN_PIN == FAN_PIN - #error "You cannot set E3_AUTO_FAN_PIN equal to FAN_PIN." + #if PIN_EXISTS(E0_AUTO_FAN) && E0_AUTO_FAN_PIN == FAN0_PIN + #error "You cannot set E0_AUTO_FAN_PIN equal to FAN0_PIN." + #elif PIN_EXISTS(E1_AUTO_FAN) && E1_AUTO_FAN_PIN == FAN0_PIN + #error "You cannot set E1_AUTO_FAN_PIN equal to FAN0_PIN." + #elif PIN_EXISTS(E2_AUTO_FAN) && E2_AUTO_FAN_PIN == FAN0_PIN + #error "You cannot set E2_AUTO_FAN_PIN equal to FAN0_PIN." + #elif PIN_EXISTS(E3_AUTO_FAN) && E3_AUTO_FAN_PIN == FAN0_PIN + #error "You cannot set E3_AUTO_FAN_PIN equal to FAN0_PIN." #endif #endif #endif #if HAS_FAN0 - #if CONTROLLER_FAN_PIN == FAN_PIN - #error "You cannot set CONTROLLER_FAN_PIN equal to FAN_PIN." + #if CONTROLLER_FAN_PIN == FAN0_PIN + #error "You cannot set CONTROLLER_FAN_PIN equal to FAN0_PIN." #elif ENABLED(FAN_SOFT_PWM_REQUIRED) && DISABLED(FAN_SOFT_PWM) #error "FAN_SOFT_PWM is required for your board. Enable it to continue." #endif @@ -2328,11 +1789,26 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #endif #endif +/** + * Make sure FAN_*_PWM values are sensible + */ +#if ANY(HAS_FAN, USE_CONTROLLER_FAN) + #if !WITHIN(FAN_MIN_PWM, 0, 255) + #error "FAN_MIN_PWM must be a value from 0 to 255." + #elif !WITHIN(FAN_MAX_PWM, 0, 255) + #error "FAN_MAX_PWM must be a value from 0 to 255." + #elif FAN_MIN_PWM > FAN_MAX_PWM + #error "FAN_MIN_PWM must be less than or equal to FAN_MAX_PWM." + #elif FAN_OFF_PWM > FAN_MIN_PWM + #error "FAN_OFF_PWM must be less than or equal to FAN_MIN_PWM." + #endif +#endif + #ifdef REDUNDANT_PART_COOLING_FAN #if FAN_COUNT < 2 #error "REDUNDANT_PART_COOLING_FAN requires a board with at least two PWM fans." - #else - static_assert(WITHIN(REDUNDANT_PART_COOLING_FAN, 1, FAN_COUNT - 1), "REDUNDANT_PART_COOLING_FAN must be between 1 and " STRINGIFY(DECREMENT(FAN_COUNT)) "."); + #elif !WITHIN(REDUNDANT_PART_COOLING_FAN, 1, FAN_COUNT - 1) + static_assert(false, "REDUNDANT_PART_COOLING_FAN must be between 1 and " STRINGIFY(DECREMENT(FAN_COUNT)) "."); #endif #endif @@ -2342,8 +1818,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #if NEED_CASE_LIGHT_PIN #if !PIN_EXISTS(CASE_LIGHT) #error "CASE_LIGHT_ENABLE requires CASE_LIGHT_PIN, CASE_LIGHT_USE_NEOPIXEL, or CASE_LIGHT_USE_RGB_LED." - #elif CASE_LIGHT_PIN == FAN_PIN - #error "CASE_LIGHT_PIN conflicts with FAN_PIN. Resolve before continuing." + #elif CASE_LIGHT_PIN == FAN0_PIN + #error "CASE_LIGHT_PIN conflicts with FAN0_PIN. Resolve before continuing." #endif #endif @@ -2409,6 +1885,10 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #undef _BAD_MINTEMP #endif +#if TEMP_SENSOR_BED == 66 && PREHEAT_TIME_BED_MS < 15000 + #error "Thermistor 66 requires PREHEAT_TIME_BED_MS ≥ 15000, but 30000 or higher is recommended." +#endif + /** * Required MAX31865 settings */ @@ -2509,7 +1989,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "TEMP_SENSOR_0 MAX thermocouple requires TEMP_0_CS_PIN." #elif HAS_HOTEND && !HAS_TEMP_HOTEND && !TEMP_SENSOR_0_IS_DUMMY #error "TEMP_0_PIN (required for TEMP_SENSOR_0) not defined for this board." -#elif EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) && !HAS_HEATER_1 +#elif ANY(HAS_MULTI_HOTEND, HEATERS_PARALLEL) && !HAS_HEATER_1 #error "HEATER_1_PIN is not defined. TEMP_SENSOR_1 might not be set, or the board (not EEB / EEF?) doesn't define a pin." #endif @@ -2652,7 +2132,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * FYSETC/MKS/BTT Mini Panel Requirements */ -#if EITHER(FYSETC_242_OLED_12864, FYSETC_MINI_12864_2_1) +#if ANY(FYSETC_242_OLED_12864, FYSETC_MINI_12864_2_1) #ifndef NEO_RGB #define NEO_RGB 123 #define FAUX_RGB 1 @@ -2666,7 +2146,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #undef NEO_RGB #undef FAUX_RGB #endif -#elif EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) && DISABLED(RGB_LED) +#elif ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) && DISABLED(RGB_LED) #error "Your FYSETC Mini Panel requires RGB_LED." #endif @@ -2702,8 +2182,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "E0_STEP_PIN or E0_DIR_PIN not defined for this board." #elif ( !(defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && (!PINS_EXIST(E0_STEP, E0_DIR) || !HAS_E0_ENABLE)) #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board." - #elif EXTRUDERS && TEMP_SENSOR_0 == 0 - #error "TEMP_SENSOR_0 is required if there are any extruders." + #elif HOTENDS && TEMP_SENSOR_0 == 0 + #error "TEMP_SENSOR_0 is required if there are any hotends." #endif #endif @@ -2815,14 +2295,14 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "Enable USE_ZMIN_PLUG when homing Z to MIN." #elif Z_HOME_TO_MAX && ENABLED(USE_PROBE_FOR_Z_HOMING) #error "Z_HOME_DIR must be -1 when homing Z with the probe." - #elif BOTH(HOMING_Z_WITH_PROBE, Z_MULTI_ENDSTOPS) + #elif ALL(HOMING_Z_WITH_PROBE, Z_MULTI_ENDSTOPS) #error "Z_MULTI_ENDSTOPS is incompatible with USE_PROBE_FOR_Z_HOMING." #elif Z_HOME_TO_MAX && DISABLED(USE_ZMAX_PLUG) #error "Enable USE_ZMAX_PLUG when homing Z to MAX." #endif #endif -#if BOTH(HOME_Z_FIRST, USE_PROBE_FOR_Z_HOMING) +#if ALL(HOME_Z_FIRST, USE_PROBE_FOR_Z_HOMING) #error "HOME_Z_FIRST can't be used when homing Z with a probe." #endif @@ -2957,21 +2437,21 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS * Fan check */ #if HAS_FANCHECK - #if BOTH(E0_FAN_TACHO_PULLUP, E0_FAN_TACHO_PULLDOWN) + #if ALL(E0_FAN_TACHO_PULLUP, E0_FAN_TACHO_PULLDOWN) #error "Enable only one of E0_FAN_TACHO_PULLUP or E0_FAN_TACHO_PULLDOWN." - #elif BOTH(E1_FAN_TACHO_PULLUP, E1_FAN_TACHO_PULLDOWN) + #elif ALL(E1_FAN_TACHO_PULLUP, E1_FAN_TACHO_PULLDOWN) #error "Enable only one of E1_FAN_TACHO_PULLUP or E1_FAN_TACHO_PULLDOWN." - #elif BOTH(E2_FAN_TACHO_PULLUP, E2_FAN_TACHO_PULLDOWN) + #elif ALL(E2_FAN_TACHO_PULLUP, E2_FAN_TACHO_PULLDOWN) #error "Enable only one of E2_FAN_TACHO_PULLUP or E2_FAN_TACHO_PULLDOWN." - #elif BOTH(E3_FAN_TACHO_PULLUP, E3_FAN_TACHO_PULLDOWN) + #elif ALL(E3_FAN_TACHO_PULLUP, E3_FAN_TACHO_PULLDOWN) #error "Enable only one of E3_FAN_TACHO_PULLUP or E3_FAN_TACHO_PULLDOWN." - #elif BOTH(E4_FAN_TACHO_PULLUP, E4_FAN_TACHO_PULLDOWN) + #elif ALL(E4_FAN_TACHO_PULLUP, E4_FAN_TACHO_PULLDOWN) #error "Enable only one of E4_FAN_TACHO_PULLUP or E4_FAN_TACHO_PULLDOWN." - #elif BOTH(E5_FAN_TACHO_PULLUP, E5_FAN_TACHO_PULLDOWN) + #elif ALL(E5_FAN_TACHO_PULLUP, E5_FAN_TACHO_PULLDOWN) #error "Enable only one of E5_FAN_TACHO_PULLUP or E5_FAN_TACHO_PULLDOWN." - #elif BOTH(E6_FAN_TACHO_PULLUP, E6_FAN_TACHO_PULLDOWN) + #elif ALL(E6_FAN_TACHO_PULLUP, E6_FAN_TACHO_PULLDOWN) #error "Enable only one of E6_FAN_TACHO_PULLUP or E6_FAN_TACHO_PULLDOWN." - #elif BOTH(E7_FAN_TACHO_PULLUP, E7_FAN_TACHO_PULLDOWN) + #elif ALL(E7_FAN_TACHO_PULLUP, E7_FAN_TACHO_PULLDOWN) #error "Enable only one of E7_FAN_TACHO_PULLUP or E7_FAN_TACHO_PULLDOWN." #endif #elif ENABLED(AUTO_REPORT_FANS) @@ -2997,14 +2477,13 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS /** * Make sure features that need to write to the SD card can */ -#if ENABLED(SDCARD_READONLY) && ANY(POWER_LOSS_RECOVERY, BINARY_FILE_TRANSFER, SDCARD_EEPROM_EMULATION) - #undef SDCARD_READONLY +#if ENABLED(SDCARD_READONLY) #if ENABLED(POWER_LOSS_RECOVERY) - #warning "Either disable SDCARD_READONLY or disable POWER_LOSS_RECOVERY." + #error "Either disable SDCARD_READONLY or disable POWER_LOSS_RECOVERY." #elif ENABLED(BINARY_FILE_TRANSFER) - #warning "Either disable SDCARD_READONLY or disable BINARY_FILE_TRANSFER." + #error "Either disable SDCARD_READONLY or disable BINARY_FILE_TRANSFER." #elif ENABLED(SDCARD_EEPROM_EMULATION) - #warning "Either disable SDCARD_READONLY or disable SDCARD_EEPROM_EMULATION." + #error "Either disable SDCARD_READONLY or disable SDCARD_EEPROM_EMULATION." #endif #endif @@ -3025,8 +2504,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_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(FYSETC_MINI_12864_2_1) && NONE(MKS_MINI_12864_V3, BTT_MINI_12864)) \ + + COUNT_ENABLED(MKS_MINI_12864_V3, BTT_MINI_12864) \ + (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)) \ @@ -3037,7 +2516,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS + 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) \ + + 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) \ + COUNT_ENABLED(TFTGLCD_PANEL_SPI, TFTGLCD_PANEL_I2C) \ + COUNT_ENABLED(VIKI2, miniVIKI) \ + ENABLED(WYH_L12864) \ @@ -3100,10 +2580,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #if ENABLED(TFT_GENERIC) && NONE(TFT_INTERFACE_FSMC, TFT_INTERFACE_SPI) #error "TFT_GENERIC requires either TFT_INTERFACE_FSMC or TFT_INTERFACE_SPI interface." -#endif - -#if BOTH(TFT_INTERFACE_FSMC, TFT_INTERFACE_SPI) - #error "Please enable only one of TFT_INTERFACE_SPI or TFT_INTERFACE_SPI." +#elif ALL(TFT_INTERFACE_FSMC, TFT_INTERFACE_SPI) + #error "Please enable only one of TFT_INTERFACE_FSMC or TFT_INTERFACE_SPI." #endif #if defined(LCD_SCREEN_ROTATE) && LCD_SCREEN_ROTATE != 0 && LCD_SCREEN_ROTATE != 90 && LCD_SCREEN_ROTATE != 180 && LCD_SCREEN_ROTATE != 270 @@ -3117,7 +2595,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #if ENABLED(TFT_LVGL_UI) #if DISABLED(TFT_RES_480x320) #error "TFT_LVGL_UI requires TFT_RES_480x320." - #elif DISABLED(SDSUPPORT) + #elif !HAS_MEDIA #error "TFT_LVGL_UI requires SDSUPPORT." #endif #endif @@ -3126,14 +2604,14 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "GRAPHICAL_TFT_UPSCALE must be between 2 and 8." #endif -#if BOTH(CHIRON_TFT_STANDARD, CHIRON_TFT_NEW) +#if ALL(CHIRON_TFT_STANDARD, CHIRON_TFT_NEW) #error "Please select only one of CHIRON_TFT_STANDARD or CHIRON_TFT_NEW." #endif #if ENABLED(ANYCUBIC_LCD_CHIRON) #ifndef BEEPER_PIN #error "ANYCUBIC_LCD_CHIRON requires BEEPER_PIN" - #elif DISABLED(SDSUPPORT) + #elif !HAS_MEDIA #error "ANYCUBIC_LCD_CHIRON requires SDSUPPORT" #elif TEMP_SENSOR_BED == 0 #error "ANYCUBIC_LCD_CHIRON requires heatbed (TEMP_SENSOR_BED)" @@ -3144,7 +2622,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #endif #endif -#if EITHER(MKS_TS35_V2_0, BTT_TFT35_SPI_V1_0) && SD_CONNECTION_IS(LCD) +#if ANY(MKS_TS35_V2_0, BTT_TFT35_SPI_V1_0) && SD_CONNECTION_IS(LCD) #error "SDCARD_CONNECTION cannot be set to LCD for the enabled TFT. No available SD card reader." #endif @@ -3152,27 +2630,27 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS * Ender-3 V2 controller has some limitations */ #if ENABLED(DWIN_CREALITY_LCD) - #if DISABLED(SDSUPPORT) + #if !HAS_MEDIA #error "DWIN_CREALITY_LCD requires SDSUPPORT to be enabled." - #elif EITHER(PID_EDIT_MENU, PID_AUTOTUNE_MENU) + #elif ANY(PID_EDIT_MENU, PID_AUTOTUNE_MENU) #error "DWIN_CREALITY_LCD does not support PID_EDIT_MENU or PID_AUTOTUNE_MENU." - #elif EITHER(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) + #elif ANY(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) #error "DWIN_CREALITY_LCD does not support MPC_EDIT_MENU or MPC_AUTOTUNE_MENU." #elif ENABLED(LCD_BED_TRAMMING) #error "DWIN_CREALITY_LCD does not support LCD_BED_TRAMMING." - #elif BOTH(LCD_BED_LEVELING, PROBE_MANUALLY) + #elif ALL(LCD_BED_LEVELING, PROBE_MANUALLY) #error "DWIN_CREALITY_LCD does not support LCD_BED_LEVELING with PROBE_MANUALLY." #endif #elif ENABLED(DWIN_LCD_PROUI) - #if DISABLED(SDSUPPORT) + #if !HAS_MEDIA #error "DWIN_LCD_PROUI requires SDSUPPORT to be enabled." - #elif EITHER(PID_EDIT_MENU, PID_AUTOTUNE_MENU) + #elif ANY(PID_EDIT_MENU, PID_AUTOTUNE_MENU) #error "DWIN_LCD_PROUI does not support PID_EDIT_MENU or PID_AUTOTUNE_MENU." - #elif EITHER(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) + #elif ANY(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) #error "DWIN_LCD_PROUI does not support MPC_EDIT_MENU or MPC_AUTOTUNE_MENU." #elif ENABLED(LCD_BED_TRAMMING) #error "DWIN_LCD_PROUI does not support LCD_BED_TRAMMING." - #elif BOTH(LCD_BED_LEVELING, PROBE_MANUALLY) + #elif ALL(LCD_BED_LEVELING, PROBE_MANUALLY) #error "DWIN_LCD_PROUI does not support LCD_BED_LEVELING with PROBE_MANUALLY." #endif #endif @@ -3237,7 +2715,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #else #if HAS_DGUS_LCD #error "The DGUS LCD requires LCD_SERIAL_PORT to be defined." - #elif EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON) + #elif ANY(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON) #error "The ANYCUBIC LCD requires LCD_SERIAL_PORT to be defined." #elif ENABLED(MALYAN_LCD) #error "MALYAN_LCD requires LCD_SERIAL_PORT to be defined." @@ -3333,17 +2811,17 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_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 HAS_I_AXIS && INVALID_TMC_UART(I) +#elif INVALID_TMC_UART(I) #error "TMC2208 or TMC2209 on I requires I_HARDWARE_SERIAL or I_SERIAL_(RX|TX)_PIN." -#elif HAS_J_AXIS && INVALID_TMC_UART(J) +#elif INVALID_TMC_UART(J) #error "TMC2208 or TMC2209 on J requires J_HARDWARE_SERIAL or J_SERIAL_(RX|TX)_PIN." -#elif HAS_K_AXIS && INVALID_TMC_UART(K) +#elif INVALID_TMC_UART(K) #error "TMC2208 or TMC2209 on K requires K_HARDWARE_SERIAL or K_SERIAL_(RX|TX)_PIN." -#elif HAS_U_AXIS && INVALID_TMC_UART(U) +#elif INVALID_TMC_UART(U) #error "TMC2208 or TMC2209 on U requires U_HARDWARE_SERIAL or U_SERIAL_(RX|TX)_PIN." -#elif HAS_V_AXIS && INVALID_TMC_UART(V) +#elif INVALID_TMC_UART(V) #error "TMC2208 or TMC2209 on V requires V_HARDWARE_SERIAL or V_SERIAL_(RX|TX)_PIN." -#elif HAS_W_AXIS && INVALID_TMC_UART(W) +#elif INVALID_TMC_UART(W) #error "TMC2208 or TMC2209 on W requires W_HARDWARE_SERIAL or W_SERIAL_(RX|TX)_PIN." #endif @@ -3436,17 +2914,17 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS INVALID_TMC_MS(E6) #elif !TMC_MICROSTEP_IS_VALID(E7) INVALID_TMC_MS(E7) -#elif HAS_I_AXIS && !TMC_MICROSTEP_IS_VALID(I) +#elif !TMC_MICROSTEP_IS_VALID(I) INVALID_TMC_MS(I) -#elif HAS_J_AXIS && !TMC_MICROSTEP_IS_VALID(J) +#elif !TMC_MICROSTEP_IS_VALID(J) INVALID_TMC_MS(J) -#elif HAS_K_AXIS && !TMC_MICROSTEP_IS_VALID(K) +#elif !TMC_MICROSTEP_IS_VALID(K) INVALID_TMC_MS(K) -#elif HAS_U_AXIS && !TMC_MICROSTEP_IS_VALID(U) +#elif !TMC_MICROSTEP_IS_VALID(U) INVALID_TMC_MS(U) -#elif HAS_V_AXIS && !TMC_MICROSTEP_IS_VALID(V) +#elif !TMC_MICROSTEP_IS_VALID(V) INVALID_TMC_MS(V) -#elif HAS_W_AXIS && !TMC_MICROSTEP_IS_VALID(W) +#elif !TMC_MICROSTEP_IS_VALID(W) INVALID_TMC_MS(W) #endif #undef INVALID_TMC_MS @@ -3457,6 +2935,25 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "STEALTHCHOP_XY and STEALTHCHOP_Z must be the same on DELTA." #endif +// H-Bot kinematic axes can't use homing phases +#if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) && defined(TMC_HOME_PHASE) + constexpr float _phases[] = TMC_HOME_PHASE, _vphase[9] = TMC_HOME_PHASE; + constexpr int _nphase = COUNT(_phases); + static_assert(_nphase == NUM_AXES, "TMC_HOME_PHASE must have exactly " _NUM_AXES_STR " elements."); + static_assert(_nphase < 0 || _vphase[0] == -1 || NORMAL_AXIS == 0, "TMC_HOME_PHASE.x must be -1 for the selected kinematics."); + static_assert(_nphase < 1 || _vphase[1] == -1 || NORMAL_AXIS == 1, "TMC_HOME_PHASE.y must be -1 for the selected kinematics."); + static_assert(_nphase < 2 || _vphase[2] == -1 || NORMAL_AXIS == 2, "TMC_HOME_PHASE.z must be -1 for the selected kinematics."); + static_assert(_nphase < 0 || WITHIN(_vphase[0], -1, 1023), "TMC_HOME_PHASE.x must be between -1 and 1023."); + static_assert(_nphase < 1 || WITHIN(_vphase[1], -1, 1023), "TMC_HOME_PHASE.y must be between -1 and 1023."); + static_assert(_nphase < 2 || WITHIN(_vphase[2], -1, 1023), "TMC_HOME_PHASE.z must be between -1 and 1023."); + static_assert(_nphase < 3 || WITHIN(_vphase[3], -1, 1023), "TMC_HOME_PHASE.i must be between -1 and 1023."); + static_assert(_nphase < 4 || WITHIN(_vphase[4], -1, 1023), "TMC_HOME_PHASE.j must be between -1 and 1023."); + static_assert(_nphase < 5 || WITHIN(_vphase[5], -1, 1023), "TMC_HOME_PHASE.k must be between -1 and 1023."); + static_assert(_nphase < 6 || WITHIN(_vphase[6], -1, 1023), "TMC_HOME_PHASE.u must be between -1 and 1023."); + static_assert(_nphase < 7 || WITHIN(_vphase[7], -1, 1023), "TMC_HOME_PHASE.v must be between -1 and 1023."); + static_assert(_nphase < 8 || WITHIN(_vphase[8], -1, 1023), "TMC_HOME_PHASE.w must be between -1 and 1023."); +#endif + #if ENABLED(SENSORLESS_HOMING) // Require STEALTHCHOP for SENSORLESS_HOMING on DELTA as the transition from spreadCycle to stealthChop // is necessary in order to reset the stallGuard indication between the initial movement of all three @@ -3489,42 +2986,41 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #if NONE(SPI_ENDSTOPS, ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS) #if X_SENSORLESS && X_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_XMIN) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_XMIN (or ENDSTOPPULLUPS) when homing to X_MIN." + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_XMIN (or ENDSTOPPULLUPS) for X MIN homing." #elif X_SENSORLESS && X_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_XMAX) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_XMAX (or ENDSTOPPULLUPS) when homing to X_MAX." + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_XMAX (or ENDSTOPPULLUPS) for X MAX homing." #elif Y_SENSORLESS && Y_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_YMIN) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_YMIN (or ENDSTOPPULLUPS) when homing to Y_MIN." + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_YMIN (or ENDSTOPPULLUPS) for Y MIN homing." #elif Y_SENSORLESS && Y_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_YMAX) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_YMAX (or ENDSTOPPULLUPS) when homing to Y_MAX." + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_YMAX (or ENDSTOPPULLUPS) for Y MAX homing." #elif Z_SENSORLESS && Z_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_ZMIN) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) when homing to Z_MIN." + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) for Z MIN homing." #elif Z_SENSORLESS && Z_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_ZMAX) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) when homing to Z_MAX." - #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 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 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 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 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 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." - #elif HAS_U_AXIS && U_SENSORLESS && U_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_UMIN) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_UMIN (or ENDSTOPPULLUPS) when homing to U_MIN." - #elif HAS_U_AXIS && U_SENSORLESS && U_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_UMAX) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_UMAX (or ENDSTOPPULLUPS) when homing to U_MAX." - #elif HAS_V_AXIS && V_SENSORLESS && V_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_VMIN) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_VMIN (or ENDSTOPPULLUPS) when homing to V_MIN." - #elif HAS_V_AXIS && V_SENSORLESS && V_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_VMAX) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_VMAX (or ENDSTOPPULLUPS) when homing to V_MAX." - #elif HAS_W_AXIS && W_SENSORLESS && W_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_WMIN) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_WMIN (or ENDSTOPPULLUPS) when homing to W_MIN." - #elif HAS_W_AXIS && W_SENSORLESS && W_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_WMAX) - #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_WMAX (or ENDSTOPPULLUPS) when homing to W_MAX." - + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) for Z MAX homing." + #elif I_SENSORLESS && I_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_IMIN) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_IMIN (or ENDSTOPPULLUPS) for I MIN homing." + #elif I_SENSORLESS && I_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_IMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_IMAX (or ENDSTOPPULLUPS) for I MAX homing." + #elif J_SENSORLESS && J_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_JMIN) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_JMIN (or ENDSTOPPULLUPS) for J MIN homing." + #elif J_SENSORLESS && J_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_JMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_JMAX (or ENDSTOPPULLUPS) for J MAX homing." + #elif K_SENSORLESS && K_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_KMIN) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMIN (or ENDSTOPPULLUPS) for K MIN homing." + #elif K_SENSORLESS && K_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_KMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMAX (or ENDSTOPPULLUPS) for K MAX homing." + #elif U_SENSORLESS && U_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_UMIN) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_UMIN (or ENDSTOPPULLUPS) for U MIN homing." + #elif U_SENSORLESS && U_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_UMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_UMAX (or ENDSTOPPULLUPS) for U MAX homing." + #elif V_SENSORLESS && V_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_VMIN) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_VMIN (or ENDSTOPPULLUPS) for V MIN homing." + #elif V_SENSORLESS && V_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_VMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_VMAX (or ENDSTOPPULLUPS) for V MAX homing." + #elif W_SENSORLESS && W_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_WMIN) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_WMIN (or ENDSTOPPULLUPS) for W MIN homing." + #elif W_SENSORLESS && W_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_WMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_WMAX (or ENDSTOPPULLUPS) for W MAX homing." #endif #endif @@ -3644,7 +3140,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #endif #endif - #if ENABLED(DELTA) && !BOTH(STEALTHCHOP_XY, STEALTHCHOP_Z) + #if ENABLED(DELTA) && !ALL(STEALTHCHOP_XY, STEALTHCHOP_Z) #error "SENSORLESS_HOMING on DELTA currently requires STEALTHCHOP_XY and STEALTHCHOP_Z." #elif ENDSTOP_NOISE_THRESHOLD #error "SENSORLESS_HOMING is incompatible with ENDSTOP_NOISE_THRESHOLD." @@ -3661,7 +3157,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #undef U_ENDSTOP_INVERTING #undef V_ENDSTOP_INVERTING #undef W_ENDSTOP_INVERTING -#endif +#endif // SENSORLESS_HOMING // Sensorless probing requirements #if ENABLED(SENSORLESS_PROBING) @@ -3683,7 +3179,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_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 EITHER(MARKFORGED_XY, MARKFORGED_YX) && X_SENSORLESS != Y_SENSORLESS +#elif ANY(MARKFORGED_XY, MARKFORGED_YX) && X_SENSORLESS != Y_SENSORLESS #error "MARKFORGED requires both X and Y to use sensorless homing if either one does." #endif @@ -3702,10 +3198,12 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS * TMC SPI Chaining */ #define IN_CHAIN(A) A##_CHAIN_POS > 0 -#if IN_CHAIN(X ) || IN_CHAIN(Y ) || IN_CHAIN(Z ) || IN_CHAIN(X2) || IN_CHAIN(Y2) || IN_CHAIN(Z2) || IN_CHAIN(Z3) || IN_CHAIN(Z4) \ +#if IN_CHAIN(X) || IN_CHAIN(Y) || IN_CHAIN(Z) || IN_CHAIN(I) || IN_CHAIN(J) || IN_CHAIN(K) || IN_CHAIN(U) || IN_CHAIN(V) || IN_CHAIN(W) \ + || IN_CHAIN(X2) || IN_CHAIN(Y2) || IN_CHAIN(Z2) || IN_CHAIN(Z3) || IN_CHAIN(Z4) \ || IN_CHAIN(E0) || IN_CHAIN(E1) || IN_CHAIN(E2) || IN_CHAIN(E3) || IN_CHAIN(E4) || IN_CHAIN(E5) || IN_CHAIN(E6) || IN_CHAIN(E7) #define BAD_CHAIN(A) (IN_CHAIN(A) && !PIN_EXISTS(A##_CS)) - #if BAD_CHAIN(X ) || BAD_CHAIN(Y ) || BAD_CHAIN(Z ) || BAD_CHAIN(X2) || BAD_CHAIN(Y2) || BAD_CHAIN(Z2) || BAD_CHAIN(Z3) || BAD_CHAIN(Z4) \ + #if BAD_CHAIN(X) || BAD_CHAIN(Y) || BAD_CHAIN(Z) || BAD_CHAIN(I) || BAD_CHAIN(J) || BAD_CHAIN(K) || BAD_CHAIN(U) || BAD_CHAIN(V) || BAD_CHAIN(W) \ + || BAD_CHAIN(X2) || BAD_CHAIN(Y2) || BAD_CHAIN(Z2) || BAD_CHAIN(Z3) || BAD_CHAIN(Z4) \ || BAD_CHAIN(E0) || BAD_CHAIN(E1) || BAD_CHAIN(E2) || BAD_CHAIN(E3) || BAD_CHAIN(E4) || BAD_CHAIN(E5) || BAD_CHAIN(E6) || BAD_CHAIN(E7) #error "All chained TMC drivers need a CS pin." #else @@ -3753,9 +3251,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #define CS_COMPARE E7_CS_PIN #endif #define BAD_CS_PIN(A) (IN_CHAIN(A) && A##_CS_PIN != CS_COMPARE) - #if BAD_CS_PIN(X ) || BAD_CS_PIN(Y ) || BAD_CS_PIN(Z ) || BAD_CS_PIN(X2) || BAD_CS_PIN(Y2) || BAD_CS_PIN(Z2) || BAD_CS_PIN(Z3) || BAD_CS_PIN(Z4) \ - || BAD_CS_PIN(I) || BAD_CS_PIN(J) || BAD_CS_PIN(K) \ - || BAD_CS_PIN(U) || BAD_CS_PIN(V) || BAD_CS_PIN(W) \ + #if BAD_CS_PIN(X) || BAD_CS_PIN(Y) || BAD_CS_PIN(Z) || BAD_CS_PIN(I) || BAD_CS_PIN(J) || BAD_CS_PIN(K) || BAD_CS_PIN(U) || BAD_CS_PIN(V) || BAD_CS_PIN(W) \ + || BAD_CS_PIN(X2) || BAD_CS_PIN(Y2) || BAD_CS_PIN(Z2) || BAD_CS_PIN(Z3) || BAD_CS_PIN(Z4) \ || BAD_CS_PIN(E0) || BAD_CS_PIN(E1) || BAD_CS_PIN(E2) || BAD_CS_PIN(E3) || BAD_CS_PIN(E4) || BAD_CS_PIN(E5) || BAD_CS_PIN(E6) || BAD_CS_PIN(E7) #error "All chained TMC drivers must use the same CS pin." #endif @@ -3770,7 +3267,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS * Digipot requirement */ #if HAS_MOTOR_CURRENT_I2C - #if BOTH(DIGIPOT_MCP4018, DIGIPOT_MCP4451) + #if ALL(DIGIPOT_MCP4018, DIGIPOT_MCP4451) #error "Enable only one of DIGIPOT_MCP4018 or DIGIPOT_MCP4451." #elif !MB(MKS_SBASE, AZTEEG_X5_GT, AZTEEG_X5_MINI, AZTEEG_X5_MINI_WIFI) \ && (!defined(DIGIPOTS_I2C_SDA_X) || !defined(DIGIPOTS_I2C_SDA_Y) || !defined(DIGIPOTS_I2C_SDA_Z) || !defined(DIGIPOTS_I2C_SDA_E0) || !defined(DIGIPOTS_I2C_SDA_E1)) @@ -3805,9 +3302,11 @@ static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES, "DEFAULT_MAX_ACCELERATION re static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE); static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive."); -constexpr float sanity_arr_4[] = HOMING_FEEDRATE_MM_M; -static_assert(COUNT(sanity_arr_4) == NUM_AXES, "HOMING_FEEDRATE_MM_M requires " _NUM_AXES_STR "elements (and no others)."); -static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); +#if NUM_AXES + constexpr float sanity_arr_4[] = HOMING_FEEDRATE_MM_M; + static_assert(COUNT(sanity_arr_4) == NUM_AXES, "HOMING_FEEDRATE_MM_M requires " _NUM_AXES_STR "elements (and no others)."); + static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); +#endif #ifdef MAX_ACCEL_EDIT_VALUES constexpr float sanity_arr_5[] = MAX_ACCEL_EDIT_VALUES; @@ -3841,12 +3340,12 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #undef _PLUS_TEST #undef _EXTRA_NOTE -#if BOTH(CNC_COORDINATE_SYSTEMS, NO_WORKSPACE_OFFSETS) +#if ALL(CNC_COORDINATE_SYSTEMS, NO_WORKSPACE_OFFSETS) #error "CNC_COORDINATE_SYSTEMS is incompatible with NO_WORKSPACE_OFFSETS." #endif -#if !BLOCK_BUFFER_SIZE || !IS_POWER_OF_2(BLOCK_BUFFER_SIZE) - #error "BLOCK_BUFFER_SIZE must be a power of 2." +#if !BLOCK_BUFFER_SIZE + #error "BLOCK_BUFFER_SIZE must be non-zero." #elif BLOCK_BUFFER_SIZE > 64 #error "A very large BLOCK_BUFFER_SIZE is not needed and takes longer to drain the buffer on pause / cancel." #endif @@ -3877,18 +3376,18 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #endif #endif -#if BOTH(X_AXIS_TWIST_COMPENSATION, NOZZLE_AS_PROBE) +#if ALL(X_AXIS_TWIST_COMPENSATION, NOZZLE_AS_PROBE) #error "X_AXIS_TWIST_COMPENSATION is incompatible with NOZZLE_AS_PROBE." #endif #if ENABLED(POWER_LOSS_RECOVERY) #if ENABLED(BACKUP_POWER_SUPPLY) && !PIN_EXISTS(POWER_LOSS) #error "BACKUP_POWER_SUPPLY requires a POWER_LOSS_PIN." - #elif BOTH(POWER_LOSS_PULLUP, POWER_LOSS_PULLDOWN) + #elif ALL(POWER_LOSS_PULLUP, POWER_LOSS_PULLDOWN) #error "You can't enable POWER_LOSS_PULLUP and POWER_LOSS_PULLDOWN at the same time." #elif ENABLED(POWER_LOSS_RECOVER_ZHOME) && Z_HOME_TO_MAX #error "POWER_LOSS_RECOVER_ZHOME is not needed on a machine that homes to ZMAX." - #elif BOTH(IS_CARTESIAN, POWER_LOSS_RECOVER_ZHOME) && Z_HOME_TO_MIN && !defined(POWER_LOSS_ZHOME_POS) + #elif ALL(IS_CARTESIAN, POWER_LOSS_RECOVER_ZHOME) && Z_HOME_TO_MIN && !defined(POWER_LOSS_ZHOME_POS) #error "POWER_LOSS_RECOVER_ZHOME requires POWER_LOSS_ZHOME_POS for a Cartesian that homes to ZMIN." #endif #endif @@ -3950,7 +3449,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 EITHER(MARKFORGED_XY, MARKFORGED_YX) + #elif ANY(MARKFORGED_XY, MARKFORGED_YX) constexpr float backlash_arr[] = BACKLASH_DISTANCE_MM; static_assert(!backlash_arr[CORE_AXIS_1] && !backlash_arr[CORE_AXIS_2], "BACKLASH_COMPENSATION can only apply to " STRINGIFY(NORMAL_AXIS) " on a MarkForged system."); @@ -4000,11 +3499,11 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); /** * Require soft endstops for certain setups */ -#if !BOTH(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) +#if !ALL(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) #if ENABLED(DUAL_X_CARRIAGE) #error "DUAL_X_CARRIAGE requires both MIN_ and MAX_SOFTWARE_ENDSTOPS." #elif HAS_HOTEND_OFFSET - #error "MIN_ and MAX_SOFTWARE_ENDSTOPS are both required with offset hotends." + #error "Multi-hotends with offset requires both MIN_ and MAX_SOFTWARE_ENDSTOPS." #endif #endif @@ -4061,7 +3560,7 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #endif #define _PIN_CONFLICT(P) (PIN_EXISTS(P) && P##_PIN == SPINDLE_LASER_PWM_PIN) - #if BOTH(SPINDLE_FEATURE, LASER_FEATURE) + #if ALL(SPINDLE_FEATURE, LASER_FEATURE) #error "Enable only one of SPINDLE_FEATURE or LASER_FEATURE." #elif NONE(SPINDLE_SERVO, SPINDLE_LASER_USE_PWM) && !PIN_EXISTS(SPINDLE_LASER_ENA) #error "(SPINDLE|LASER)_FEATURE requires SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_USE_PWM, or SPINDLE_SERVO to control the power." @@ -4077,11 +3576,11 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #elif !(defined(SPEED_POWER_MIN) && defined(SPEED_POWER_MAX) && defined(SPEED_POWER_STARTUP)) #error "SPINDLE_LASER_USE_PWM equation constant(s) missing." #elif _PIN_CONFLICT(X_MIN) - #error "SPINDLE_LASER_USE_PWM pin conflicts with X_MIN_PIN." + #error "SPINDLE_LASER_PWM_PIN conflicts with X_MIN_PIN." #elif _PIN_CONFLICT(X_MAX) - #error "SPINDLE_LASER_USE_PWM pin conflicts with X_MAX_PIN." + #error "SPINDLE_LASER_PWM_PIN conflicts with X_MAX_PIN." #elif _PIN_CONFLICT(Z_STEP) - #error "SPINDLE_LASER_USE_PWM pin conflicts with Z_STEP_PIN." + #error "SPINDLE_LASER_PWM_PIN conflicts with Z_STEP_PIN." #elif _PIN_CONFLICT(CASE_LIGHT) #error "SPINDLE_LASER_PWM_PIN conflicts with CASE_LIGHT_PIN." #elif _PIN_CONFLICT(E0_AUTO_FAN) @@ -4100,8 +3599,8 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #error "SPINDLE_LASER_PWM_PIN conflicts with E6_AUTO_FAN_PIN." #elif _PIN_CONFLICT(E7_AUTO_FAN) #error "SPINDLE_LASER_PWM_PIN conflicts with E7_AUTO_FAN_PIN." - #elif _PIN_CONFLICT(FAN) - #error "SPINDLE_LASER_PWM_PIN conflicts with FAN_PIN." + #elif _PIN_CONFLICT(FAN0) + #error "SPINDLE_LASER_PWM_PIN conflicts with FAN0_PIN." #elif _PIN_CONFLICT(FAN1) #error "SPINDLE_LASER_PWM_PIN conflicts with FAN1_PIN." #elif _PIN_CONFLICT(FAN2) @@ -4129,15 +3628,19 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #undef _PIN_CONFLICT #ifdef LASER_SAFETY_TIMEOUT_MS - static_assert(LASER_SAFETY_TIMEOUT_MS < (DEFAULT_STEPPER_DEACTIVE_TIME) * 1000UL, "LASER_SAFETY_TIMEOUT_MS must be less than DEFAULT_STEPPER_DEACTIVE_TIME (" STRINGIFY(DEFAULT_STEPPER_DEACTIVE_TIME) " seconds)"); + static_assert(LASER_SAFETY_TIMEOUT_MS < (DEFAULT_STEPPER_TIMEOUT_SEC) * 1000UL, "LASER_SAFETY_TIMEOUT_MS must be less than DEFAULT_STEPPER_TIMEOUT_SEC (" STRINGIFY(DEFAULT_STEPPER_TIMEOUT_SEC) " seconds)"); #endif #endif -#if ENABLED(COOLANT_MIST) && !PIN_EXISTS(COOLANT_MIST) - #error "COOLANT_MIST requires COOLANT_MIST_PIN to be defined." -#elif ENABLED(COOLANT_FLOOD) && !PIN_EXISTS(COOLANT_FLOOD) - #error "COOLANT_FLOOD requires COOLANT_FLOOD_PIN to be defined." +#if ENABLED(COOLANT_CONTROL) + #if NONE(COOLANT_MIST, COOLANT_FLOOD) + #error "COOLANT_CONTROL requires either COOLANT_MIST or COOLANT_FLOOD." + #elif ENABLED(COOLANT_MIST) && !PIN_EXISTS(COOLANT_MIST) + #error "COOLANT_MIST requires COOLANT_MIST_PIN to be defined." + #elif ENABLED(COOLANT_FLOOD) && !PIN_EXISTS(COOLANT_FLOOD) + #error "COOLANT_FLOOD requires COOLANT_FLOOD_PIN to be defined." + #endif #endif #if HAS_ADC_BUTTONS && defined(ADC_BUTTON_DEBOUNCE_DELAY) && ADC_BUTTON_DEBOUNCE_DELAY < 16 @@ -4168,12 +3671,20 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); /** * Sanity check WiFi options */ -#if ENABLED(ESP3D_WIFISUPPORT) && DISABLED(ARDUINO_ARCH_ESP32) - #error "ESP3D_WIFISUPPORT requires an ESP32 MOTHERBOARD." -#elif ENABLED(WEBSUPPORT) && NONE(ARDUINO_ARCH_ESP32, WIFISUPPORT) - #error "WEBSUPPORT requires WIFISUPPORT and an ESP32 MOTHERBOARD." -#elif BOTH(ESP3D_WIFISUPPORT, WIFISUPPORT) - #error "Enable only one of ESP3D_WIFISUPPORT or WIFISUPPORT." +#if ALL(WIFISUPPORT, ESP3D_WIFISUPPORT) + #error "Enable only one of WIFISUPPORT or ESP3D_WIFISUPPORT." +#elif ENABLED(ESP3D_WIFISUPPORT) && DISABLED(ARDUINO_ARCH_ESP32) + #error "ESP3D_WIFISUPPORT requires an ESP32 motherboard." +#elif ALL(ARDUINO_ARCH_ESP32, WIFISUPPORT) + #if !(defined(WIFI_SSID) && defined(WIFI_PWD)) + #error "ESP32 motherboard with WIFISUPPORT requires WIFI_SSID and WIFI_PWD." + #endif +#elif ENABLED(WIFI_CUSTOM_COMMAND) + #error "WIFI_CUSTOM_COMMAND requires an ESP32 motherboard and WIFISUPPORT." +#elif ENABLED(OTASUPPORT) + #error "OTASUPPORT requires an ESP32 motherboard and WIFISUPPORT." +#elif defined(WIFI_SSID) || defined(WIFI_PWD) + #error "WIFI_SSID and WIFI_PWD only apply to ESP32 motherboard with WIFISUPPORT." #endif /** @@ -4190,14 +3701,14 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); /** * Sanity Check for MEATPACK and BINARY_FILE_TRANSFER Features */ -#if BOTH(HAS_MEATPACK, BINARY_FILE_TRANSFER) +#if ALL(HAS_MEATPACK, BINARY_FILE_TRANSFER) #error "Either enable MEATPACK_ON_SERIAL_PORT_* or BINARY_FILE_TRANSFER, not both." #endif /** * Sanity Check for Slim LCD Menus and Probe Offset Wizard */ -#if BOTH(SLIM_LCD_MENUS, PROBE_OFFSET_WIZARD) +#if ALL(SLIM_LCD_MENUS, PROBE_OFFSET_WIZARD) #error "SLIM_LCD_MENUS disables \"Advanced Settings > Probe Offsets > PROBE_OFFSET_WIZARD.\"" #endif @@ -4219,7 +3730,7 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); /** * Sanity check for MIXING_EXTRUDER & DISTINCT_E_FACTORS these are not compatible */ -#if BOTH(MIXING_EXTRUDER, DISTINCT_E_FACTORS) +#if ALL(MIXING_EXTRUDER, DISTINCT_E_FACTORS) #error "MIXING_EXTRUDER can't be used with DISTINCT_E_FACTORS. But you may use SINGLENOZZLE with DISTINCT_E_FACTORS." #endif @@ -4332,14 +3843,14 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #endif // Check requirements for upload.py -#if ENABLED(XFER_BUILD) && !BOTH(BINARY_FILE_TRANSFER, CUSTOM_FIRMWARE_UPLOAD) - #error "BINARY_FILE_TRANSFER and CUSTOM_FIRMWARE_UPLOAD are required for custom upload." +#if ENABLED(XFER_BUILD) && !ALL(SDSUPPORT, BINARY_FILE_TRANSFER, CUSTOM_FIRMWARE_UPLOAD) + #error "SDSUPPORT, BINARY_FILE_TRANSFER, and CUSTOM_FIRMWARE_UPLOAD are required for custom upload." #endif /** * Input Shaping requirements */ -#if HAS_SHAPING +#if HAS_ZV_SHAPING #if ENABLED(DELTA) #error "Input Shaping is not compatible with DELTA kinematics." #elif ENABLED(SCARA) @@ -4352,12 +3863,12 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #error "Input Shaping is not compatible with POLARGRAPH kinematics." #elif ENABLED(DIRECT_STEPPING) #error "Input Shaping is not compatible with DIRECT_STEPPING." - #elif BOTH(INPUT_SHAPING_X, CORE_IS_XZ) + #elif ALL(INPUT_SHAPING_X, CORE_IS_XZ) #error "INPUT_SHAPING_X is not supported with COREXZ." - #elif BOTH(INPUT_SHAPING_Y, CORE_IS_YZ) + #elif ALL(INPUT_SHAPING_Y, CORE_IS_YZ) #error "INPUT_SHAPING_Y is not supported with COREYZ." #elif ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) - #if !BOTH(INPUT_SHAPING_X, INPUT_SHAPING_Y) + #if !ALL(INPUT_SHAPING_X, INPUT_SHAPING_Y) #error "INPUT_SHAPING_X and INPUT_SHAPING_Y must both be enabled for COREXY, COREYX, or MARKFORGED_*." #else static_assert(SHAPING_FREQ_X == SHAPING_FREQ_Y, "SHAPING_FREQ_X and SHAPING_FREQ_Y must be the same for COREXY / COREYX / MARKFORGED_*."); diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index f2aa547135d8..8a249c4d2ea8 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -25,7 +25,7 @@ * Release version. Leave the Marlin version or apply a custom scheme. */ #ifndef SHORT_BUILD_VERSION - #define SHORT_BUILD_VERSION "2.1.2.1" + #define SHORT_BUILD_VERSION "2.1.2.2" #endif /** @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-05-16" + #define STRING_DISTRIBUTION_DATE "2024-02-08" #endif /** @@ -52,7 +52,7 @@ * to alert users to major changes. */ -#define MARLIN_HEX_VERSION 02010201 +#define MARLIN_HEX_VERSION 02010202 #ifndef REQUIRED_CONFIGURATION_H_VERSION #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION #endif diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index 9b3d69860736..8c5494060f51 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -33,6 +33,13 @@ #if ENABLED(MARLIN_DEV_MODE) #warning "WARNING! Disable MARLIN_DEV_MODE for the final build!" + #ifdef __LONG_MAX__ + #if __LONG_MAX__ > __INT_MAX__ + #warning "The 'long' type is larger than the 'int' type on this platform." + #else + #warning "The 'long' type is the same as the 'int' type on this platform." + #endif + #endif #endif #if ENABLED(LA_DEBUG) @@ -749,17 +756,17 @@ /** * FYSETC/MKS/BTT Mini Panel backlighting */ -#if EITHER(FYSETC_242_OLED_12864, FYSETC_MINI_12864_2_1) && !ALL(NEOPIXEL_LED, LED_CONTROL_MENU, LED_USER_PRESET_STARTUP, LED_COLOR_PRESETS) +#if ANY(FYSETC_242_OLED_12864, FYSETC_MINI_12864_2_1) && !ALL(NEOPIXEL_LED, LED_CONTROL_MENU, LED_USER_PRESET_STARTUP, LED_COLOR_PRESETS) #warning "Your FYSETC/MKS/BTT Mini Panel works best with NEOPIXEL_LED, LED_CONTROL_MENU, LED_USER_PRESET_STARTUP, and LED_COLOR_PRESETS." #endif -#if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) && DISABLED(RGB_LED) +#if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) && DISABLED(RGB_LED) #warning "Your FYSETC Mini Panel works best with RGB_LED." -#elif EITHER(FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1) && DISABLED(LED_USER_PRESET_STARTUP) +#elif ANY(FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1) && DISABLED(LED_USER_PRESET_STARTUP) #warning "Your FYSETC Mini Panel works best with LED_USER_PRESET_STARTUP." #endif -#if EITHER(FYSETC_242_OLED_12864, FYSETC_MINI_12864) && BOTH(PSU_CONTROL, HAS_COLOR_LEDS) && !LED_POWEROFF_TIMEOUT +#if ANY(FYSETC_242_OLED_12864, FYSETC_MINI_12864) && ALL(PSU_CONTROL, HAS_COLOR_LEDS) && !LED_POWEROFF_TIMEOUT #warning "Your FYSETC display with PSU_CONTROL works best with LED_POWEROFF_TIMEOUT." #endif @@ -794,6 +801,30 @@ /** * Input Shaping */ -#if HAS_SHAPING && ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) +#if HAS_ZV_SHAPING && ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) #warning "Input Shaping for CORE / MARKFORGED kinematic axes is still experimental." #endif + +/** + * SD Card extras + */ +#if SDSORT_CACHE_VFATS_WARNING + #warning "SDSORT_CACHE_VFATS has been reduced to VFAT_ENTRIES_LIMIT." +#endif +#if SDSORT_CACHE_LPC1768_WARNING + #warning "SDCARD_SORT_ALPHA sub-options overridden for LPC1768 with DOGM LCD SCK overlap." +#endif + +/** + * Ender-5 S1 bootloader + */ +#ifdef STM32F4_UPDATE_FOLDER + #warning "Place the firmware bin file in a folder named 'STM32F4_UPDATE' on the SD card. Install with 'M936 V2'." +#endif + +/** + * ProUI Boot Screen Duration + */ +#if ENABLED(DWIN_LCD_PROUI) && BOOTSCREEN_TIMEOUT > 2000 + #warning "For ProUI the original BOOTSCREEN_TIMEOUT of 1100 is recommended." +#endif diff --git a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp index 48f5f97133db..dd1ba06a7832 100644 --- a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp +++ b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp @@ -449,7 +449,6 @@ static const hd44780_charmap_t g_hd44780_charmap_device[] PROGMEM = { {IV('⭢'), 0xC7, 0}, {IV('⭣'), 0xC6, 0}, - {IV('⯆'), 0xF5, 0}, {IV('⯇'), 0xF7, 0}, // ⯅ {IV('⯈'), 0xF6, 0}, @@ -500,7 +499,6 @@ static const hd44780_charmap_t g_hd44780_charmap_device[] PROGMEM = { //{IV(''), 0x9E, 0}, //{IV(''), 0x9F, 0}, - {IV('¼'), 0xF0, 0}, // 00BC {IV('⅓'), 0xF1, 0}, {IV('½'), 0xF2, 0}, // 00BD @@ -1043,7 +1041,7 @@ int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { * @param cb_read_byte : the callback function to read one byte from the utf8_str (from RAM or ROM) * @param max_length : the pixel length of the string allowed (or number of slots in HD44780) * - * @return the number of pixels advanced + * @return the number of characters emitted * * Draw a UTF-8 string */ diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 8817ad74ad50..7585ba95631a 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -41,12 +41,12 @@ #include "../../module/planner.h" #include "../../module/motion.h" -#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) +#if DISABLED(LCD_PROGRESS_BAR) && ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) #include "../../feature/filwidth.h" #include "../../gcode/parser.h" #endif -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "../../feature/cooler.h" #endif @@ -70,7 +70,7 @@ LCD_CLASS lcd(LCD_I2C_ADDRESS, LCD_I2C_PIN_EN, LCD_I2C_PIN_RW, LCD_I2C_PIN_RS, LCD_I2C_PIN_D4, LCD_I2C_PIN_D5, LCD_I2C_PIN_D6, LCD_I2C_PIN_D7); -#elif EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) +#elif ANY(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) LCD_CLASS lcd(LCD_I2C_ADDRESS OPTARG(DETECT_I2C_LCD_DEVICE, 1)); @@ -81,7 +81,7 @@ #elif ENABLED(SR_LCD_2W_NL) // 2 wire Non-latching LCD SR from: - // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection + // https://github.com/fmalpartida/New-LiquidCrystal/wiki/schematics#user-content-ShiftRegister_connection LCD_CLASS lcd(SR_DATA_PIN, SR_CLK_PIN #if PIN_EXISTS(SR_STROBE) @@ -103,18 +103,18 @@ #elif ENABLED(YHCB2004) - LCD_CLASS lcd(YHCB2004_CLK, 20, 4, YHCB2004_MOSI, YHCB2004_MISO); // CLK, cols, rows, MOSI, MISO + LCD_CLASS lcd(YHCB2004_SCK_PIN, 20, 4, YHCB2004_MOSI_PIN, YHCB2004_MISO_PIN); // CLK, cols, rows, MOSI, MISO #else // Standard direct-connected LCD implementations - LCD_CLASS lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5, LCD_PINS_D6, LCD_PINS_D7); + LCD_CLASS lcd(LCD_PINS_RS, LCD_PINS_EN, LCD_PINS_D4, LCD_PINS_D5, LCD_PINS_D6, LCD_PINS_D7); #endif static void createChar_P(const char c, const byte * const ptr) { byte temp[8]; - LOOP_L_N(i, 8) + for (uint8_t i = 0; i < 8; ++i) temp[i] = pgm_read_byte(&ptr[i]); lcd.createChar(c, temp); } @@ -289,7 +289,7 @@ void MarlinUI::set_custom_characters(const HD44780CharSet screen_charset/*=CHARS #endif // LCD_PROGRESS_BAR - #if BOTH(SDSUPPORT, HAS_MARLINUI_MENU) + #if ALL(HAS_MEDIA, HAS_MARLINUI_MENU) // CHARSET_MENU const static PROGMEM byte refresh[8] = { @@ -313,7 +313,7 @@ void MarlinUI::set_custom_characters(const HD44780CharSet screen_charset/*=CHARS B00000 }; - #endif // SDSUPPORT + #endif // HAS_MEDIA #if ENABLED(SHOW_BOOTSCREEN) // Set boot screen corner characters @@ -339,7 +339,7 @@ void MarlinUI::set_custom_characters(const HD44780CharSet screen_charset/*=CHARS #endif { createChar_P(LCD_STR_UPLEVEL[0], uplevel); - #if BOTH(SDSUPPORT, HAS_MARLINUI_MENU) + #if ALL(HAS_MEDIA, HAS_MARLINUI_MENU) // SD Card sub-menu special characters createChar_P(LCD_STR_REFRESH[0], refresh); createChar_P(LCD_STR_FOLDER[0], folder); @@ -424,7 +424,7 @@ void MarlinUI::clear_lcd() { lcd.clear(); } else { PGM_P p = FTOP(ftxt); int dly = time / _MAX(slen, 1); - LOOP_LE_N(i, slen) { + for (uint8_t i = 0; i <= slen; ++i) { // Print the text at the correct place lcd_put_u8str_max_P(col, line, p, len); @@ -521,7 +521,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const else if (axis_should_home(axis)) while (const char c = *value++) lcd_put_lchar(c <= '.' ? c : '?'); else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis)) - lcd_put_u8str(axis == Z_AXIS ? F(" ") : F(" ")); + lcd_put_u8str(TERN0(HAS_Z_AXIS, axis == Z_AXIS) ? F(" ") : F(" ")); else lcd_put_u8str(value); } @@ -537,7 +537,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const */ FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char prefix, const bool blink) { #if HAS_HEATED_BED - const bool isBed = TERN(HAS_HEATED_CHAMBER, heater_id == H_BED, heater_id < 0); + const bool isBed = heater_id == H_BED; const celsius_t t1 = (isBed ? thermalManager.wholeDegBed() : thermalManager.wholeDegHotend(heater_id)), t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater_id)); #else @@ -546,7 +546,17 @@ FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char pr if (prefix >= 0) lcd_put_lchar(prefix); - lcd_put_u8str(t1 < 0 ? "err" : i16tostr3rj(t1)); + if (t1 >= 0) + lcd_put_u8str(ui16tostr3rj(t1)); + else { + #if ENABLED(SHOW_TEMPERATURE_BELOW_ZERO) + char * const str = i16tostr3rj(t1); + lcd_put_u8str(&str[1]); + #else + lcd_put_u8str(F("err")); + #endif + } + lcd_put_u8str(F("/")); #if !HEATER_IDLE_HANDLER @@ -687,7 +697,7 @@ void MarlinUI::draw_status_message(const bool blink) { if (progress > 2) return draw_progress_bar(progress); } - #elif BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #elif ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) // Alternate Status message and Filament display if (ELAPSED(millis(), next_filament_display)) { @@ -699,7 +709,7 @@ void MarlinUI::draw_status_message(const bool blink) { return; } - #endif // FILAMENT_LCD_DISPLAY && SDSUPPORT + #endif // FILAMENT_LCD_DISPLAY && HAS_MEDIA #if ENABLED(STATUS_MESSAGE_SCROLLING) static bool last_blink = false; @@ -758,12 +768,14 @@ void MarlinUI::draw_status_message(const bool blink) { } #if HAS_PRINT_PROGRESS + #define TPOFFSET (LCD_WIDTH - 1) static uint8_t timepos = TPOFFSET - 6; static char buffer[8]; - static lcd_uint_t pc, pr; #if ENABLED(SHOW_PROGRESS_PERCENT) + static lcd_uint_t pc = 0, pr = 2; + inline void setPercentPos(const lcd_uint_t c, const lcd_uint_t r) { pc = c; pr = r; } void MarlinUI::drawPercent() { const uint8_t progress = ui.get_progress_percent(); if (progress) { @@ -774,6 +786,7 @@ void MarlinUI::draw_status_message(const bool blink) { } } #endif + #if ENABLED(SHOW_REMAINING_TIME) void MarlinUI::drawRemain() { if (printJobOngoing()) { @@ -785,6 +798,7 @@ void MarlinUI::draw_status_message(const bool blink) { } } #endif + #if ENABLED(SHOW_INTERACTION_TIME) void MarlinUI::drawInter() { const duration_t interactt = ui.interaction_time; @@ -796,6 +810,7 @@ void MarlinUI::draw_status_message(const bool blink) { } } #endif + #if ENABLED(SHOW_ELAPSED_TIME) void MarlinUI::drawElapsed() { if (printJobOngoing()) { @@ -807,6 +822,7 @@ void MarlinUI::draw_status_message(const bool blink) { } } #endif + #endif // HAS_PRINT_PROGRESS /** @@ -921,7 +937,7 @@ void MarlinUI::draw_status_screen() { #if LCD_WIDTH < 20 #if HAS_PRINT_PROGRESS - pc = 0; pr = 2; + TERN_(SHOW_PROGRESS_PERCENT, setPercentPos(0, 2)); rotate_progress(); #endif @@ -947,25 +963,25 @@ void MarlinUI::draw_status_screen() { // Two-component mix / gradient instead of XY - char mixer_messages[12]; - const char *mix_label; + char mixer_messages[15]; + PGM_P mix_label; #if ENABLED(GRADIENT_MIX) if (mixer.gradient.enabled) { mixer.update_mix_from_gradient(); - mix_label = "Gr"; + mix_label = PSTR("Gr"); } else #endif { mixer.update_mix_from_vtool(); - mix_label = "Mx"; + mix_label = PSTR("Mx"); } - sprintf_P(mixer_messages, PSTR("%s %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); + sprintf_P(mixer_messages, PSTR(S_FMT " %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); lcd_put_u8str(mixer_messages); #else // !HAS_DUAL_MIXING - const bool show_e_total = TERN0(LCD_SHOW_E_TOTAL, printingIsActive()); + const bool show_e_total = TERN1(HAS_X_AXIS, TERN0(LCD_SHOW_E_TOTAL, printingIsActive())); if (show_e_total) { #if ENABLED(LCD_SHOW_E_TOTAL) @@ -976,10 +992,14 @@ void MarlinUI::draw_status_screen() { #endif } else { - const xy_pos_t lpos = current_position.asLogical(); - _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink); - lcd_put_u8str(F(" ")); - _draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink); + #if HAS_X_AXIS + const xy_pos_t lpos = current_position.asLogical(); + _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink); + #endif + #if HAS_Y_AXIS + TERN_(HAS_X_AXIS, lcd_put_u8str(F(" "))); + _draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink); + #endif } #endif // !HAS_DUAL_MIXING @@ -988,11 +1008,12 @@ void MarlinUI::draw_status_screen() { #endif // LCD_WIDTH >= 20 - lcd_moveto(LCD_WIDTH - 8, 1); - _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink); - - #if HAS_LEVELING && !HAS_HEATED_BED - lcd_put_lchar(planner.leveling_active || blink ? '_' : ' '); + #if HAS_Z_AXIS + lcd_moveto(LCD_WIDTH - 8, 1); + _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink); + #if HAS_LEVELING && !HAS_HEATED_BED + lcd_put_lchar(planner.leveling_active || blink ? '_' : ' '); + #endif #endif #endif // LCD_HEIGHT > 2 @@ -1008,14 +1029,14 @@ void MarlinUI::draw_status_screen() { #if LCD_WIDTH >= 20 #if HAS_PRINT_PROGRESS - pc = 6; pr = 2; + TERN_(SHOW_PROGRESS_PERCENT, setPercentPos(6, 2)); rotate_progress(); #else char c; uint16_t per; #if HAS_FAN0 if (true - #if BOTH(HAS_EXTRUDERS, ADAPTIVE_FAN_SLOWING) + #if ALL(HAS_EXTRUDERS, ADAPTIVE_FAN_SLOWING) && (blink || thermalManager.fan_speed_scaler[0] < 128) #endif ) { @@ -1054,8 +1075,10 @@ void MarlinUI::draw_status_screen() { // // Z Coordinate // - lcd_moveto(LCD_WIDTH - 9, 0); - _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink); + #if HAS_Z_AXIS + lcd_moveto(LCD_WIDTH - 9, 0); + _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink); + #endif #if HAS_LEVELING && (HAS_MULTI_HOTEND || !HAS_HEATED_BED) lcd_put_lchar(LCD_WIDTH - 1, 0, planner.leveling_active || blink ? '_' : ' '); @@ -1089,7 +1112,7 @@ void MarlinUI::draw_status_screen() { _draw_bed_status(blink); #elif HAS_PRINT_PROGRESS #define DREW_PRINT_PROGRESS 1 - pc = 0; pr = 2; + TERN_(SHOW_PROGRESS_PERCENT, setPercentPos(0, 2)); rotate_progress(); #endif @@ -1097,7 +1120,7 @@ void MarlinUI::draw_status_screen() { // All progress strings // #if HAS_PRINT_PROGRESS && !DREW_PRINT_PROGRESS - pc = LCD_WIDTH - 9; pr = 2; + TERN_(SHOW_PROGRESS_PERCENT, setPercentPos(LCD_WIDTH - 9, 2)); rotate_progress(); #endif #endif // LCD_INFO_SCREEN_STYLE 1 @@ -1186,7 +1209,7 @@ void MarlinUI::draw_status_screen() { } } - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA void MenuItem_sdbase::draw(const bool sel, const uint8_t row, FSTR_P const, CardReader &theCard, const bool isDir) { lcd_put_lchar(0, row, sel ? LCD_STR_ARROW_RIGHT[0] : ' '); diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.h b/Marlin/src/lcd/HD44780/marlinui_HD44780.h index 62c0c7620220..b83454845680 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.h +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.h @@ -70,7 +70,7 @@ #elif ENABLED(SR_LCD_2W_NL) // 2 wire Non-latching LCD SR from: - // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection + // https://github.com/fmalpartida/New-LiquidCrystal/wiki/schematics#user-content-ShiftRegister_connection #include #include #define LCD_CLASS LiquidCrystal_SR @@ -103,5 +103,5 @@ #endif -#include "../fontutils.h" +#include "../utf8.h" #include "../lcdprint.h" diff --git a/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp index e681ff0a9170..c0b9975014d1 100644 --- a/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp @@ -446,7 +446,6 @@ static const TFTGLCD_charmap_t g_TFTGLCD_charmap_device[] PROGMEM = { {IV('⭢'), 0xC7, 0}, {IV('⭣'), 0xC6, 0}, - {IV('⯆'), 0xF5, 0}, {IV('⯇'), 0xF7, 0}, // ⯅ {IV('⯈'), 0xF6, 0}, @@ -1041,7 +1040,7 @@ int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { * @param cb_read_byte : the callback function to read one byte from the utf8_str (from RAM or ROM) * @param max_length : the pixel length of the string allowed (or number of slots in HD44780) * - * @return the number of pixels advanced + * @return the number of characters emitted * * Draw a UTF-8 string */ diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index f87d76cef78c..b1068982925c 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -52,12 +52,12 @@ #include "../../module/planner.h" #include "../../module/motion.h" -#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) +#if DISABLED(LCD_PROGRESS_BAR) && ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) #include "../../feature/filwidth.h" #include "../../gcode/parser.h" #endif -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "../../feature/cooler.h" #endif @@ -141,7 +141,7 @@ static uint8_t PanelDetected = 0; #if ANY(__AVR__, TARGET_LPC1768, __STM32F1__, ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) #define SPI_SEND_ONE(V) SPI.transfer(V); #define SPI_SEND_TWO(V) SPI.transfer16(V); -#elif EITHER(STM32F4xx, STM32F1xx) +#elif ANY(STM32F4xx, STM32F1xx) #define SPI_SEND_ONE(V) SPI.transfer(V, SPI_CONTINUE); #define SPI_SEND_TWO(V) SPI.transfer16(V, SPI_CONTINUE); #elif defined(ARDUINO_ARCH_ESP32) @@ -151,7 +151,7 @@ static uint8_t PanelDetected = 0; #if ANY(__AVR__, ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) #define SPI_SEND_SOME(V,L,Z) SPI.transfer(&V[Z], L); -#elif EITHER(STM32F4xx, STM32F1xx) +#elif ANY(STM32F4xx, STM32F1xx) #define SPI_SEND_SOME(V,L,Z) SPI.transfer(&V[Z], L, SPI_CONTINUE); #elif ANY(TARGET_LPC1768, __STM32F1__, ARDUINO_ARCH_ESP32) #define SPI_SEND_SOME(V,L,Z) do{ for (uint16_t i = 0; i < L; i++) SPI_SEND_ONE(V[(Z)+i]); }while(0) @@ -290,7 +290,7 @@ uint8_t MarlinUI::read_slow_buttons() { Wire.requestFrom((uint8_t)LCD_I2C_ADDRESS, 2, 0, 0, 1); #elif defined(STM32F1) Wire.requestFrom((uint8_t)LCD_I2C_ADDRESS, (uint8_t)2); - #elif EITHER(STM32F4xx, TARGET_LPC1768) + #elif ANY(STM32F4xx, TARGET_LPC1768) Wire.requestFrom(LCD_I2C_ADDRESS, 2); #endif encoderDiff += Wire.read(); @@ -596,8 +596,8 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #endif // HAS_CUTTER - #if HAS_PRINT_PROGRESS // UNTESTED!!! + #define TPOFFSET (LCD_WIDTH - 1) static uint8_t timepos = TPOFFSET - 6; @@ -648,6 +648,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const } } #endif + #endif // HAS_PRINT_PROGRESS #if ENABLED(LCD_PROGRESS_BAR) @@ -672,7 +673,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const void MarlinUI::draw_status_message(const bool blink) { if (!PanelDetected) return; lcd_moveto(0, 3); - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #if ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) // Alternate Status message and Filament display if (ELAPSED(millis(), next_filament_display)) { @@ -689,7 +690,7 @@ void MarlinUI::draw_status_message(const bool blink) { return; } - #endif // FILAMENT_LCD_DISPLAY && SDSUPPORT + #endif // FILAMENT_LCD_DISPLAY && HAS_MEDIA // Get the UTF8 character count of the string uint8_t slen = utf8_strlen(status_message); @@ -863,20 +864,20 @@ void MarlinUI::draw_status_screen() { #if DUAL_MIXING_EXTRUDER lcd_moveto(0, 4); // Two-component mix / gradient instead of XY - char mixer_messages[12]; - const char *mix_label; + char mixer_messages[15]; + PGM_P mix_label; #if ENABLED(GRADIENT_MIX) if (mixer.gradient.enabled) { mixer.update_mix_from_gradient(); - mix_label = "Gr"; + mix_label = PSTR("Gr"); } else #endif { mixer.update_mix_from_vtool(); - mix_label = "Mx"; + mix_label = PSTR("Mx"); } - sprintf_P(mixer_messages, PSTR("%s %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); + sprintf_P(mixer_messages, PSTR(S_FMT " %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); lcd_put_u8str(mixer_messages); #endif #endif @@ -1037,7 +1038,7 @@ void MarlinUI::draw_status_screen() { lcd.print_line(); } - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA void MenuItem_sdbase::draw(const bool sel, const uint8_t row, FSTR_P const, CardReader &theCard, const bool isDir) { if (!PanelDetected) return; @@ -1050,7 +1051,7 @@ void MarlinUI::draw_status_screen() { lcd.print_line(); } - #endif // SDSUPPORT + #endif // HAS_MEDIA #if ENABLED(LCD_HAS_STATUS_INDICATORS) diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.h b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.h index c399b907e460..3e447fa19617 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.h +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.h @@ -57,7 +57,6 @@ class TFTGLCD { extern TFTGLCD lcd; -#include "../fontutils.h" #include "../lcdprint.h" // Use panel encoder - free old encoder pins diff --git a/Marlin/src/lcd/buttons.h b/Marlin/src/lcd/buttons.h index 58471239bbfb..601e8a70ae05 100644 --- a/Marlin/src/lcd/buttons.h +++ b/Marlin/src/lcd/buttons.h @@ -38,7 +38,7 @@ #define HAS_SLOW_BUTTONS 1 #endif -#if EITHER(HAS_DIGITAL_BUTTONS, HAS_DWIN_E3V2) +#if ANY(HAS_DIGITAL_BUTTONS, HAS_DWIN_E3V2) // Wheel spin pins where BA is 00, 10, 11, 01 (1 bit always changes) #define BLEN_A 0 #define BLEN_B 1 @@ -149,7 +149,7 @@ #ifndef EN_C #define EN_C 0 #endif -#if BUTTON_EXISTS(BACK) || EITHER(HAS_TOUCH_BUTTONS, IS_TFTGLCD_PANEL) +#if BUTTON_EXISTS(BACK) || ANY(HAS_TOUCH_BUTTONS, IS_TFTGLCD_PANEL) #define BLEN_D 3 #define EN_D _BV(BLEN_D) #else diff --git a/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h b/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h index 28ca26134e16..f07064ea7165 100644 --- a/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h +++ b/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h @@ -31,12 +31,12 @@ extern u8g_dev_t u8g_dev_st7565_64128n_HAL_2x_hw_spi; class U8GLIB_64128N_2X_HAL : public U8GLIB { public: U8GLIB_64128N_2X_HAL() : U8GLIB() { } - U8GLIB_64128N_2X_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { init(sck, mosi, cs, a0, reset); } - U8GLIB_64128N_2X_HAL(pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { init(cs, a0, reset); } - void init(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { + U8GLIB_64128N_2X_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { init(sck, mosi, cs, a0, reset); } + U8GLIB_64128N_2X_HAL(pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { init(cs, a0, reset); } + void init(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_st7565_64128n_HAL_2x_sw_spi, (uint8_t)sck, (uint8_t)mosi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset); } - void init(pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { + void init(pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_st7565_64128n_HAL_2x_hw_spi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset); } }; @@ -47,12 +47,12 @@ extern u8g_dev_t u8g_dev_st7920_128x64_HAL_4x_hw_spi; class U8GLIB_ST7920_128X64_4X_HAL : public U8GLIB { public: U8GLIB_ST7920_128X64_4X_HAL() : U8GLIB() { } - U8GLIB_ST7920_128X64_4X_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t reset = U8G_PIN_NONE) { init(sck, mosi, cs, reset); } - U8GLIB_ST7920_128X64_4X_HAL(pin_t cs, pin_t reset = U8G_PIN_NONE) { init(cs, reset); } - void init(pin_t sck, pin_t mosi, pin_t cs, pin_t reset = U8G_PIN_NONE) { + U8GLIB_ST7920_128X64_4X_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t reset=U8G_PIN_NONE) { init(sck, mosi, cs, reset); } + U8GLIB_ST7920_128X64_4X_HAL(pin_t cs, pin_t reset=U8G_PIN_NONE) { init(cs, reset); } + void init(pin_t sck, pin_t mosi, pin_t cs, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_st7920_128x64_HAL_4x_sw_spi, (uint8_t)sck, (uint8_t)mosi, (uint8_t)cs, U8G_PIN_NONE, (uint8_t)reset); // a0 = U8G_PIN_NONE } - void init(pin_t cs, pin_t reset = U8G_PIN_NONE) { + void init(pin_t cs, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_st7920_128x64_HAL_4x_hw_spi, (uint8_t)cs, U8G_PIN_NONE, (uint8_t)reset); // a0 = U8G_PIN_NONE } }; @@ -66,8 +66,8 @@ extern u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi; class U8GLIB_ST7920_128X64_RRD : public U8GLIB { public: U8GLIB_ST7920_128X64_RRD() : U8GLIB() { } - U8GLIB_ST7920_128X64_RRD(pin_t sck, pin_t mosi, pin_t cs, pin_t reset = U8G_PIN_NONE) { init(sck, mosi, cs, reset); } - void init(pin_t sck, pin_t mosi, pin_t cs, pin_t reset = U8G_PIN_NONE) { + U8GLIB_ST7920_128X64_RRD(pin_t sck, pin_t mosi, pin_t cs, pin_t reset=U8G_PIN_NONE) { init(sck, mosi, cs, reset); } + void init(pin_t sck, pin_t mosi, pin_t cs, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_st7920_128x64_rrd_sw_spi, (uint8_t)sck, (uint8_t)mosi, (uint8_t)cs, U8G_PIN_NONE, (uint8_t)reset); // a0 = U8G_PIN_NONE } }; @@ -99,22 +99,21 @@ extern u8g_dev_t u8g_dev_tft_320x240_upscale_from_128x64; class U8GLIB_TFT_320X240_UPSCALE_FROM_128X64 : public U8GLIB { public: U8GLIB_TFT_320X240_UPSCALE_FROM_128X64() : U8GLIB() { } - U8GLIB_TFT_320X240_UPSCALE_FROM_128X64(uint8_t cs, uint8_t rs, uint8_t reset = U8G_PIN_NONE) { init(cs, rs, reset); } - void init(uint8_t cs, uint8_t rs, uint8_t reset = U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_tft_320x240_upscale_from_128x64, cs, rs, reset); } + U8GLIB_TFT_320X240_UPSCALE_FROM_128X64(uint8_t cs, uint8_t rs, uint8_t reset=U8G_PIN_NONE) { init(cs, rs, reset); } + void init(uint8_t cs, uint8_t rs, uint8_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_tft_320x240_upscale_from_128x64, cs, rs, reset); } }; - extern u8g_dev_t u8g_dev_uc1701_mini12864_HAL_2x_sw_spi, u8g_dev_uc1701_mini12864_HAL_2x_hw_spi; class U8GLIB_MINI12864_2X_HAL : public U8GLIB { public: U8GLIB_MINI12864_2X_HAL() : U8GLIB() { } - U8GLIB_MINI12864_2X_HAL(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE) { init(sck, mosi, cs, a0, reset); } - U8GLIB_MINI12864_2X_HAL(uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE) { init(cs, a0, reset); } - void init(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE) { + U8GLIB_MINI12864_2X_HAL(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset=U8G_PIN_NONE) { init(sck, mosi, cs, a0, reset); } + U8GLIB_MINI12864_2X_HAL(uint8_t cs, uint8_t a0, uint8_t reset=U8G_PIN_NONE) { init(cs, a0, reset); } + void init(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_uc1701_mini12864_HAL_2x_sw_spi, sck, mosi, cs, a0, reset); } - void init(uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE) { + void init(uint8_t cs, uint8_t a0, uint8_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_uc1701_mini12864_HAL_2x_hw_spi, cs, a0, reset); } }; @@ -125,12 +124,12 @@ extern u8g_dev_t u8g_dev_ssd1309_hw_spi; class U8GLIB_SSD1309_128X64_HAL : public U8GLIB { public: U8GLIB_SSD1309_128X64_HAL() : U8GLIB() { } - U8GLIB_SSD1309_128X64_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { init(sck, mosi, cs, a0, reset); } - U8GLIB_SSD1309_128X64_HAL(pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { init(cs, a0, reset); } - void init(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { + U8GLIB_SSD1309_128X64_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { init(sck, mosi, cs, a0, reset); } + U8GLIB_SSD1309_128X64_HAL(pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { init(cs, a0, reset); } + void init(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_ssd1309_sw_spi, (uint8_t)sck, (uint8_t)mosi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset); } - void init(pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { + void init(pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_ssd1309_hw_spi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset); } }; diff --git a/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h b/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h index cfba12acff1b..059b4eca1df6 100644 --- a/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h +++ b/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h @@ -21,7 +21,9 @@ */ #pragma once -// Use this file to select the com driver for device drivers that are NOT in the U8G library +/** + * Assign custom or standard U8G device drivers + */ #include @@ -41,11 +43,9 @@ #define U8G_COM_HAL_HW_SPI_FN u8g_com_samd51_hw_spi_fn #define U8G_COM_ST7920_HAL_HW_SPI u8g_com_samd51_st7920_hw_spi_fn - #elif defined(__SAMD21__) uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); - #define U8G_COM_ST7920_HAL_HW_SPI u8g_com_samd21_st7920_hw_spi_fn #elif defined(__STM32F1__) @@ -116,6 +116,7 @@ #define U8G_COM_ST7920_HAL_SW_SPI u8g_com_ST7920_sw_spi_fn #endif +// U8G_HAL_LINKS is defined for LPC1768/9 and Native envs by -DU8G_HAL_LINKS in platform.ini #ifndef U8G_COM_HAL_SW_SPI_FN #define U8G_COM_HAL_SW_SPI_FN u8g_com_null_fn #endif diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 8d0ab4efbe46..9eec9d198717 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -143,7 +143,7 @@ // Can also be overridden in Configuration_adv.h // If you can afford it, try the 3-frame fan animation! // Don't compile in the fan animation with no fan -#if !HAS_FAN0 || (HOTENDS == 5 || (HOTENDS == 4 && BED_OR_CHAMBER) || BOTH(STATUS_COMBINE_HEATERS, HAS_HEATED_CHAMBER)) +#if !HAS_FAN0 || (HOTENDS == 5 || (HOTENDS == 4 && BED_OR_CHAMBER) || ALL(STATUS_COMBINE_HEATERS, HAS_HEATED_CHAMBER)) #undef STATUS_FAN_FRAMES #elif !STATUS_FAN_FRAMES #define STATUS_FAN_FRAMES 2 @@ -253,7 +253,7 @@ ((STATUS_CHAMBER_WIDTH || STATUS_FAN_WIDTH || STATUS_BED_WIDTH) && STATUS_HOTEND_BITMAPS == 4) #define STATUS_HEATERS_X 5 #else - #if BOTH(STATUS_COMBINE_HEATERS, HAS_HEATED_BED) && HOTENDS <= 4 + #if ALL(STATUS_COMBINE_HEATERS, HAS_HEATED_BED) && HOTENDS <= 4 #define STATUS_HEATERS_X 5 #else #define STATUS_HEATERS_X 8 // Like the included bitmaps @@ -742,22 +742,22 @@ #if HAS_FAN0 && STATUS_FAN_WIDTH && HOTENDS <= 4 && defined(STATUS_FAN_FRAMES) #define DO_DRAW_FAN 1 #endif -#if BOTH(HAS_HOTEND, STATUS_HOTEND_ANIM) +#if ALL(HAS_HOTEND, STATUS_HOTEND_ANIM) #define ANIM_HOTEND 1 #endif -#if BOTH(DO_DRAW_BED, STATUS_BED_ANIM) +#if ALL(DO_DRAW_BED, STATUS_BED_ANIM) #define ANIM_BED 1 #endif -#if BOTH(DO_DRAW_CHAMBER, STATUS_CHAMBER_ANIM) +#if ALL(DO_DRAW_CHAMBER, STATUS_CHAMBER_ANIM) #define ANIM_CHAMBER 1 #endif -#if BOTH(DO_DRAW_CUTTER, STATUS_CUTTER_ANIM) +#if ALL(DO_DRAW_CUTTER, STATUS_CUTTER_ANIM) #define ANIM_CUTTER 1 #endif -#if BOTH(DO_DRAW_COOLER, STATUS_COOLER_ANIM) +#if ALL(DO_DRAW_COOLER, STATUS_COOLER_ANIM) #define ANIM_COOLER 1 #endif -#if BOTH(DO_DRAW_FLOWMETER, STATUS_FLOWMETER_ANIM) +#if ALL(DO_DRAW_FLOWMETER, STATUS_FLOWMETER_ANIM) #define ANIM_FLOWMETER 1 #endif #if ANIM_HOTEND || ANIM_BED || ANIM_CHAMBER || ANIM_CUTTER diff --git a/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h b/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h index 524ff18778dc..c81c63f2ed8f 100644 --- a/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h +++ b/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h @@ -22,15 +22,15 @@ #pragma once /** - Fontname: -Misc-Fixed-Medium-R-Normal--9-90-75-75-C-60-ISO10646-1 - Copyright: Public domain font. Share and enjoy. - Capital A Height: 6, '1' Height: 6 - Calculated Max Values w= 6 h= 9 x= 5 y= 5 dx= 6 dy= 0 ascent= 7 len= 9 - Font Bounding box w= 6 h= 9 x= 0 y=-2 - Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 - Pure Font ascent = 6 descent=-2 - X Font ascent = 6 descent=-2 - Max Font ascent = 7 descent=-2 + * Fontname: -Misc-Fixed-Medium-R-Normal--9-90-75-75-C-60-ISO10646-1 + * Copyright: Public domain font. Share and enjoy. + * Capital A Height: 6, '1' Height: 6 + * Calculated Max Values w= 6 h= 9 x= 5 y= 5 dx= 6 dy= 0 ascent= 7 len= 9 + * Font Bounding box w= 6 h= 9 x= 0 y=-2 + * Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 + * Pure Font ascent = 6 descent=-2 + * X Font ascent = 6 descent=-2 + * Max Font ascent = 7 descent=-2 */ #include const u8g_fntpgm_uint8_t u8g_font_6x9[2434] U8G_FONT_SECTION(".progmem.u8g_font_6x9") = { @@ -186,4 +186,5 @@ const u8g_fntpgm_uint8_t u8g_font_6x9[2434] U8G_FONT_SECTION(".progmem.u8g_font_ 0x00,0x50,0x00,0x90,0x90,0x90,0x70,0x04,0x09,0x09,0x06,0x01,0xFE,0x20,0x40,0x00, 0x90,0x90,0x90,0x70,0x90,0x60,0x04,0x08,0x08,0x06,0x01,0xFE,0x80,0x80,0xE0,0x90, 0x90,0xE0,0x80,0x80,0x04,0x08,0x08,0x06,0x01,0xFE,0x50,0x00,0x90,0x90,0x90,0x70, - 0x90,0x60}; + 0x90,0x60 +}; diff --git a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h index 6f55d3bc3df8..1ebe9884c06e 100644 --- a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h +++ b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h @@ -25,17 +25,17 @@ #if defined(__AVR__) && ENABLED(NOT_EXTENDED_ISO10646_1_5X7) // reduced font (only symbols 1 - 127) - saves about 1278 bytes of FLASH -/* - Fontname: -Marlin6x12-Fixed-Medium-R-SemiCondensed--12-90-100-100-C-111-ISO10646-1 - Copyright: Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1 - Capital A Height: 7, '1' Height: 7 - Calculated Max Values w= 7 h=10 x= 5 y= 5 dx= 7 dy= 0 ascent= 8 len=10 - Font Bounding box w=12 h=15 x= 0 y=-2 - Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 - Pure Font ascent = 7 descent=-2 - X Font ascent = 8 descent=-2 - Max Font ascent = 8 descent=-2 -*/ +/** + * Fontname: -Marlin6x12-Fixed-Medium-R-SemiCondensed--12-90-100-100-C-111-ISO10646-1 + * Copyright: Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1 + * Capital A Height: 7, '1' Height: 7 + * Calculated Max Values w= 7 h=10 x= 5 y= 5 dx= 7 dy= 0 ascent= 8 len=10 + * Font Bounding box w=12 h=15 x= 0 y=-2 + * Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 + * Pure Font ascent = 7 descent=-2 + * X Font ascent = 8 descent=-2 + * Max Font ascent = 8 descent=-2 + */ const u8g_fntpgm_uint8_t ISO10646_1_5x7[1324] U8G_FONT_SECTION("ISO10646_1_5x7") = { 0x00,0x0C,0x0F,0x00,0xFE,0x07,0x02,0x25,0x03,0xBB,0x01,0x7F,0xFE,0x08,0xFE,0x08, 0xFE,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0xF0,0xC8,0x88,0x88,0x98,0x78,0x10,0x05, @@ -123,17 +123,17 @@ const u8g_fntpgm_uint8_t ISO10646_1_5x7[1324] U8G_FONT_SECTION("ISO10646_1_5x7") #else // extended (original) font (symbols 1 - 255) -/* - Fontname: -Marlin6x12-Fixed-Medium-R-SemiCondensed--12-90-100-100-C-111-ISO10646-1 - Copyright: Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1 - Capital A Height: 7, '1' Height: 7 - Calculated Max Values w= 7 h=10 x= 5 y= 7 dx= 7 dy= 0 ascent=10 len=10 - Font Bounding box w=12 h=15 x= 0 y=-2 - Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 - Pure Font ascent = 7 descent=-2 - X Font ascent = 8 descent=-2 - Max Font ascent =10 descent=-2 -*/ +/** + * Fontname: -Marlin6x12-Fixed-Medium-R-SemiCondensed--12-90-100-100-C-111-ISO10646-1 + * Copyright: Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1 + * Capital A Height: 7, '1' Height: 7 + * Calculated Max Values w= 7 h=10 x= 5 y= 7 dx= 7 dy= 0 ascent=10 len=10 + * Font Bounding box w=12 h=15 x= 0 y=-2 + * Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 + * Pure Font ascent = 7 descent=-2 + * X Font ascent = 8 descent=-2 + * Max Font ascent =10 descent=-2 + */ const u8g_fntpgm_uint8_t ISO10646_1_5x7[2647] U8G_FONT_SECTION("ISO10646_1_5x7") = { 0x00,0x0C,0x0F,0x00,0xFE,0x07,0x02,0x25,0x03,0xBB,0x01,0xFF,0xFE,0x0A,0xFE,0x08, 0xFE,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0xF0,0xC8,0x88,0x88,0x98,0x78,0x10,0x05, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata.h b/Marlin/src/lcd/dogm/fontdata/langdata.h index 746a3bd0b451..a9e1b6cd94bd 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ro.h b/Marlin/src/lcd/dogm/fontdata/langdata_ro.h index 6be486355314..bdd4795f8ba2 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ro.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ro.h @@ -7,4 +7,10 @@ #include "langdata.h" -static const uxg_fontinfo_t g_fontinfo_ro[] PROGMEM = {}; +const u8g_fntpgm_uint8_t fontpage_2_131_131[31] U8G_FONT_SECTION("fontpage_2_131_131") = { + 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x83,0x83,0x00,0x08,0x00,0x00, + 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x88,0x70,0x00,0x70,0x08,0x78,0x88,0x78}; + +static const uxg_fontinfo_t g_fontinfo_ro[] PROGMEM = { + FONTDATA_ITEM(2, 131, 131, fontpage_2_131_131), // 'ă' -- 'ă' +}; diff --git a/Marlin/src/lcd/dogm/lcdprint_u8g.cpp b/Marlin/src/lcd/dogm/lcdprint_u8g.cpp index 74a49b095021..20a7eafb6f61 100644 --- a/Marlin/src/lcd/dogm/lcdprint_u8g.cpp +++ b/Marlin/src/lcd/dogm/lcdprint_u8g.cpp @@ -16,7 +16,7 @@ #include "../marlinui.h" #include "../../MarlinCore.h" -#include "../fontutils.h" +#include "../utf8.h" #include "u8g_fontutf8.h" #include "../lcdprint.h" @@ -27,7 +27,7 @@ void lcd_moveto(const lcd_uint_t col, const lcd_uint_t row) { u8g.setPrintPos(co void lcd_put_int(const int i) { u8g.print(i); } // return < 0 on error -// return the advanced pixels +// return the number of pixels advanced int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { if (c < 256) { u8g.print((char)c); @@ -39,6 +39,9 @@ int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { return ret; } +/** + * @return output width in pixels + */ int lcd_put_u8str_max(const char * utf8_str, const pixel_len_t max_length) { u8g_uint_t x = u8g.getPrintCol(), y = u8g.getPrintRow(), ret = uxg_DrawUtf8Str(u8g.getU8g(), x, y, utf8_str, max_length); @@ -46,6 +49,9 @@ int lcd_put_u8str_max(const char * utf8_str, const pixel_len_t max_length) { return ret; } +/** + * @return output width in pixels + */ int lcd_put_u8str_max_P(PGM_P utf8_pstr, const pixel_len_t max_length) { u8g_uint_t x = u8g.getPrintCol(), y = u8g.getPrintRow(), ret = uxg_DrawUtf8StrP(u8g.getU8g(), x, y, utf8_pstr, max_length); diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 1a86058b943c..eda3673fc2a5 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -47,7 +47,7 @@ #endif #include "../lcdprint.h" -#include "../fontutils.h" +#include "../utf8.h" #include "../../libs/numtostr.h" #include "../marlinui.h" @@ -56,7 +56,7 @@ #include "../../module/printcounter.h" #include "../../MarlinCore.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../../libs/duration_t.h" #endif @@ -156,7 +156,7 @@ bool MarlinUI::detected() { return true; } #if DISABLED(CUSTOM_BOOTSCREEN_ANIMATED_FRAME_TIME) constexpr millis_t frame_time = CUSTOM_BOOTSCREEN_FRAME_TIME; #endif - LOOP_L_N(f, COUNT(custom_bootscreen_animation)) + for (uint8_t f = 0; f < COUNT(custom_bootscreen_animation); ++f) #endif { #if ENABLED(CUSTOM_BOOTSCREEN_ANIMATED_FRAME_TIME) @@ -229,7 +229,7 @@ bool MarlinUI::detected() { return true; } draw_bootscreen_bmp(start_bmp); #else constexpr millis_t frame_time = MARLIN_BOOTSCREEN_FRAME_TIME; - LOOP_L_N(f, COUNT(marlin_bootscreen_animation)) { + for (uint8_t f = 0; f < COUNT(marlin_bootscreen_animation); ++f) { draw_bootscreen_bmp((uint8_t*)pgm_read_ptr(&marlin_bootscreen_animation[f])); if (frame_time) safe_delay(frame_time); } @@ -527,7 +527,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop if (yes) draw_boxed_string(LCD_WIDTH - (utf8_strlen(yes) * (USE_WIDE_GLYPH ? 2 : 1) + 1), LCD_HEIGHT - 1, yes, yesno); } - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA void MenuItem_sdbase::draw(const bool sel, const uint8_t row, FSTR_P const, CardReader &theCard, const bool isDir) { if (mark_as_selected(row, sel)) { @@ -539,7 +539,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop } } - #endif // SDSUPPORT + #endif // HAS_MEDIA #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -628,7 +628,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop #endif // AUTO_BED_LEVELING_UBL - #if EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + #if ANY(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) // // Draw knob rotation => Z motion key for: diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.h b/Marlin/src/lcd/dogm/marlinui_DOGM.h index f70621574c33..59df915f496e 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.h +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.h @@ -36,17 +36,22 @@ // RepRapWorld Graphical LCD - - #if DISABLED(SDSUPPORT) && (LCD_PINS_D4 == SD_SCK_PIN) && (LCD_PINS_ENABLE == SD_MOSI_PIN) - #define U8G_CLASS U8GLIB_ST7920_128X64_4X_HAL + #if HAS_MEDIA + #ifdef __SAMD21__ + #define U8G_CLASS U8GLIB_ST7920_128X64_4X_HAL + #else + // Hardware SPI on DUE + #define U8G_CLASS U8GLIB_ST7920_128X64_4X + #endif #define U8G_PARAM LCD_PINS_RS - #elif ENABLED(SDSUPPORT) && __SAMD21__ - - #define U8G_CLASS U8GLIB_ST7920_128X64_4X + #elif (LCD_PINS_D4 == SD_SCK_PIN) && (LCD_PINS_EN == SD_MOSI_PIN) + // Hardware SPI shared with SD Card + #define U8G_CLASS U8GLIB_ST7920_128X64_4X_HAL #define U8G_PARAM LCD_PINS_RS #else + // Software SPI #define U8G_CLASS U8GLIB_ST7920_128X64_4X - #define U8G_PARAM LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS + #define U8G_PARAM LCD_PINS_D4, LCD_PINS_EN, LCD_PINS_RS #endif #elif IS_U8GLIB_ST7920 @@ -54,7 +59,7 @@ // RepRap Discount Full Graphics Smart Controller // and other variant LCDs using ST7920 - #if DISABLED(SDSUPPORT) && (LCD_PINS_D4 == SD_SCK_PIN) && (LCD_PINS_ENABLE == SD_MOSI_PIN) + #if !HAS_MEDIA && (LCD_PINS_D4 == SD_SCK_PIN) && (LCD_PINS_EN == SD_MOSI_PIN) #define U8G_CLASS U8GLIB_ST7920_128X64_4X_HAL // 2 stripes, HW SPI (Shared with SD card. Non-standard LCD adapter on AVR.) #define U8G_PARAM LCD_PINS_RS #else @@ -63,7 +68,7 @@ #else #define U8G_CLASS U8GLIB_ST7920_128X64_RRD // Adjust stripes with PAGE_HEIGHT in ultralcd_st7920_u8glib_rrd.h #endif - #define U8G_PARAM LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS // AVR version ignores these pin settings + #define U8G_PARAM LCD_PINS_D4, LCD_PINS_EN, LCD_PINS_RS // AVR version ignores these pin settings // HAL version uses these pin settings #endif @@ -95,7 +100,7 @@ #define SMART_RAMPS MB(RAMPS_SMART_EFB, RAMPS_SMART_EEB, RAMPS_SMART_EFF, RAMPS_SMART_EEF, RAMPS_SMART_SF) #define U8G_CLASS U8GLIB_64128N_2X_HAL // 4 stripes (HW-SPI) - #if (SMART_RAMPS && defined(__SAM3X8E__)) || DOGLCD_SCK != SD_SCK_PIN || DOGLCD_MOSI != SD_MOSI_PIN + #if (SMART_RAMPS && defined(__SAM3X8E__)) || (defined(DOGLCD_SCK) && (DOGLCD_SCK != -1 && DOGLCD_SCK != SD_SCK_PIN)) || (defined(DOGLCD_MOSI) && (DOGLCD_MOSI != -1 && DOGLCD_MOSI != SD_MOSI_PIN)) #define FORCE_SOFT_SPI // SW-SPI #endif @@ -129,7 +134,7 @@ #define U8G_CLASS U8GLIB_SSD1306_128X64 // 8 stripes #endif -#elif EITHER(FYSETC_242_OLED_12864, K3D_242_OLED_CONTROLLER) +#elif ANY(FYSETC_242_OLED_12864, K3D_242_OLED_CONTROLLER) // FYSETC OLED 2.42" 128 × 64 Full Graphics Controller // or K3D OLED 2.42" 128 × 64 Full Graphics Controller @@ -153,7 +158,7 @@ #define U8G_CLASS U8GLIB_SH1306_128X64 // 8 stripes #endif -#elif EITHER(MKS_12864OLED, ZONESTAR_12864OLED) +#elif ANY(MKS_12864OLED, ZONESTAR_12864OLED) // MKS 128x64 (SH1106) OLED I2C LCD // - or - @@ -228,7 +233,7 @@ #if ENABLED(FORCE_SOFT_SPI) #define U8G_PARAM DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, DOGLCD_A0 // SW-SPI #else - #define U8G_PARAM DOGLCD_CS, DOGLCD_A0 // HW-SPI + #define U8G_PARAM DOGLCD_CS, DOGLCD_A0 // HW-SPI #endif #endif diff --git a/Marlin/src/lcd/dogm/status/chamber.h b/Marlin/src/lcd/dogm/status/chamber.h index 787a90884ae8..9b8cc7a0a063 100644 --- a/Marlin/src/lcd/dogm/status/chamber.h +++ b/Marlin/src/lcd/dogm/status/chamber.h @@ -41,32 +41,32 @@ #ifdef STATUS_CHAMBER_ANIM const unsigned char status_chamber_bmp[] PROGMEM = { - B00011111,B11111111,B11111000, - B00010000,B00000000,B00001000, - B00010000,B00000000,B00001000, - B00010000,B00000000,B00001000, - B00010000,B00000000,B00001000, - B00010000,B00000000,B00001000, - B00010000,B00000000,B00001000, - B00010000,B00000000,B00001000, - B00010000,B00000000,B00001000, - B00010000,B00000000,B00001000, - B00011111,B11111111,B11111000, - B00011111,B11111111,B11111000 + B00001111,B11111111,B11111000, + B00001000,B00000000,B00001000, + B00001000,B00000000,B00001000, + B00001000,B00000000,B00001000, + B00001000,B00000000,B00001000, + B00001000,B00000000,B00001000, + B00001000,B00000000,B00001000, + B00001000,B00000000,B00001000, + B00001000,B00000000,B00001000, + B00001000,B00000000,B00001000, + B00001111,B11111111,B11111000, + B00001111,B11111111,B11111000 }; const unsigned char status_chamber_on_bmp[] PROGMEM = { - B00011111,B11111111,B11111000, - B00010000,B00000000,B00001000, - B00010000,B10000100,B00001000, - B00010000,B01000010,B00001000, - B00010000,B01000010,B00001000, - B00010000,B10000100,B00001000, - B00010001,B00001000,B00001000, - B00010001,B00001000,B00001000, - B00010000,B10000100,B00001000, - B00010000,B00000000,B00001000, - B00011111,B11111111,B11111000, - B00011111,B11111111,B11111000 + B00001111,B11111111,B11111000, + B00001000,B00000000,B00001000, + B00001000,B10000100,B00001000, + B00001000,B01000010,B00001000, + B00001000,B01000010,B00001000, + B00001000,B10000100,B00001000, + B00001001,B00001000,B00001000, + B00001001,B00001000,B00001000, + B00001000,B10000100,B00001000, + B00001000,B00000000,B00001000, + B00001111,B11111111,B11111000, + B00001111,B11111111,B11111000 }; #else diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index cba58f5c02f9..1e2a689b5a84 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -55,7 +55,7 @@ #include "../../feature/spindle_laser.h" #endif -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "../../feature/cooler.h" #endif @@ -67,7 +67,7 @@ #include "../../feature/power_monitor.h" #endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../../sd/cardreader.h" #endif @@ -96,9 +96,10 @@ DRAWBIT_HOTEND, DRAWBIT_BED = HOTENDS, DRAWBIT_CHAMBER, - DRAWBIT_CUTTER + DRAWBIT_CUTTER, + DRAWBIT_COUNT }; - IF<(DRAWBIT_CUTTER > 7), uint16_t, uint8_t>::type draw_bits; + bits_t(DRAWBIT_COUNT) draw_bits; #endif #if ANIM_HOTEND @@ -126,7 +127,7 @@ #define MAX_HOTEND_DRAW _MIN(HOTENDS, ((LCD_PIXEL_WIDTH - (STATUS_LOGO_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8) / (STATUS_HEATERS_XSPACE))) #endif -#if EITHER(DO_DRAW_BED, DO_DRAW_HOTENDS) +#if ANY(DO_DRAW_BED, DO_DRAW_HOTENDS) #define STATUS_HEATERS_BOT (STATUS_HEATERS_Y + STATUS_HEATERS_HEIGHT - 1) #endif @@ -234,13 +235,8 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co const celsius_t temp = thermalManager.wholeDegHotend(heater_id), target = thermalManager.degTargetHotend(heater_id); - #if DISABLED(STATUS_HOTEND_ANIM) - #define STATIC_HOTEND true - #define HOTEND_DOT isHeat - #else - #define STATIC_HOTEND false - #define HOTEND_DOT false - #endif + #define STATIC_HOTEND DISABLED(STATUS_HOTEND_ANIM) + #define HOTEND_DOT TERN(STATUS_HOTEND_ANIM, false, isHeat) #if ENABLED(STATUS_HOTEND_NUMBERLESS) #define OFF_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend_b_bmp, status_hotend_a_bmp) @@ -333,13 +329,8 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co const bool isHeat = BED_ALT(); #endif - #if DISABLED(STATUS_BED_ANIM) - #define STATIC_BED true - #define BED_DOT isHeat - #else - #define STATIC_BED false - #define BED_DOT false - #endif + #define STATIC_BED DISABLED(STATUS_BED_ANIM) + #define BED_DOT TERN(STATUS_BED_ANIM, false, isHeat) if (PAGE_CONTAINS(STATUS_HEATERS_Y, STATUS_HEATERS_BOT)) { @@ -472,19 +463,23 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #if ENABLED(SHOW_REMAINING_TIME) void MarlinUI::drawRemain() { if (printJobOngoing() && get_remaining_time() != 0) - prepare_time_string(get_remaining_time(), 'R'); } + prepare_time_string(get_remaining_time(), 'R'); + } #endif #if ENABLED(SHOW_INTERACTION_TIME) void MarlinUI::drawInter() { if (printingIsActive() && interaction_time) - prepare_time_string(interaction_time, 'C'); } + prepare_time_string(interaction_time, 'C'); + } #endif #if ENABLED(SHOW_ELAPSED_TIME) void MarlinUI::drawElapsed() { if (printJobOngoing()) - prepare_time_string(print_job_timer.duration(), 'E'); } + prepare_time_string(print_job_timer.duration(), 'E'); + } #endif -#endif // HAS_PRINT_PROGRESS + +#endif // HAS_EXTRA_PROGRESS /** * Draw the Status Screen for a 128x64 DOGM (U8glib) display. @@ -588,7 +583,7 @@ void MarlinUI::draw_status_screen() { #if DO_DRAW_BED && DISABLED(STATUS_COMBINE_HEATERS) #if ANIM_BED - #if BOTH(HAS_LEVELING, STATUS_ALT_BED_BITMAP) + #if ALL(HAS_LEVELING, STATUS_ALT_BED_BITMAP) #define BED_BITMAP(S) ((S) \ ? (planner.leveling_active ? status_bed_leveled_on_bmp : status_bed_on_bmp) \ : (planner.leveling_active ? status_bed_leveled_bmp : status_bed_bmp)) @@ -648,7 +643,7 @@ void MarlinUI::draw_status_screen() { if (PAGE_UNDER(6 + 1 + 12 + 1 + 6 + 1)) { // Extruders #if DO_DRAW_HOTENDS - LOOP_L_N(e, MAX_HOTEND_DRAW) _draw_hotend_status((heater_id_t)e, blink); + for (uint8_t e = 0; e < MAX_HOTEND_DRAW; ++e) _draw_hotend_status((heater_id_t)e, blink); #endif // Laser / Spindle @@ -723,7 +718,7 @@ void MarlinUI::draw_status_screen() { #endif } - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA // // SD Card Symbol // @@ -737,7 +732,7 @@ void MarlinUI::draw_status_screen() { // Corner pixel u8g.drawPixel(50, 43); // 43 (or 42) } - #endif // SDSUPPORT + #endif // HAS_MEDIA #if HAS_PRINT_PROGRESS // Progress bar frame @@ -759,7 +754,7 @@ void MarlinUI::draw_status_screen() { // XYZ Coordinates // - #if EITHER(XYZ_NO_FRAME, XYZ_HOLLOW_FRAME) + #if ANY(XYZ_NO_FRAME, XYZ_HOLLOW_FRAME) #define XYZ_FRAME_TOP 29 #define XYZ_FRAME_HEIGHT INFO_FONT_ASCENT + 3 #else @@ -826,9 +821,7 @@ void MarlinUI::draw_status_screen() { #endif - #if HAS_Z_AXIS - _draw_axis_value(Z_AXIS, zstring, blink); - #endif + TERN_(HAS_Z_AXIS, _draw_axis_value(Z_AXIS, zstring, blink)); #if NONE(XYZ_NO_FRAME, XYZ_HOLLOW_FRAME) u8g.setColorIndex(1); // black on white @@ -852,7 +845,7 @@ void MarlinUI::draw_status_screen() { // // Filament sensor display if SD is disabled // - #if ENABLED(FILAMENT_LCD_DISPLAY) && DISABLED(SDSUPPORT) + #if ENABLED(FILAMENT_LCD_DISPLAY) && !HAS_MEDIA lcd_put_u8str(56, EXTRAS_2_BASELINE, wstring); lcd_put_u8str(102, EXTRAS_2_BASELINE, mstring); lcd_put_u8str(F("%")); @@ -868,7 +861,7 @@ void MarlinUI::draw_status_screen() { if (PAGE_CONTAINS(STATUS_BASELINE - INFO_FONT_ASCENT, STATUS_BASELINE + INFO_FONT_DESCENT)) { lcd_moveto(0, STATUS_BASELINE); - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #if ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) // Alternate Status message and Filament display if (ELAPSED(millis(), next_filament_display)) { lcd_put_u8str(F(LCD_STR_FILAM_DIA)); diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index bb5294ea3d43..8b70db5cdbb1 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -73,7 +73,7 @@ #if ENABLED(LIGHTWEIGHT_UI) #include "../marlinui.h" -#include "../fontutils.h" +#include "../utf8.h" #include "../lcdprint.h" #include "../../libs/duration_t.h" #include "../../module/motion.h" @@ -81,7 +81,7 @@ #include "../../module/temperature.h" #include "../../libs/numtostr.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../../sd/cardreader.h" #endif @@ -238,7 +238,7 @@ void ST7920_Lite_Status_Screen::clear_ddram() { /* This fills the entire graphics buffer with zeros */ void ST7920_Lite_Status_Screen::clear_gdram() { - LOOP_L_N(y, BUFFER_HEIGHT) { + for (uint8_t y = 0; y < BUFFER_HEIGHT; ++y) { set_gdram_address(0, y); begin_data(); for (uint8_t i = (BUFFER_WIDTH) / 16; i--;) write_word(0); @@ -436,7 +436,7 @@ void ST7920_Lite_Status_Screen::draw_degree_symbol(uint8_t x, uint8_t y, const b const uint8_t x_word = x >> 1, y_top = degree_symbol_y_top, y_bot = y_top + COUNT(degree_symbol); - LOOP_S_L_N(i, y_top, y_bot) { + for (uint8_t i = y_top; i < y_bot; ++i) { uint8_t byte = pgm_read_byte(p_bytes++); set_gdram_address(x_word, i + y * 16); begin_data(); @@ -680,17 +680,17 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { void ST7920_Lite_Status_Screen::draw_progress_string(uint8_t addr, const char *str) { set_ddram_address(addr); begin_data(); - write_str(str, TERN(HOTENDS == 1, 8, 6)); + write_str(str, HOTENDS == 1 ? 8 : 6); } - #define PPOS (DDRAM_LINE_3 + TERN(HOTENDS == 1, 4, 5)) // progress string position, in 16-bit words + constexpr uint8_t PPOS = (DDRAM_LINE_3 + (HOTENDS == 1 ? 4 : 5)); // Progress string position, in 16-bit words #if ENABLED(SHOW_PROGRESS_PERCENT) void MarlinUI::drawPercent() { lightUI.drawPercent(); } void ST7920_Lite_Status_Screen::drawPercent() { #define LSHIFT TERN(HOTENDS == 1, 0, 1) const uint8_t progress = ui.get_progress_percent(); - memset(&screenstr, 0x20, 8); // fill with spaces to avoid artifacts + memset(&screenstr, ' ', 8); // fill with spaces to avoid artifacts if (progress){ memcpy(&screenstr[2 - LSHIFT], \ TERN(PRINT_PROGRESS_SHOW_DECIMALS, permyriadtostr4(ui.get_progress_permyriad()), ui8tostr3rj(progress)), \ @@ -705,7 +705,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { void ST7920_Lite_Status_Screen::drawRemain() { const duration_t remaint = TERN0(SET_REMAINING_TIME, ui.get_remaining_time()); if (printJobOngoing() && remaint.value) { - draw_progress_string( PPOS, prepare_time_string(remaint, 'R')); + draw_progress_string(PPOS, prepare_time_string(remaint, 'R')); } } #endif @@ -714,7 +714,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { void ST7920_Lite_Status_Screen::drawInter() { const duration_t interactt = ui.interaction_time; if (printingIsActive() && interactt.value) { - draw_progress_string( PPOS, prepare_time_string(interactt, 'C')); + draw_progress_string(PPOS, prepare_time_string(interactt, 'C')); } } #endif @@ -723,7 +723,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { void ST7920_Lite_Status_Screen::drawElapsed() { if (printJobOngoing()) { const duration_t elapsedt = print_job_timer.duration(); - draw_progress_string( PPOS, prepare_time_string(elapsedt, 'E')); + draw_progress_string(PPOS, prepare_time_string(elapsedt, 'E')); } } #endif @@ -755,10 +755,10 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { // This drawing is a mess and only produce readable result around 25% steps // i.e. 74-76% look fine [|||||||||||||||||||||||| ], but 73% look like this: [|||||||||||||||| | ] // meaning partially filled bytes produce only single vertical line, and i bet they're not supposed to! - LOOP_S_LE_N(y, top, bottom) { + for (uint8_t y = top; y <= bottom; ++y) { set_gdram_address(left, y); begin_data(); - LOOP_L_N(x, width) { + for (uint8_t x = 0; x < width; ++x) { uint16_t gfx_word = 0x0000; if ((x + 1) * char_pcnt <= value) gfx_word = 0xFFFF; // Draw completely filled bytes diff --git a/Marlin/src/lcd/dogm/u8g_dev_ssd1306_sh1106_128x64_I2C.cpp b/Marlin/src/lcd/dogm/u8g_dev_ssd1306_sh1106_128x64_I2C.cpp index b3e579e6a44a..5865bb11873b 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_ssd1306_sh1106_128x64_I2C.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_ssd1306_sh1106_128x64_I2C.cpp @@ -230,12 +230,10 @@ uint8_t u8g_dev_ssd1306_128x64_2x_2_wire_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t return u8g_dev_pb16v1_base_fn(u8g, dev, msg, arg); } - uint8_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire_buf[WIDTH*2] U8G_NOCOMMON ; u8g_pb_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_ssd1306_128x64_2x_i2c_2_wire_buf}; u8g_dev_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire = { u8g_dev_ssd1306_128x64_2x_2_wire_fn, &u8g_dev_ssd1306_128x64_2x_i2c_2_wire_pb, U8G_COM_SSD_I2C_HAL }; - ///////////////////////////////////////////////////////////////////////////////////////////// // This routine adds the instruction byte in between the command bytes. This makes the init diff --git a/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp b/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp index 63e7b2e2b8b5..6c7066179eb0 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp @@ -234,7 +234,6 @@ uint8_t u8g_dev_st7565_64128n_HAL_2x_buf[WIDTH*2] U8G_NOCOMMON ; u8g_pb_t u8g_dev_st7565_64128n_HAL_2x_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_st7565_64128n_HAL_2x_buf}; u8g_dev_t u8g_dev_st7565_64128n_HAL_2x_sw_spi = { u8g_dev_st7565_64128n_HAL_2x_fn, &u8g_dev_st7565_64128n_HAL_2x_pb, U8G_COM_HAL_SW_SPI_FN }; - U8G_PB_DEV(u8g_dev_st7565_64128n_HAL_hw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_st7565_64128n_HAL_fn, U8G_COM_HAL_HW_SPI_FN); u8g_dev_t u8g_dev_st7565_64128n_HAL_2x_hw_spi = { u8g_dev_st7565_64128n_HAL_2x_fn, &u8g_dev_st7565_64128n_HAL_2x_pb, U8G_COM_HAL_HW_SPI_FN }; diff --git a/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp b/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp index fde6e41792dc..d5f1be18ec95 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp @@ -84,19 +84,19 @@ static const uint8_t u8g_dev_st7920_128x64_HAL_init_seq[] PROGMEM = { void clear_graphics_DRAM(u8g_t *u8g, u8g_dev_t *dev) { u8g_SetChipSelect(u8g, dev, 1); u8g_Delay(1); - u8g_SetAddress(u8g, dev, 0); // cmd mode - u8g_WriteByte(u8g, dev, 0x08); //display off, cursor+blink off - u8g_WriteByte(u8g, dev, 0x3E); //extended mode + GDRAM active - LOOP_L_N(y, (LCD_PIXEL_HEIGHT) / 2) { //clear GDRAM - u8g_WriteByte(u8g, dev, 0x80 | y); //set y - u8g_WriteByte(u8g, dev, 0x80); //set x = 0 - u8g_SetAddress(u8g, dev, 1); /* data mode */ - LOOP_L_N(i, 2 * (LCD_PIXEL_WIDTH) / 8) //2x width clears both segments + u8g_SetAddress(u8g, dev, 0); // Cmd mode + u8g_WriteByte(u8g, dev, 0x08); // Display off, cursor+blink off + u8g_WriteByte(u8g, dev, 0x3E); // Extended mode + GDRAM active + for (uint8_t y = 0; y < (LCD_PIXEL_HEIGHT) / 2; ++y) { // Clear GDRAM + u8g_WriteByte(u8g, dev, 0x80 | y); // Set y + u8g_WriteByte(u8g, dev, 0x80); // Set x = 0 + u8g_SetAddress(u8g, dev, 1); // Data mode + for (uint8_t i = 0; i < 2 * (LCD_PIXEL_WIDTH) / 8; ++i) // 2x width clears both segments u8g_WriteByte(u8g, dev, 0); - u8g_SetAddress(u8g, dev, 0); /* cmd mode */ + u8g_SetAddress(u8g, dev, 0); // Cmd mode } - u8g_WriteByte(u8g, dev, 0x0C); //display on, cursor+blink off + u8g_WriteByte(u8g, dev, 0x0C); // Display on, cursor+blink off u8g_SetChipSelect(u8g, dev, 0); } diff --git a/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp b/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp index efc010ca8960..2372bd488043 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp @@ -88,8 +88,8 @@ TFT_IO tftio; #define X_HI (UPSCALE(TFT_PIXEL_OFFSET_X, WIDTH) - 1) #define Y_HI (UPSCALE(TFT_PIXEL_OFFSET_Y, HEIGHT) - 1) -// 16 bit color generator: https://ee-programming-notepad.blogspot.com/2016/10/16-bit-color-generator-picker.html -// RGB565 color picker: https://trolsoft.ru/en/articles/rgb565-color-picker +// RGB565 color picker: https://embeddednotepad.com/page/rgb565-color-picker +// Hex code to color name: https://www.color-name.com/ #define COLOR_BLACK 0x0000 // #000000 #define COLOR_WHITE 0xFFFF // #FFFFFF @@ -136,8 +136,8 @@ TFT_IO tftio; #define TFT_BTOKMENU_COLOR COLOR_RED #endif -static void setWindow(u8g_t *u8g, u8g_dev_t *dev, uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ymax) { - tftio.set_window(Xmin, Ymin, Xmax, Ymax); +static void setWindow(u8g_t *u8g, u8g_dev_t *dev, uint16_t xMin, uint16_t yMin, uint16_t xMax, uint16_t yMax) { + tftio.set_window(xMin, yMin, xMax, yMax); } #if HAS_TOUCH_BUTTONS @@ -298,10 +298,10 @@ static void setWindow(u8g_t *u8g, u8g_dev_t *dev, uint16_t Xmin, uint16_t Ymin, v = color; else v = TFT_MARLINBG_COLOR; - LOOP_L_N(n, GRAPHICAL_TFT_UPSCALE) buffer[k++] = v; + for (uint8_t n = 0; n < GRAPHICAL_TFT_UPSCALE; ++n) buffer[k++] = v; } #if HAS_LCD_IO - LOOP_S_L_N(n, 1, GRAPHICAL_TFT_UPSCALE) + for (uint8_t n = 1; n < GRAPHICAL_TFT_UPSCALE; ++n) for (uint16_t l = 0; l < UPSCALE0(length); l++) buffer[l + n * UPSCALE0(length)] = buffer[l]; @@ -412,16 +412,16 @@ uint8_t u8g_dev_tft_320x240_upscale_from_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, u if (TERN0(HAS_TOUCH_BUTTONS_SLEEP, touchBt.isSleeping())) break; if (++page > (HEIGHT / PAGE_HEIGHT)) return 1; - LOOP_L_N(y, PAGE_HEIGHT) { + for (uint8_t y = 0; y < PAGE_HEIGHT; ++y) { uint32_t k = 0; TERN_(HAS_LCD_IO, buffer = (y & 1) ? bufferB : bufferA); for (uint16_t i = 0; i < (uint32_t)pb->width; i++) { const uint8_t b = *(((uint8_t *)pb->buf) + i); const uint16_t c = TEST(b, y) ? TFT_MARLINUI_COLOR : TFT_MARLINBG_COLOR; - LOOP_L_N(n, GRAPHICAL_TFT_UPSCALE) buffer[k++] = c; + for (uint8_t n = 0; n < GRAPHICAL_TFT_UPSCALE; ++n) buffer[k++] = c; } #if HAS_LCD_IO - LOOP_S_L_N(n, 1, GRAPHICAL_TFT_UPSCALE) + for (uint8_t n = 1; n < GRAPHICAL_TFT_UPSCALE; ++n) for (uint16_t l = 0; l < UPSCALE0(WIDTH); l++) buffer[l + n * UPSCALE0(WIDTH)] = buffer[l]; @@ -429,7 +429,7 @@ uint8_t u8g_dev_tft_320x240_upscale_from_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, u #else uint8_t *bufptr = (uint8_t*) buffer; for (uint8_t i = GRAPHICAL_TFT_UPSCALE; i--;) { - LOOP_S_L_N(n, 0, GRAPHICAL_TFT_UPSCALE * 2) { + for (uint8_t n = 0; n < GRAPHICAL_TFT_UPSCALE * 2; ++n) { u8g_WriteSequence(u8g, dev, WIDTH, &bufptr[WIDTH * n]); } } @@ -556,4 +556,4 @@ U8G_PB_DEV(u8g_dev_tft_320x240_upscale_from_128x64, WIDTH, HEIGHT, PAGE_HEIGHT, #endif // TOUCH_SCREEN_CALIBRATION -#endif // HAS_MARLINUI_U8GLIB && (FSMC_CS_PIN || HAS_SPI_GRAPHICAL_TFT) +#endif // HAS_MARLINUI_U8GLIB && (FSMC_CS_PIN || HAS_SPI_GRAPHICAL_TFT || HAS_LTDC_GRAPHICAL_TFT) diff --git a/Marlin/src/lcd/dogm/u8g_fontutf8.cpp b/Marlin/src/lcd/dogm/u8g_fontutf8.cpp index e9d15350963a..5d9ef627c985 100644 --- a/Marlin/src/lcd/dogm/u8g_fontutf8.cpp +++ b/Marlin/src/lcd/dogm/u8g_fontutf8.cpp @@ -12,7 +12,7 @@ #if HAS_MARLINUI_U8GLIB #include -#include "../fontutils.h" +#include "../utf8.h" #include "u8g_fontutf8.h" typedef void font_t; @@ -121,8 +121,8 @@ static font_group_t g_fontgroup_root = { nullptr, 0 }; */ static inline bool uxg_Utf8FontIsInited() { return flag_fontgroup_was_inited; } -int uxg_SetUtf8Fonts (const uxg_fontinfo_t * fntinfo, int number) { - flag_fontgroup_was_inited = 1; +int uxg_SetUtf8Fonts(const uxg_fontinfo_t *fntinfo, int number) { + flag_fontgroup_was_inited = true; return fontgroup_init(&g_fontgroup_root, fntinfo, number); } diff --git a/Marlin/src/lcd/dogm/u8g_fontutf8.h b/Marlin/src/lcd/dogm/u8g_fontutf8.h index 660eb28ffeb3..281894509d6f 100644 --- a/Marlin/src/lcd/dogm/u8g_fontutf8.h +++ b/Marlin/src/lcd/dogm/u8g_fontutf8.h @@ -9,7 +9,7 @@ #pragma once #include -#include "../fontutils.h" +#include "../utf8.h" // the macro to indicate a UTF-8 string // You should to save the C/C++ source in UTF-8 encoding! diff --git a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp index e844eee25183..557899766943 100644 --- a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp @@ -20,8 +20,8 @@ * */ -// NOTE - the HAL version of the rrd device uses a generic ST7920 device. See the -// file u8g_dev_st7920_128x64_HAL.cpp for the HAL version. +// NOTE - the HAL version of the rrd device uses a generic ST7920 device. +// See u8g_dev_st7920_128x64_HAL.cpp for the HAL version. #include "../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h index 446bfcfd4212..9a565fc2efb9 100644 --- a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h +++ b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.h @@ -28,7 +28,7 @@ #include "../../HAL/shared/Delay.h" #define ST7920_CLK_PIN LCD_PINS_D4 -#define ST7920_DAT_PIN LCD_PINS_ENABLE +#define ST7920_DAT_PIN LCD_PINS_EN #define ST7920_CS_PIN LCD_PINS_RS //#define PAGE_HEIGHT 8 // 128 byte framebuffer diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.cpp b/Marlin/src/lcd/e3v2/common/dwin_api.cpp index f3abaf25c96b..319c861ea4ff 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.cpp +++ b/Marlin/src/lcd/e3v2/common/dwin_api.cpp @@ -38,8 +38,8 @@ uint8_t databuf[26] = { 0 }; // Send the data in the buffer plus the packet tail void DWIN_Send(size_t &i) { ++i; - LOOP_L_N(n, i) { LCD_SERIAL.write(DWIN_SendBuf[n]); delayMicroseconds(1); } - LOOP_L_N(n, 4) { LCD_SERIAL.write(DWIN_BufTail[n]); delayMicroseconds(1); } + for (uint8_t n = 0; n < i; ++n) { LCD_SERIAL.write(DWIN_SendBuf[n]); delayMicroseconds(1); } + for (uint8_t n = 0; n < 4; ++n) { LCD_SERIAL.write(DWIN_BufTail[n]); delayMicroseconds(1); } } /*-------------------------------------- System variable function --------------------------------------*/ diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.h b/Marlin/src/lcd/e3v2/common/dwin_api.h index dc97ef2723fa..3ef20f076d82 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.h +++ b/Marlin/src/lcd/e3v2/common/dwin_api.h @@ -162,7 +162,6 @@ inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_ void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - /*---------------------------------------- Text related functions ----------------------------------------*/ // Draw a string diff --git a/Marlin/src/lcd/e3v2/common/dwin_color.h b/Marlin/src/lcd/e3v2/common/dwin_color.h index d327f21a9384..ad01fb0912b0 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_color.h +++ b/Marlin/src/lcd/e3v2/common/dwin_color.h @@ -22,7 +22,7 @@ #pragma once // Extended and default UI Colors -#define RGB(R,G,B) (R << 11) | (G << 5) | (B) // R,B: 0..31; G: 0..63 +#define RGB(R,G,B) (R << 11) | (G << 5) | (B) // R: 0..31, G: 0..63, B: 0..31 #define GetRColor(color) ((color >> 11) & 0x1F) #define GetGColor(color) ((color >> 5) & 0x3F) #define GetBColor(color) ((color >> 0) & 0x1F) diff --git a/Marlin/src/lcd/e3v2/common/dwin_font.h b/Marlin/src/lcd/e3v2/common/dwin_font.h index 10bb104d27bc..b92bfcf99c9f 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_font.h +++ b/Marlin/src/lcd/e3v2/common/dwin_font.h @@ -28,13 +28,15 @@ typedef uint8_t fontid_t; * 0x00=6*12 0x01=8*16 0x02=10*20 0x03=12*24 0x04=14*28 * 0x05=16*32 0x06=20*40 0x07=24*48 0x08=28*56 0x09=32*64 */ -#define font6x12 0x00 +#if DISABLED(TJC_DISPLAY) + #define font6x12 0x00 + #define font20x40 0x06 + #define font24x48 0x07 + #define font28x56 0x08 + #define font32x64 0x09 +#endif #define font8x16 0x01 #define font10x20 0x02 #define font12x24 0x03 #define font14x28 0x04 #define font16x32 0x05 -#define font20x40 0x06 -#define font24x48 0x07 -#define font28x56 0x08 -#define font32x64 0x09 diff --git a/Marlin/src/lcd/e3v2/common/encoder.cpp b/Marlin/src/lcd/e3v2/common/encoder.cpp index 5081e27690f2..2364458096c8 100644 --- a/Marlin/src/lcd/e3v2/common/encoder.cpp +++ b/Marlin/src/lcd/e3v2/common/encoder.cpp @@ -87,7 +87,10 @@ EncoderState Encoder_ReceiveAnalyze() { #if PIN_EXISTS(LCD_LED) //LED_Action(); #endif - if (!ui.backlight) ui.refresh_brightness(); + if (!ui.backlight) { + ui.refresh_brightness(); + return ENCODER_DIFF_NO; + } const bool was_waiting = wait_for_user; wait_for_user = false; return was_waiting ? ENCODER_DIFF_NO : ENCODER_DIFF_ENTER; @@ -154,6 +157,10 @@ EncoderState Encoder_ReceiveAnalyze() { temp_diff = 0; } + if (temp_diffState != ENCODER_DIFF_NO) { + TERN_(HAS_BACKLIGHT_TIMEOUT, ui.refresh_backlight_timeout()); + if (!ui.backlight) ui.refresh_brightness(); + } return temp_diffState; } @@ -164,9 +171,9 @@ EncoderState Encoder_ReceiveAnalyze() { // LED light operation void LED_Action() { - LED_Control(RGB_SCALE_WARM_WHITE,0x0F); + LED_Control(RGB_SCALE_WARM_WHITE, 0x0F); delay(30); - LED_Control(RGB_SCALE_WARM_WHITE,0x00); + LED_Control(RGB_SCALE_WARM_WHITE, 0x00); } // LED initialization diff --git a/Marlin/src/lcd/e3v2/common/encoder.h b/Marlin/src/lcd/e3v2/common/encoder.h index 3ab8c3bf422b..4401242a0d0d 100644 --- a/Marlin/src/lcd/e3v2/common/encoder.h +++ b/Marlin/src/lcd/e3v2/common/encoder.h @@ -45,7 +45,7 @@ typedef enum { ENCODER_DIFF_ENTER = 3 // click } EncoderState; -#define ENCODER_WAIT_MS 20 +#define ENCODER_WAIT_MS TERN(DWIN_LCD_PROUI, 10, 20) // Encoder initialization void Encoder_Configuration(); diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 8eda8ca4477c..7a3e3ff44e09 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -45,7 +45,7 @@ #define JUST_BABYSTEP 1 #endif -#include "../../fontutils.h" +#include "../../utf8.h" #include "../../marlinui.h" #include "../../../sd/cardreader.h" @@ -76,7 +76,7 @@ #include "../../../module/probe.h" #endif -#if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) +#if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) #include "../../../feature/babystep.h" #endif @@ -214,7 +214,7 @@ void HMI_SetLanguageCache() { } void HMI_SetLanguage() { - #if BOTH(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) + #if ALL(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) BL24CXX::read(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); #endif HMI_SetLanguageCache(); @@ -223,7 +223,7 @@ void HMI_SetLanguage() { void HMI_ToggleLanguage() { HMI_flag.language = HMI_IsChinese() ? DWIN_ENGLISH : DWIN_CHINESE; HMI_SetLanguageCache(); - #if BOTH(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) + #if ALL(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); #endif } @@ -411,7 +411,7 @@ void Scroll_Menu(const uint8_t dir) { } inline uint16_t nr_sd_menu_items() { - return card.get_num_Files() + !card.flag.workDirIsRoot; + return card.get_num_items() + !card.flag.workDirIsRoot; } void Erase_Menu_Text(const uint8_t line) { @@ -488,7 +488,7 @@ void Draw_Back_First(const bool is_sel=true) { #define PREPARE_CASE_ZOFF (PREPARE_CASE_HOME + ENABLED(HAS_ZOFFSET_ITEM)) #define PREPARE_CASE_PLA (PREPARE_CASE_ZOFF + ENABLED(HAS_PREHEAT)) #define PREPARE_CASE_ABS (PREPARE_CASE_PLA + (TERN0(HAS_PREHEAT, PREHEAT_COUNT > 1))) -#define PREPARE_CASE_COOL (PREPARE_CASE_ABS + EITHER(HAS_HOTEND, HAS_HEATED_BED)) +#define PREPARE_CASE_COOL (PREPARE_CASE_ABS + ANY(HAS_HOTEND, HAS_HEATED_BED)) #define PREPARE_CASE_LANG (PREPARE_CASE_COOL + 1) #define PREPARE_CASE_TOTAL PREPARE_CASE_LANG @@ -1273,7 +1273,7 @@ void Goto_MainMenu() { DWIN_Frame_TitleCopy(2, 2, 26, 13); // "Home" etc else { #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_MAIN)); + Draw_Title(GET_TEXT_F(MSG_MAIN_MENU)); #else DWIN_Frame_TitleCopy(0, 2, 40, 11); // "Home" #endif @@ -1388,7 +1388,7 @@ void HMI_Move_Z() { LIMIT(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MIN) * 100, (Z_PROBE_OFFSET_RANGE_MAX) * 100); last_zoffset = dwin_zoffset; dwin_zoffset = HMI_ValueStruct.offset_value / 100.0f; - #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) if (BABYSTEP_ALLOWED()) babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); #endif Draw_Edit_Signed_Float2(zoff_line, HMI_ValueStruct.offset_value, true); @@ -1830,9 +1830,9 @@ void MarlinUI::refresh() { /* Nothing to see here */ } void Init_Shift_Name() { const bool is_subdir = !card.flag.workDirIsRoot; const int8_t filenum = select_file.now - 1 - is_subdir; // Skip "Back" and ".." - const uint16_t fileCnt = card.get_num_Files(); + const int16_t fileCnt = card.get_num_items(); if (WITHIN(filenum, 0, fileCnt - 1)) { - card.getfilename_sorted(SD_ORDER(filenum, fileCnt)); + card.selectFileByIndexSorted(filenum); char * const name = card.longest_filename(); make_name_without_ext(shift_name, name, 100); } @@ -1857,7 +1857,7 @@ void Draw_SDItem(const uint16_t item, int16_t row=-1) { return; } - card.getfilename_sorted(SD_ORDER(item - is_subdir, card.get_num_Files())); + card.selectFileByIndexSorted(item - is_subdir); char * const name = card.longest_filename(); #if ENABLED(SCROLL_LONG_FILENAMES) @@ -1908,7 +1908,7 @@ void Redraw_SD_List() { if (card.isMounted()) { // As many files as will fit - LOOP_L_N(i, _MIN(nr_sd_menu_items(), MROWS)) + for (uint8_t i = 0; i < _MIN(nr_sd_menu_items(), MROWS); ++i) Draw_SDItem(i, i + 1); TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); @@ -2055,7 +2055,7 @@ void Draw_Info_Menu() { DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(CORP_WEBSITE) * MENU_CHR_W) / 2, 268, F(CORP_WEBSITE)); Draw_Back_First(); - LOOP_L_N(i, 3) { + for (uint8_t i = 0; i < 3; ++i) { DWIN_ICON_Show(ICON, ICON_PrintSize + i, 26, 99 + i * 73); DWIN_Draw_Line(Line_Color, 16, MBASE(2) + i * 73, 256, 156 + i * 73); } @@ -2223,7 +2223,7 @@ void HMI_SelectFile() { } else { const uint16_t filenum = select_file.now - 1 - hasUpDir; - card.getfilename_sorted(SD_ORDER(filenum, card.get_num_Files())); + card.selectFileByIndexSorted(filenum); // Enter that folder! if (card.flag.filenameIsDir) { @@ -2308,10 +2308,10 @@ void HMI_Printing() { char cmd[40]; cmd[0] = '\0'; - #if BOTH(HAS_HEATED_BED, PAUSE_HEAT) + #if ALL(HAS_HEATED_BED, PAUSE_HEAT) if (resume_bed_temp) sprintf_P(cmd, PSTR("M190 S%i\n"), resume_bed_temp); #endif - #if BOTH(HAS_HOTEND, PAUSE_HEAT) + #if ALL(HAS_HOTEND, PAUSE_HEAT) if (resume_hotend_temp) sprintf_P(&cmd[strlen(cmd)], PSTR("M109 S%i\n"), resume_hotend_temp); #endif @@ -2407,7 +2407,7 @@ void Draw_Move_Menu() { if (select_axis.now != CASE_BACK) Draw_Menu_Cursor(select_axis.now); // Draw separators and icons - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MoveX + i); + for (uint8_t i = 0; i < 3 + ENABLED(HAS_HOTEND); ++i) Draw_Menu_Line(i + 1, ICON_MoveX + i); } void Item_Adv_HomeOffsets(const uint8_t row) { @@ -2718,7 +2718,7 @@ void HMI_Prepare() { #if HAS_ZOFFSET_ITEM case PREPARE_CASE_ZOFF: - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + #if ANY(HAS_BED_PROBE, BABYSTEPPING) checkkey = Homeoffset; HMI_ValueStruct.show_mode = -4; HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; @@ -3281,7 +3281,7 @@ void Draw_Max_Speed_Menu() { } Draw_Back_First(); - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedX + i); + for (uint8_t i = 0; i < 3 + ENABLED(HAS_HOTEND); ++i) Draw_Menu_Line(i + 1, ICON_MaxSpeedX + i); Draw_Edit_Integer4(1, planner.settings.max_feedrate_mm_s[X_AXIS]); Draw_Edit_Integer4(2, planner.settings.max_feedrate_mm_s[Y_AXIS]); Draw_Edit_Integer4(3, planner.settings.max_feedrate_mm_s[Z_AXIS]); @@ -3335,7 +3335,7 @@ void Draw_Max_Accel_Menu() { } Draw_Back_First(); - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxAccX + i); + for (uint8_t i = 0; i < 3 + ENABLED(HAS_HOTEND); ++i) Draw_Menu_Line(i + 1, ICON_MaxAccX + i); Draw_Edit_Integer4(1, planner.settings.max_acceleration_mm_per_s2[X_AXIS]); Draw_Edit_Integer4(2, planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); Draw_Edit_Integer4(3, planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); @@ -3394,7 +3394,7 @@ void Draw_Max_Accel_Menu() { } Draw_Back_First(); - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedJerkX + i); + for (uint8_t i = 0; i < 3 + ENABLED(HAS_HOTEND); ++i) Draw_Menu_Line(i + 1, ICON_MaxSpeedJerkX + i); Draw_Edit_Float3(1, planner.max_jerk.x * MINUNITMULT); Draw_Edit_Float3(2, planner.max_jerk.y * MINUNITMULT); Draw_Edit_Float3(3, planner.max_jerk.z * MINUNITMULT); @@ -3445,7 +3445,7 @@ void Draw_Steps_Menu() { } Draw_Back_First(); - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_StepX + i); + for (uint8_t i = 0; i < 3 + ENABLED(HAS_HOTEND); ++i) Draw_Menu_Line(i + 1, ICON_StepX + i); Draw_Edit_Float3(1, planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT); Draw_Edit_Float3(2, planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT); Draw_Edit_Float3(3, planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT); @@ -3797,7 +3797,7 @@ void HMI_Tune() { #endif #if HAS_ZOFFSET_ITEM case TUNE_CASE_ZOFF: // Z-offset - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + #if ANY(HAS_BED_PROBE, BABYSTEPPING) checkkey = Homeoffset; HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; Draw_Edit_Signed_Float2(TUNE_CASE_ZOFF + MROWS - index_tune, HMI_ValueStruct.offset_value, true); @@ -4257,7 +4257,7 @@ void DWIN_HandleScreen() { case Extruder: HMI_Move_E(); break; case ETemp: HMI_ETemp(); break; #endif - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + #if ANY(HAS_BED_PROBE, BABYSTEPPING) case Homeoffset: HMI_Zoffset(); break; #endif #if HAS_HEATED_BED diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 34985a54cbbf..a475e24a8271 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -96,7 +96,7 @@ #define MENU_CHAR_LIMIT 24 #define STATUS_Y 352 -#define MAX_PRINT_SPEED 500 +#define MAX_PRINT_SPEED 999 #define MIN_PRINT_SPEED 10 #if HAS_FAN @@ -116,7 +116,7 @@ #endif #if HAS_HOTEND - #define MAX_FLOW_RATE 200 + #define MAX_FLOW_RATE 299 #define MIN_FLOW_RATE 10 #define MAX_E_TEMP (HEATER_0_MAXTEMP - HOTEND_OVERSHOOT) @@ -203,7 +203,7 @@ bool livemove = false; bool liveadjust = false; uint8_t preheatmode = 0; float zoffsetvalue = 0; -uint8_t gridpoint; +grid_count_t gridpoint; float corner_avg; float corner_pos; @@ -416,7 +416,7 @@ class TextScroller { // Draw value text on if (viewer_print_value) { - int8_t offset_x, offset_y = cell_height_px / 2 - 6; + const int8_t offset_y = cell_height_px / 2 - 6; if (isnan(bedlevel.z_values[x][y])) { // undefined DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px + cell_width_px / 2 - 5, start_y_px + offset_y, F("X")); } @@ -425,7 +425,7 @@ class TextScroller { sprintf_P(buf, PSTR("%s"), dtostrf(abs(bedlevel.z_values[x][y]), 1, 2, str_1)); else sprintf_P(buf, PSTR("%02i"), (uint16_t)(abs(bedlevel.z_values[x][y] - (int16_t)bedlevel.z_values[x][y]) * 100)); - offset_x = cell_width_px / 2 - 3 * (strlen(buf)) - 2; + const int8_t offset_x = cell_width_px / 2 - 3 * (strlen(buf)) - 2; if (!(GRID_MAX_POINTS_X < 10)) DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px - 2 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, F(".")); DWIN_Draw_String(false, font6x12, Color_White, Color_Bg_Blue, start_x_px + 1 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, buf); @@ -597,7 +597,7 @@ void CrealityDWINClass::Draw_Menu(const uint8_t menu, const uint8_t select/*=0*/ active_menu = menu; Clear_Screen(); Draw_Title(Get_Menu_Title(menu)); - LOOP_L_N(i, TROWS) Menu_Item_Handler(menu, i + scrollpos); + for (uint8_t i = 0; i < TROWS; ++i) Menu_Item_Handler(menu, i + scrollpos); DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); } @@ -808,18 +808,18 @@ void CrealityDWINClass::Draw_SD_Item(const uint8_t item, const uint8_t row) { if (item == 0) Draw_Menu_Item(0, ICON_Back, card.flag.workDirIsRoot ? F("Back") : F("..")); else { - card.getfilename_sorted(SD_ORDER(item - 1, card.get_num_Files())); + card.selectFileByIndexSorted(item - 1); char * const filename = card.longest_filename(); - size_t max = MENU_CHAR_LIMIT; - size_t pos = strlen(filename), len = pos; + constexpr uint8_t max = MENU_CHAR_LIMIT; + uint8_t pos = strlen(filename), len = pos; if (!card.flag.filenameIsDir) while (pos && filename[pos] != '.') pos--; len = pos; if (len > max) len = max; char name[len + 1]; - LOOP_L_N(i, len) name[i] = filename[i]; + for (uint8_t i = 0; i < len; ++i) name[i] = filename[i]; if (pos > max) - LOOP_S_L_N(i, len - 3, len) name[i] = '.'; + for (uint8_t i = len - 3; i < len; ++i) name[i] = '.'; name[len] = '\0'; Draw_Menu_Item(row, card.flag.filenameIsDir ? ICON_More : ICON_File, name); } @@ -832,7 +832,7 @@ void CrealityDWINClass::Draw_SD_List(const bool removed/*=false*/) { scrollpos = 0; process = File; if (card.isMounted() && !removed) { - LOOP_L_N(i, _MIN(card.get_num_Files() + 1, TROWS)) + for (int16_t i = 0; i < _MIN(card.get_num_items() + 1, TROWS); ++i) Draw_SD_Item(i, i); } else { @@ -1038,7 +1038,9 @@ void CrealityDWINClass::Update_Status_Bar(const bool refresh/*=false*/) { } } -/* Menu Item Config */ +// +// Menu Item Config +// void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item, bool draw/*=true*/) { const uint8_t row = item - scrollpos; @@ -1107,7 +1109,7 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item #define PREPARE_MANUALLEVEL (PREPARE_HOME + 1) #define PREPARE_ZOFFSET (PREPARE_MANUALLEVEL + ENABLED(HAS_ZOFFSET_ITEM)) #define PREPARE_PREHEAT (PREPARE_ZOFFSET + ENABLED(HAS_PREHEAT)) - #define PREPARE_COOLDOWN (PREPARE_PREHEAT + EITHER(HAS_HOTEND, HAS_HEATED_BED)) + #define PREPARE_COOLDOWN (PREPARE_PREHEAT + ANY(HAS_HOTEND, HAS_HEATED_BED)) #define PREPARE_CHANGEFIL (PREPARE_COOLDOWN + ENABLED(ADVANCED_PAUSE_FEATURE)) #define PREPARE_CUSTOM_MENU (PREPARE_CHANGEFIL + ENABLED(HAS_CUSTOM_MENU)) #define PREPARE_TOTAL PREPARE_CUSTOM_MENU @@ -3060,7 +3062,7 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item #define LEVELING_BACK 0 #define LEVELING_ACTIVE (LEVELING_BACK + 1) - #define LEVELING_GET_TILT (LEVELING_ACTIVE + BOTH(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL)) + #define LEVELING_GET_TILT (LEVELING_ACTIVE + ALL(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL)) #define LEVELING_GET_MESH (LEVELING_GET_TILT + 1) #define LEVELING_MANUAL (LEVELING_GET_MESH + 1) #define LEVELING_VIEW (LEVELING_MANUAL + 1) @@ -3095,7 +3097,7 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item Draw_Checkbox(row, planner.leveling_active); } break; - #if BOTH(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL) + #if ALL(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL) case LEVELING_GET_TILT: if (draw) Draw_Menu_Item(row, ICON_Tilt, F("Autotilt Current Mesh")); @@ -3908,7 +3910,6 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item } break; - #define _PREHEAT_HOTEND_CASE(N) \ case PREHEATHOTEND_##N: \ if (draw) Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_## N ##_LABEL)); \ @@ -4154,7 +4155,7 @@ void CrealityDWINClass::Menu_Control() { if (encoder_diffState == ENCODER_DIFF_CW && selection < Get_Menu_Size(active_menu)) { DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); selection++; // Select Down - if (selection > scrollpos+MROWS) { + if (selection > scrollpos + MROWS) { scrollpos++; DWIN_Frame_AreaMove(1, 2, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); Menu_Item_Handler(active_menu, selection); @@ -4282,7 +4283,7 @@ void CrealityDWINClass::File_Control() { EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState == ENCODER_DIFF_NO) { if (selection > 0) { - card.getfilename_sorted(SD_ORDER(selection - 1, card.get_num_Files())); + card.selectFileByIndexSorted(selection - 1); char * const filename = card.longest_filename(); size_t len = strlen(filename); size_t pos = len; @@ -4301,7 +4302,7 @@ void CrealityDWINClass::File_Control() { } return; } - if (encoder_diffState == ENCODER_DIFF_CW && selection < card.get_num_Files()) { + if (encoder_diffState == ENCODER_DIFF_CW && selection < card.get_num_items()) { DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); if (selection > 0) { DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(selection - scrollpos) - 14, 271, MBASE(selection - scrollpos) + 28); @@ -4341,7 +4342,7 @@ void CrealityDWINClass::File_Control() { } } else { - card.getfilename_sorted(SD_ORDER(selection - 1, card.get_num_Files())); + card.selectFileByIndexSorted(selection - 1); if (card.flag.filenameIsDir) { card.cd(card.filename); Draw_SD_List(); @@ -4390,7 +4391,7 @@ void CrealityDWINClass::Print_Screen_Control() { #endif TERN_(HAS_FAN, thermalManager.fan_speed[0] = pausefan); planner.synchronize(); - TERN_(SDSUPPORT, queue.inject(F("M24"))); + TERN_(HAS_MEDIA, queue.inject(F("M24"))); #endif } else { @@ -4428,7 +4429,7 @@ void CrealityDWINClass::Popup_Control() { #endif #if ENABLED(PARK_HEAD_ON_PAUSE) Popup_Handler(Home, true); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (IS_SD_PRINTING()) card.pauseSDPrint(); #endif planner.synchronize(); @@ -4580,7 +4581,9 @@ void CrealityDWINClass::Confirm_Control() { DWIN_UpdateLCD(); } -/* In-Menu Value Modification */ +// +// In-Menu Value Modification +// void CrealityDWINClass::Setup_Value(const_float_t value, const_float_t min, const_float_t max, const_float_t unit, const uint8_t type) { if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Ki) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Ki)) @@ -4639,16 +4642,18 @@ void CrealityDWINClass::Modify_Option(const uint8_t value, const char * const * Draw_Option(value, options, selection - scrollpos, true); } -/* Main Functions */ +// +// Main Functions +// void CrealityDWINClass::Update_Status(const char * const text) { if (strncmp_P(text, PSTR(""), 3) == 0) { - LOOP_L_N(i, _MIN((size_t)LONG_FILENAME_LENGTH, strlen(text))) filename[i] = text[i + 3]; + for (uint8_t i = 0; i < _MIN((size_t)LONG_FILENAME_LENGTH, strlen(text)); ++i) filename[i] = text[i + 3]; filename[_MIN((size_t)LONG_FILENAME_LENGTH - 1, strlen(text))] = '\0'; Draw_Print_Filename(true); } else { - LOOP_L_N(i, _MIN((size_t)64, strlen(text))) statusmsg[i] = text[i]; + for (uint8_t i = 0; i < _MIN((size_t)64, strlen(text)); ++i) statusmsg[i] = text[i]; statusmsg[_MIN((size_t)64, strlen(text))] = '\0'; } } diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp b/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp index 38a8eafe2366..10a478f75650 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp @@ -25,7 +25,7 @@ #if IS_DWIN_MARLINUI #include "dwin_string.h" -//#include "../../fontutils.h" +//#include "../../utf8.h" char DWIN_String::data[]; uint16_t DWIN_String::span; @@ -44,7 +44,7 @@ uint8_t read_byte(const uint8_t *byte) { return *byte; } * Add a string, applying substitutions for the following characters: * * $ displays the clipped string given by fstr or cstr - * = displays '0'....'10' for indexes 0 - 10 + * { displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) * @ displays an axis name such as XYZUVW, or E for an extruder @@ -57,9 +57,9 @@ void DWIN_String::add(const char *tpl, const int8_t index, const char *cstr/*=nu if (wc > 255) wc |= 0x0080; const uint8_t ch = uint8_t(wc & 0x00FF); - if (ch == '=' || ch == '~' || ch == '*') { + if (ch == '{' || ch == '~' || ch == '*') { if (index >= 0) { - int8_t inum = index + ((ch == '=') ? 0 : LCD_FIRST_TOOL); + int8_t inum = index + ((ch == '{') ? 0 : LCD_FIRST_TOOL); if (ch == '*') add_character('E'); if (inum >= 10) { add_character('0' + (inum / 10)); inum %= 10; } add_character('0' + inum); diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h index 686b1aa2b17a..e61382e1578a 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h @@ -23,7 +23,7 @@ // TODO: Make AVR-compatible with separate ROM / RAM string methods -#include "../../fontutils.h" +#include "../../utf8.h" #include "../../marlinui.h" #include @@ -525,7 +525,6 @@ const dwin_charmap_t g_dwin_charmap_device[] PROGMEM = { {IV('⭢'), 0xC7, 0}, {IV('⭣'), 0xC6, 0}, - {IV('⯆'), 0xF5, 0}, {IV('⯇'), 0xF7, 0}, // ⯅ {IV('⯈'), 0xF6, 0}, @@ -576,7 +575,6 @@ const dwin_charmap_t g_dwin_charmap_device[] PROGMEM = { //{IV(''), 0x9E, 0}, //{IV(''), 0x9F, 0}, - {IV('¼'), 0xF0, 0}, // 00BC {IV('⅓'), 0xF1, 0}, {IV('½'), 0xF2, 0}, // 00BD diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp index e822371c0df1..b3c474d5bcdb 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp @@ -30,7 +30,7 @@ //#include "../../lcdprint.h" #include "lcdprint_dwin.h" -#include "../../fontutils.h" +#include "../../utf8.h" #include "../../../libs/numtostr.h" #include "../../marlinui.h" @@ -39,7 +39,7 @@ #include "../../../module/temperature.h" #include "../../../module/printcounter.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../../../libs/duration_t.h" #endif @@ -449,7 +449,7 @@ void MarlinUI::draw_status_message(const bool blink) { if (yes) draw_boxed_string(true, yes, yesno); } - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA void MenuItem_sdbase::draw(const bool sel, const uint8_t row, FSTR_P const, CardReader &theCard, const bool isDir) { if (mark_as_selected(row, sel)) { @@ -469,7 +469,7 @@ void MarlinUI::draw_status_message(const bool blink) { } } - #endif // SDSUPPORT + #endif // HAS_MEDIA #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -565,7 +565,7 @@ void MarlinUI::draw_status_message(const bool blink) { #endif // AUTO_BED_LEVELING_UBL - #if EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + #if ANY(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) void MarlinUI::zoffset_overlay(const int8_t dir) { const int rot_up = TERN(OVERLAY_GFX_REVERSE, ICON_RotateCCW, ICON_RotateCW), diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp index 5ec94b853f10..ac31506d6eca 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp @@ -29,7 +29,7 @@ #include "dwin_string.h" #include "lcdprint_dwin.h" -#include "../../fontutils.h" +#include "../../utf8.h" #include "../../../libs/numtostr.h" #include "../../marlinui.h" @@ -39,7 +39,7 @@ #include "../../../module/printcounter.h" #include "../../../module/planner.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../../../libs/duration_t.h" #endif @@ -192,7 +192,7 @@ FORCE_INLINE void _draw_heater_status(const heater_id_t heater, const uint16_t x #endif celsius_float_t tc = 0, tt = 0; - bool isBed = (DISABLED(HAS_HOTEND) && ENABLED(HAS_HEATED_BED)) || (BOTH(HAS_HOTEND, HAS_HEATED_BED) && heater < 0), + bool isBed = (DISABLED(HAS_HOTEND) && ENABLED(HAS_HEATED_BED)) || (ALL(HAS_HOTEND, HAS_HEATED_BED) && heater < 0), ta = false, c_draw, t_draw, i_draw; c_draw = t_draw = i_draw = !ui.did_first_redraw; if (isBed) { diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp index 47b104c5ba47..a675130a1fa9 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp @@ -46,7 +46,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, HAS_LEVELING) +#if ALL(DWIN_LCD_PROUI, HAS_LEVELING) #include "../../marlinui.h" #include "../../../core/types.h" @@ -89,9 +89,10 @@ char cmd[MAX_CMD_SIZE+16], str_1[16], str_2[16], str_3[16]; struct linear_fit_data lsf_results; incremental_LSF_reset(&lsf_results); GRID_LOOP(x, y) { - if (!isnan(bedlevel.z_values[x][y])) { + const float z = bedlevel.z_values[x][y]; + if (!isnan(z)) { xy_pos_t rpos = { bedlevel.get_mesh_x(x), bedlevel.get_mesh_y(y) }; - incremental_LSF(&lsf_results, rpos, bedlevel.z_values[x][y]); + incremental_LSF(&lsf_results, rpos, z); } } diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h index 6e642f030c18..f307bd16e6a8 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h @@ -1,4 +1,4 @@ -/* +/** * Marlin 3D Printer Firmware * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 4a332f973e20..a399cd1e9727 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -62,7 +62,7 @@ #warning "MESH_EDIT_MENU is recommended with ProUI." #endif -#include "../../fontutils.h" +#include "../../utf8.h" #include "../../marlinui.h" #include "../../../sd/cardreader.h" @@ -346,7 +346,7 @@ void HMI_SetLanguageCache() { } void HMI_SetLanguage() { - #if BOTH(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) + #if ALL(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) BL24CXX::read(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); #endif HMI_SetLanguageCache(); @@ -355,7 +355,7 @@ void HMI_SetLanguage() { void HMI_ToggleLanguage() { HMI_flag.language = HMI_IsChinese() ? DWIN_ENGLISH : DWIN_CHINESE; HMI_SetLanguageCache(); - #if BOTH(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) + #if ALL(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); #endif } @@ -530,8 +530,7 @@ void DWIN_ResetStatusLine() { // Djb2 hash algorithm uint32_t GetHash(char * str) { uint32_t hash = 5381; - char c; - while ((c = *str++)) hash = ((hash << 5) + hash) + c; /* hash * 33 + c */ + for (char c; (c = *str++);) hash = ((hash << 5) + hash) + c; /* hash * 33 + c */ return hash; } @@ -630,7 +629,7 @@ void DWIN_Print_Header(const char *text = nullptr) { static char headertxt[31] = ""; // Print header text if (text) { const int8_t size = _MIN(30U, strlen_P(text)); - LOOP_L_N(i, size) headertxt[i] = text[i]; + for (uint8_t i = 0; i < size; ++i) headertxt[i] = text[i]; headertxt[size] = '\0'; } if (checkkey == PrintProcess || checkkey == PrintDone) { @@ -793,7 +792,8 @@ void update_variable() { _new_hotend_target = _hotendtarget != ht; if (_new_hotend_temp) _hotendtemp = hc; if (_new_hotend_target) _hotendtarget = ht; - #endif + #endif // HAS_HOTEND + #if HAS_HEATED_BED static celsius_t _bedtemp = 0, _bedtarget = 0; const celsius_t bc = thermalManager.wholeDegBed(), @@ -802,7 +802,8 @@ void update_variable() { _new_bed_target = _bedtarget != bt; if (_new_bed_temp) _bedtemp = bc; if (_new_bed_target) _bedtarget = bt; - #endif + #endif // HAS_HEATED_BED + #if HAS_FAN static uint8_t _fanspeed = 0; const bool _new_fanspeed = _fanspeed != thermalManager.fan_speed[0]; @@ -872,7 +873,7 @@ void SetMediaAutoMount() { } inline uint16_t nr_sd_menu_items() { - return _MIN(card.get_num_Files() + !card.flag.workDirIsRoot, MENU_MAX_ITEMS); + return _MIN(card.get_num_items() + !card.flag.workDirIsRoot, MENU_MAX_ITEMS); } void make_name_without_ext(char *dst, char *src, size_t maxlen=MENU_CHAR_LIMIT) { @@ -919,7 +920,7 @@ void onClickSDItem() { if (hasUpDir && CurrentMenu->selected == 1) return SDCard_Up(); else { const uint16_t filenum = CurrentMenu->selected - 1 - hasUpDir; - card.getfilename_sorted(SD_ORDER(filenum, card.get_num_Files())); + card.selectFileByIndexSorted(filenum); // Enter that folder! if (card.flag.filenameIsDir) return SDCard_Folder(card.filename); @@ -962,7 +963,7 @@ void onClickSDItem() { last_itemselected = selected; if (selected >= 1 + hasUpDir) { const int8_t filenum = selected - 1 - hasUpDir; // Skip "Back" and ".." - card.getfilename_sorted(SD_ORDER(filenum, card.get_num_Files())); + card.selectFileByIndexSorted(filenum); make_name_without_ext(shift_name, card.longest_filename(), LONG_FILENAME_LENGTH); shift_len = strlen(shift_name); shift_amt = 0; @@ -976,8 +977,11 @@ void onClickSDItem() { shift_amt = shift_new; // Set new scroll } } -#else + +#else // !SCROLL_LONG_FILENAMES + char shift_name[FILENAME_LENGTH + 1] = ""; + #endif void onDrawFileName(MenuItemClass* menuitem, int8_t line) { @@ -987,7 +991,7 @@ void onDrawFileName(MenuItemClass* menuitem, int8_t line) { } else { uint8_t icon; - card.getfilename_sorted(SD_ORDER(menuitem->pos - is_subdir - 1, card.get_num_Files())); + card.selectFileByIndexSorted(menuitem->pos - is_subdir - 1); make_name_without_ext(shift_name, card.longest_filename()); icon = card.flag.filenameIsDir ? ICON_Folder : card.fileIsBinary() ? ICON_Binary : ICON_File; Draw_Menu_Line(line, icon, shift_name); @@ -999,9 +1003,8 @@ void Draw_Print_File_Menu() { if (card.isMounted()) { if (SET_MENU(FileMenu, MSG_MEDIA_MENU, nr_sd_menu_items() + 1)) { BACK_ITEM(Goto_Main_Menu); - LOOP_L_N(i, nr_sd_menu_items()) { + for (uint8_t i = 0; i < nr_sd_menu_items(); ++i) MenuItemAdd(onDrawFileName, onClickSDItem); - } } UpdateMenu(FileMenu); TERN_(DASH_REDRAW, DWIN_RedrawDash()); @@ -1101,7 +1104,7 @@ void Draw_Info_Menu() { DWINUI::Draw_CenteredString(122, F(MACHINE_SIZE)); DWINUI::Draw_CenteredString(195, F(SHORT_BUILD_VERSION)); - LOOP_L_N(i, 3) { + for (uint8_t i = 0; i < 3; ++i) { DWINUI::Draw_Icon(ICON_PrintSize + i, ICOX, 99 + i * 73); DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MBASE(2) + i * 73, 240); } @@ -1403,7 +1406,6 @@ void EachMomentUpdate() { #endif // POWER_LOSS_RECOVERY - void DWIN_HandleScreen() { switch (checkkey) { case MainMenu: HMI_MainMenu(); break; @@ -1468,7 +1470,7 @@ void DWIN_LevelingStart() { HMI_SaveProcessID(Leveling); Title.ShowCaption(GET_TEXT_F(MSG_BED_LEVELING)); DWIN_Show_Popup(ICON_AutoLeveling, GET_TEXT_F(MSG_BED_LEVELING), GET_TEXT_F(MSG_PLEASE_WAIT)); - #if BOTH(AUTO_BED_LEVELING_UBL, PREHEAT_BEFORE_LEVELING) + #if ALL(AUTO_BED_LEVELING_UBL, PREHEAT_BEFORE_LEVELING) #if HAS_HOTEND if (thermalManager.degTargetHotend(0) < LEVELING_NOZZLE_TEMP) thermalManager.setTargetHotend(LEVELING_NOZZLE_TEMP, 0); @@ -1527,7 +1529,7 @@ void DWIN_LevelingDone() { } #endif -#if EITHER(PIDTEMP, PIDTEMPBED) +#if ANY(PIDTEMP, PIDTEMPBED) void DWIN_PidTuning(pidresult_t result) { HMI_value.pidresult = result; @@ -1676,10 +1678,10 @@ void DWIN_SetDataDefaults() { TERN_(BAUD_RATE_GCODE, SetBaud250K()); HMI_data.FullManualTramming = false; HMI_data.MediaAutoMount = ENABLED(HAS_SD_EXTENDER); - #if BOTH(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) + #if ALL(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) HMI_data.z_after_homing = DEF_Z_AFTER_HOMING; #endif - #if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) + #if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) TERN_(LED_COLOR_PRESETS, leds.set_default()); ApplyLEDColor(); #endif @@ -1699,7 +1701,7 @@ void DWIN_CopySettingsFrom(const char * const buff) { TERN_(PREVENT_COLD_EXTRUSION, ApplyExtMinT()); feedrate_percentage = 100; TERN_(BAUD_RATE_GCODE, HMI_SetBaudRate()); - #if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) + #if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) leds.set_color( HMI_data.Led_Color.r, HMI_data.Led_Color.g, @@ -1961,7 +1963,7 @@ void AutoHome() { queue.inject_P(G28_STR); } void HomeX() { queue.inject(F("G28X")); } void HomeY() { queue.inject(F("G28Y")); } void HomeZ() { queue.inject(F("G28Z")); } - #if BOTH(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) + #if ALL(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) void ApplyZAfterHoming() { HMI_data.z_after_homing = MenuData.Value; }; void SetZAfterHoming() { SetIntOnClick(0, 20, HMI_data.z_after_homing, ApplyZAfterHoming); } #endif @@ -1979,14 +1981,14 @@ void AutoHome() { queue.inject_P(G28_STR); } void ApplyZOffset() { TERN_(EEPROM_SETTINGS, settings.save()); } void LiveZOffset() { - #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) const_float_t step_zoffset = round((MenuData.Value / 100.0f) * planner.settings.axis_steps_per_mm[Z_AXIS]) - babystep.accum; if (BABYSTEP_ALLOWED()) babystep.add_steps(Z_AXIS, step_zoffset); //DEBUG_ECHOLNF(F("BB Steps: "), step_zoffset); #endif } void SetZOffset() { - #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) babystep.accum = round(planner.settings.axis_steps_per_mm[Z_AXIS] * BABY_Z_VAR); #endif SetPFloatOnClick(Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, 2, ApplyZOffset, LiveZOffset); @@ -2057,7 +2059,7 @@ void SetMoveZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick(Z_MIN_POS, Z_MAX_POS } #endif -#if EITHER(PIDTEMP, PIDTEMPBED) +#if ANY(PIDTEMP, PIDTEMPBED) void SetPID(celsius_t t, heater_id_t h) { char cmd[53] = ""; char str_1[5] = "", str_2[5] = ""; @@ -2114,7 +2116,7 @@ void SetMoveZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick(Z_MIN_POS, Z_MAX_POS #endif #if ENABLED(LED_CONTROL_MENU) - #if !BOTH(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) + #if !ALL(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) void SetLedStatus() { leds.toggle(); Show_Chkb_Line(leds.lights_on); @@ -2394,9 +2396,9 @@ void TramC () { Tram(4); } DWINUI::Draw_CenteredString(160, F("and relative heights")); safe_delay(1000); float avg = 0.0f; - LOOP_L_N(x, 2) LOOP_L_N(y, 2) avg += zval[x][y]; + for (uint8_t x = 0; x < 2; ++x) for (uint8_t y = 0; y < 2; ++y) avg += zval[x][y]; avg /= 4.0f; - LOOP_L_N(x, 2) LOOP_L_N(y, 2) zval[x][y] -= avg; + for (uint8_t x = 0; x < 2; ++x) for (uint8_t y = 0; y < 2; ++y) zval[x][y] -= avg; MeshViewer.DrawMesh(zval, 2, 2); ui.reset_status(); @@ -2409,7 +2411,7 @@ void TramC () { Tram(4); } float max = 0; FSTR_P plabel; bool s = true; - LOOP_L_N(x, 2) LOOP_L_N(y, 2) { + for (uint8_t x = 0; x < 2; ++x) for (uint8_t y = 0; y < 2; ++y) { const float d = ABS(zval[x][y]); if (max < d) { s = (zval[x][y] >= 0); @@ -2523,7 +2525,7 @@ void SetStepsZ() { HMI_value.axis = Z_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP void SetBedPidT() { SetPIntOnClick(MIN_BEDTEMP, MAX_BEDTEMP); } #endif -#if EITHER(PIDTEMP, PIDTEMPBED) +#if ANY(PIDTEMP, PIDTEMPBED) void SetPidCycles() { SetPIntOnClick(3, 50); } void SetKp() { SetPFloatOnClick(0, 1000, 2); } void ApplyPIDi() { @@ -2632,7 +2634,7 @@ void onDrawAutoHome(MenuItemClass* menuitem, int8_t line) { } #if HAS_ZOFFSET_ITEM - #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) void onDrawZOffset(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) menuitem->SetFrame(1, 174, 164, 223, 177); onDrawPFloat2Menu(menuitem, line); @@ -2694,7 +2696,7 @@ void onDrawGetColorItem(MenuItemClass* menuitem, int8_t line) { DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MYPOS(line + 1), 240); } -#if EITHER(PIDTEMP, PIDTEMPBED) +#if ANY(PIDTEMP, PIDTEMPBED) void onDrawPIDi(MenuItemClass* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 2, unscalePID_i(*(float*)static_cast(menuitem)->value)); } void onDrawPIDd(MenuItemClass* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 2, unscalePID_d(*(float*)static_cast(menuitem)->value)); } #endif @@ -3207,7 +3209,7 @@ void Draw_GetColor_Menu() { DWIN_Draw_Rectangle(1, *MenuData.P_Int, 20, 315, DWIN_WIDTH - 20, 335); } -#if BOTH(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) +#if ALL(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) void Draw_CaseLight_Menu() { checkkey = Menu; @@ -3227,7 +3229,7 @@ void Draw_GetColor_Menu() { checkkey = Menu; if (SET_MENU(LedControlMenu, MSG_LED_CONTROL, 10)) { BACK_ITEM(Draw_Control_Menu); - #if !BOTH(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) + #if !ALL(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) EDIT_ITEM(ICON_LedControl, MSG_LEDS, onDrawChkbMenu, SetLedStatus, &leds.lights_on); #endif #if HAS_COLOR_LEDS @@ -3616,7 +3618,7 @@ void Draw_Steps_Menu() { } void UBLSmartFillMesh() { - LOOP_L_N(x, GRID_MAX_POINTS_Y) bedlevel.smart_fill_mesh(); + for (uint8_t x = 0; x < GRID_MAX_POINTS_Y; ++x) bedlevel.smart_fill_mesh(); LCD_MESSAGE(MSG_UBL_MESH_FILLED); } diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/e3v2/proui/dwin.h index a742d859605e..6bf28a938cad 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.h +++ b/Marlin/src/lcd/e3v2/proui/dwin.h @@ -35,7 +35,7 @@ #include "../common/encoder.h" #include "../../../libs/BL24CXX.h" -#if EITHER(BABYSTEPPING, HAS_BED_PROBE) +#if ANY(BABYSTEPPING, HAS_BED_PROBE) #define HAS_ZOFFSET_ITEM 1 #if !HAS_BED_PROBE #define JUST_BABYSTEP 1 @@ -128,10 +128,10 @@ typedef struct { bool FullManualTramming = false; bool MediaAutoMount = ENABLED(HAS_SD_EXTENDER); - #if BOTH(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) + #if ALL(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) uint8_t z_after_homing = DEF_Z_AFTER_HOMING; #endif - #if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) + #if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) LEDColor Led_Color = Def_Leds_Color; #endif } HMI_data_t; @@ -142,7 +142,7 @@ static constexpr size_t eeprom_data_size = sizeof(HMI_data_t); typedef struct { int8_t Color[3]; // Color components #if HAS_PID_HEATING - tempcontrol_t pidresult = PID_DONE; + pidresult_t pidresult = PID_DONE; #endif uint8_t Select = 0; // Auxiliary selector variable AxisEnum axis = X_AXIS; // Axis Select @@ -211,7 +211,7 @@ void ParkHead(); #if HAS_ONESTEP_LEVELING void Trammingwizard(); #endif -#if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) +#if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) void ApplyLEDColor(); #endif #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -319,7 +319,7 @@ void Draw_FilSet_Menu(); void Draw_PhySet_Menu(); void Draw_SelectColors_Menu(); void Draw_GetColor_Menu(); -#if BOTH(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) +#if ALL(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) void Draw_CaseLight_Menu(); #endif #if ENABLED(LED_CONTROL_MENU) @@ -340,7 +340,7 @@ void Draw_MaxAccel_Menu(); void Draw_MaxJerk_Menu(); #endif void Draw_Steps_Menu(); -#if EITHER(HAS_BED_PROBE, BABYSTEPPING) +#if ANY(HAS_BED_PROBE, BABYSTEPPING) void Draw_ZOffsetWiz_Menu(); #endif #if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) @@ -358,7 +358,7 @@ void Draw_Steps_Menu(); // PID #if HAS_PID_HEATING - void DWIN_PidTuning(tempcontrol_t result); + void DWIN_PidTuning(pidresult_t result); #if ENABLED(PIDTEMP) void Draw_HotendPID_Menu(); #endif @@ -366,4 +366,3 @@ void Draw_Steps_Menu(); void Draw_BedPID_Menu(); #endif #endif -#endif diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/e3v2/proui/dwin_defines.h index de3f40e2814b..f983332a7066 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_defines.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_defines.h @@ -19,6 +19,8 @@ * along with this program. If not, see . * */ +#pragma once + /** * DWIN general defines and data structs for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) @@ -26,8 +28,6 @@ * Date: 2022/08/08 */ -#pragma once - //#define DEBUG_DWIN 1 //#define NEED_HEX_PRINT 1 @@ -66,7 +66,7 @@ #define Def_Indicator_Color Color_White #define Def_Coordinate_Color Color_White #define Def_Button_Color RGB( 0, 23, 16) -#if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) +#if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) #define Def_Leds_Color LEDColorWhite() #endif #if ENABLED(CASELIGHT_USES_BRIGHTNESS) @@ -80,4 +80,3 @@ #define DEF_HOTENDPIDT TERN(PREHEAT_1_TEMP_BED, PREHEAT_1_TEMP_HOTEND, 195) #define DEF_BEDPIDT TERN(PREHEAT_1_TEMP_BED, PREHEAT_1_TEMP_HOTEND, 60) #define DEF_PIDCYCLES 5 - diff --git a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp index 6cdafc8a935f..ad2cd2709348 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp @@ -126,9 +126,9 @@ void DWIN_WriteToMem(uint8_t mem, uint16_t addr, uint16_t length, uint8_t *data) DWIN_Byte(i, mem); DWIN_Word(i, addr + indx); // start address of the data block ++i; - LOOP_L_N(j, i) { LCD_SERIAL.write(DWIN_SendBuf[j]); delayMicroseconds(1); } // Buf header + for (uint8_t j = 0; j < i; ++j) { LCD_SERIAL.write(DWIN_SendBuf[j]); delayMicroseconds(1); } // Buf header for (uint16_t j = indx; j <= indx + to_send - 1; j++) LCD_SERIAL.write(*(data + j)); delayMicroseconds(1); // write block of data - LOOP_L_N(j, 4) { LCD_SERIAL.write(DWIN_BufTail[j]); delayMicroseconds(1); } + for (uint8_t j = 0; j < 4; ++j) { LCD_SERIAL.write(DWIN_BufTail[j]); delayMicroseconds(1); } block++; pending -= to_send; } diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.h b/Marlin/src/lcd/e3v2/proui/dwinui.h index 55345a789985..5eb739571761 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.h +++ b/Marlin/src/lcd/e3v2/proui/dwinui.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * DWIN Enhanced implementation for PRO UI @@ -27,8 +28,6 @@ * Date: 2022/07/05 */ -#pragma once - #include "../../../inc/MarlinConfigPre.h" #include "../common/dwin_set.h" diff --git a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp index 0945d6977814..b960e40610da 100644 --- a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp +++ b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp @@ -29,7 +29,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, HAS_ESDIAG) +#if ALL(DWIN_LCD_PROUI, HAS_ESDIAG) #include "endstop_diag.h" @@ -72,13 +72,13 @@ void ESDiagClass::Draw() { DWINUI::Draw_Button(BTN_Continue, 86, 250); DWINUI::cursor.y = 80; #define ES_LABEL(S) draw_es_label(F(STR_##S)) - #if HAS_X_MIN + #if USE_X_MIN ES_LABEL(X_MIN); #endif - #if HAS_Y_MIN + #if USE_Y_MIN ES_LABEL(Y_MIN); #endif - #if HAS_Z_MIN + #if USE_Z_MIN ES_LABEL(Z_MIN); #endif #if HAS_FILAMENT_SENSOR @@ -90,13 +90,13 @@ void ESDiagClass::Draw() { void ESDiagClass::Update() { DWINUI::cursor.y = 80; #define ES_REPORT(S) draw_es_state(READ(S##_PIN) != S##_ENDSTOP_INVERTING) - #if HAS_X_MIN + #if USE_X_MIN ES_REPORT(X_MIN); #endif - #if HAS_Y_MIN + #if USE_Y_MIN ES_REPORT(Y_MIN); #endif - #if HAS_Z_MIN + #if USE_Z_MIN ES_REPORT(Z_MIN); #endif #if HAS_FILAMENT_SENSOR diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp index 6411b669bbc8..ec3c612f8e21 100644 --- a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp @@ -21,7 +21,7 @@ */ /** - * DWIN g-code thumbnail preview + * DWIN G-code thumbnail preview * Author: Miguel A. Risco-Castillo * version: 3.1.2 * Date: 2022/09/03 @@ -44,7 +44,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, HAS_GCODE_PREVIEW) +#if ALL(DWIN_LCD_PROUI, HAS_GCODE_PREVIEW) #include "../../../core/types.h" #include "../../marlinui.h" diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.h b/Marlin/src/lcd/e3v2/proui/gcode_preview.h index c1949c5abc12..2452797d0c62 100644 --- a/Marlin/src/lcd/e3v2/proui/gcode_preview.h +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.h @@ -1,12 +1,13 @@ /** - * DWIN g-code thumbnail preview - * Author: Miguel A. Risco-Castillo - * version: 3.1.2 - * Date: 2022/09/03 + * Marlin 3D Printer Firmware + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm * * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU 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,14 +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 . * - * For commercial applications additional licenses can be requested */ - #pragma once +/** + * DWIN G-code thumbnail preview + * Author: Miguel A. Risco-Castillo + * version: 3.1.2 + * Date: 2022/09/03 + */ + void Preview_DrawFromSD(); void Preview_Invalidate(); bool Preview_Valid(); diff --git a/Marlin/src/lcd/e3v2/proui/lockscreen.cpp b/Marlin/src/lcd/e3v2/proui/lockscreen.cpp index 85f35582b268..abf67ad9aff4 100644 --- a/Marlin/src/lcd/e3v2/proui/lockscreen.cpp +++ b/Marlin/src/lcd/e3v2/proui/lockscreen.cpp @@ -29,7 +29,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, HAS_LOCKSCREEN) +#if ALL(DWIN_LCD_PROUI, HAS_LOCKSCREEN) #include "dwin_defines.h" #include "dwinui.h" diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp index 18cdffd00d62..6296dbd9d697 100644 --- a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp +++ b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp @@ -29,7 +29,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, HAS_MESH) +#if ALL(DWIN_LCD_PROUI, HAS_MESH) #include "../../../core/types.h" #include "../../marlinui.h" @@ -60,7 +60,7 @@ void MeshViewerClass::DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8 #define DrawMeshHLine(yp) DWIN_Draw_HLine(HMI_data.SplitLine_Color, px(0), py(yp), DWIN_WIDTH - 2 * mx) #define DrawMeshVLine(xp) DWIN_Draw_VLine(HMI_data.SplitLine_Color, px(xp), py(sizey - 1), DWIN_WIDTH - 2 * my) int16_t maxz =-32000; int16_t minz = 32000; - LOOP_L_N(y, sizey) LOOP_L_N(x, sizex) { + for (uint8_t y = 0; y < sizey; ++y) for (uint8_t x = 0; x < sizex; ++x) { const float v = isnan(zval[x][y]) ? 0 : round(zval[x][y] * 100); zmesh[x][y] = v; NOLESS(maxz, v); @@ -70,11 +70,11 @@ void MeshViewerClass::DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8 min = (float)minz / 100; DWINUI::ClearMainArea(); DWIN_Draw_Rectangle(0, HMI_data.SplitLine_Color, px(0), py(0), px(sizex - 1), py(sizey - 1)); - LOOP_S_L_N(x, 1, sizex - 1) DrawMeshVLine(x); - LOOP_S_L_N(y, 1, sizey - 1) DrawMeshHLine(y); - LOOP_L_N(y, sizey) { + for (uint8_t x = 1; x < sizex - 1; ++x) DrawMeshVLine(x); + for (uint8_t y = 1; y < sizey - 1; ++y) DrawMeshHLine(y); + for (uint8_t y = 0; y < sizey; ++y) { hal.watchdog_refresh(); - LOOP_L_N(x, sizex) { + for (uint8_t x = 0; x < sizex; ++x) { uint16_t color = DWINUI::RainbowInt(zmesh[x][y], _MIN(-5, minz), _MAX(5, maxz)); uint8_t radius = rm(zmesh[x][y]); DWINUI::Draw_FillCircle(color, px(x), py(y), radius); diff --git a/Marlin/src/lcd/e3v2/proui/plot.cpp b/Marlin/src/lcd/e3v2/proui/plot.cpp index 75917320a45f..bb93ca565306 100644 --- a/Marlin/src/lcd/e3v2/proui/plot.cpp +++ b/Marlin/src/lcd/e3v2/proui/plot.cpp @@ -44,7 +44,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, HAS_PIDPLOT) +#if ALL(DWIN_LCD_PROUI, HAS_PIDPLOT) #include "plot.h" #include "../../../core/types.h" diff --git a/Marlin/src/lcd/e3v2/proui/plot.h b/Marlin/src/lcd/e3v2/proui/plot.h index ea15255fe53a..d071ff372328 100644 --- a/Marlin/src/lcd/e3v2/proui/plot.h +++ b/Marlin/src/lcd/e3v2/proui/plot.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * DWIN Single var plot @@ -41,7 +42,6 @@ * * For commercial applications additional licenses can be requested */ -#pragma once #include "dwinui.h" diff --git a/Marlin/src/lcd/e3v2/proui/printstats.cpp b/Marlin/src/lcd/e3v2/proui/printstats.cpp index 638cd3420809..7f45fa71ef1b 100644 --- a/Marlin/src/lcd/e3v2/proui/printstats.cpp +++ b/Marlin/src/lcd/e3v2/proui/printstats.cpp @@ -29,7 +29,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, PRINTCOUNTER) +#if ALL(DWIN_LCD_PROUI, PRINTCOUNTER) #include "printstats.h" diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp index 75061c162a7a..70ca6b37daf6 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp @@ -49,7 +49,7 @@ namespace ExtUI { void onMediaError() { Chiron.MediaEvent(AC_media_error); } void onMediaRemoved() { Chiron.MediaEvent(AC_media_removed); } - void onPlayTone(const uint16_t frequency, const uint16_t duration) { + void onPlayTone(const uint16_t frequency, const uint16_t duration/*=0*/) { #if ENABLED(SPEAKER) ::tone(BEEPER_PIN, frequency, duration); #endif @@ -94,20 +94,22 @@ namespace ExtUI { // Called after loading or resetting stored settings } - void onSettingsStored(bool success) { + void onSettingsStored(const bool success) { // Called after the entire EEPROM has been written, // whether successful or not. } - void onSettingsLoaded(bool success) { + void onSettingsLoaded(const bool success) { // Called after the entire EEPROM has been read, // whether successful or not. } - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated //SERIAL_ECHOLNPGM("onMeshUpdate() x:", xpos, " y:", ypos, " z:", zval); @@ -120,6 +122,12 @@ namespace ExtUI { #endif #if ENABLED(POWER_LOSS_RECOVERY) + void onSetPowerLoss(const bool onoff) { + // Called when power-loss is enabled/disabled + } + void onPowerLoss() { + // Called when power-loss state is detected + } // Called on resume from power-loss void onPowerLossResume() { Chiron.PowerLossRecovery(); } #endif diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp index 40a670b5b073..36b4147b30a6 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp @@ -41,7 +41,7 @@ namespace ExtUI { void onMediaInserted() { AnycubicTFT.OnSDCardStateChange(true); } void onMediaError() { AnycubicTFT.OnSDCardError(); } void onMediaRemoved() { AnycubicTFT.OnSDCardStateChange(false); } - void onPlayTone(const uint16_t frequency, const uint16_t duration) { + void onPlayTone(const uint16_t frequency, const uint16_t duration/*=0*/) { TERN_(SPEAKER, ::tone(BEEPER_PIN, frequency, duration)); } void onPrintTimerStarted() { AnycubicTFT.OnPrintTimerStarted(); } @@ -81,21 +81,22 @@ namespace ExtUI { // Called after loading or resetting stored settings } - void onSettingsStored(bool success) { + void onSettingsStored(const bool success) { // Called after the entire EEPROM has been written, // whether successful or not. } - void onSettingsLoaded(bool success) { + void onSettingsLoaded(const bool success) { // Called after the entire EEPROM has been read, // whether successful or not. } - #if HAS_MESH - + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated } @@ -106,6 +107,12 @@ namespace ExtUI { #endif #if ENABLED(POWER_LOSS_RECOVERY) + void onSetPowerLoss(const bool onoff) { + // Called when power-loss is enabled/disabled + } + void onPowerLoss() { + // Called when power-loss state is detected + } void onPowerLossResume() { // Called on resume from power-loss } diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp index 03997fa95bea..da294e43e7e9 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -92,7 +92,7 @@ void AnycubicTFTClass::OnSetup() { delay_ms(10); // Init the state of the key pins running on the TFT - #if BOTH(SDSUPPORT, HAS_SD_DETECT) + #if ALL(HAS_MEDIA, HAS_SD_DETECT) SET_INPUT_PULLUP(SD_DETECT_PIN); #endif #if ENABLED(FILAMENT_RUNOUT_SENSOR) @@ -174,7 +174,7 @@ void AnycubicTFTClass::OnUserConfirmRequired(const char * const msg) { SERIAL_ECHOLNPGM("TFT Serial Debug: OnUserConfirmRequired triggered... ", msg); #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA /** * Need to handle the process of following states * "Nozzle Parked" @@ -378,7 +378,7 @@ void AnycubicTFTClass::HandleSpecialMenu() { } void AnycubicTFTClass::RenderCurrentFileList() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA uint16_t selectedNumber = 0; SelectedDirectory[0] = 0; SelectedFile[0] = 0; @@ -402,7 +402,7 @@ void AnycubicTFTClass::RenderCurrentFileList() { RenderCurrentFolder(selectedNumber); } SENDLINE_PGM("END"); // Filelist stop - #endif // SDSUPPORT + #endif // HAS_MEDIA } void AnycubicTFTClass::RenderSpecialMenu(uint16_t selectedNumber) { @@ -514,7 +514,7 @@ void AnycubicTFTClass::RenderCurrentFolder(uint16_t selectedNumber) { } void AnycubicTFTClass::OnPrintTimerStarted() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (mediaPrintingState == AMPRINTSTATE_PRINTING) SENDLINE_DBG_PGM("J04", "TFT Serial Debug: Starting SD Print... J04"); // J04 Starting Print @@ -522,7 +522,7 @@ void AnycubicTFTClass::OnPrintTimerStarted() { } void AnycubicTFTClass::OnPrintTimerPaused() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (isPrintingFromMedia()) { mediaPrintingState = AMPRINTSTATE_PAUSED; mediaPauseState = AMPAUSESTATE_PARKING; @@ -531,7 +531,7 @@ void AnycubicTFTClass::OnPrintTimerPaused() { } void AnycubicTFTClass::OnPrintTimerStopped() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (mediaPrintingState == AMPRINTSTATE_PRINTING) { mediaPrintingState = AMPRINTSTATE_NOT_PRINTING; mediaPauseState = AMPAUSESTATE_NOT_PAUSED; @@ -606,7 +606,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { } break; case 6: // A6 GET SD CARD PRINTING STATUS - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (isPrintingFromMedia()) { SEND_PGM("A6V "); if (isMediaInserted()) @@ -635,28 +635,28 @@ void AnycubicTFTClass::GetCommandFromTFT() { break; case 8: // A8 GET SD LIST - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA SelectedFile[0] = 0; RenderCurrentFileList(); #endif break; case 9: // A9 pause sd print - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (isPrintingFromMedia()) PausePrint(); #endif break; case 10: // A10 resume sd print - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (isPrintingFromMediaPaused()) ResumePrint(); #endif break; case 11: // A11 STOP SD PRINT - TERN_(SDSUPPORT, StopPrint()); + TERN_(HAS_MEDIA, StopPrint()); break; case 12: // A12 kill @@ -664,7 +664,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { break; case 13: // A13 SELECTION FILE - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (isMediaInserted()) { starpos = (strchr(TFTstrchr_pointer + 4, '*')); if (TFTstrchr_pointer[4] == '/') { @@ -693,7 +693,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { break; case 14: // A14 START PRINTING - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (!isPrinting() && strlen(SelectedFile) > 0) StartPrint(); #endif @@ -866,7 +866,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { break; case 26: // A26 refresh SD - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (isMediaInserted()) { if (strlen(SelectedDirectory) > 0) { FileList currentFileList; @@ -922,7 +922,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { } void AnycubicTFTClass::DoSDCardStateCheck() { - #if BOTH(SDSUPPORT, HAS_SD_DETECT) + #if ALL(HAS_MEDIA, HAS_SD_DETECT) bool isInserted = isMediaInserted(); if (isInserted) SENDLINE_DBG_PGM("J00", "TFT Serial Debug: SD card state changed... isInserted"); @@ -952,7 +952,7 @@ void AnycubicTFTClass::DoFilamentRunoutCheck() { } void AnycubicTFTClass::StartPrint() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (!isPrinting() && strlen(SelectedFile) > 0) { #if ENABLED(ANYCUBIC_LCD_DEBUG) SERIAL_ECHOPGM("TFT Serial Debug: About to print file ... "); @@ -968,7 +968,7 @@ void AnycubicTFTClass::StartPrint() { } void AnycubicTFTClass::PausePrint() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (isPrintingFromMedia() && mediaPrintingState != AMPRINTSTATE_STOP_REQUESTED && mediaPauseState == AMPAUSESTATE_NOT_PAUSED) { mediaPrintingState = AMPRINTSTATE_PAUSE_REQUESTED; mediaPauseState = AMPAUSESTATE_NOT_PAUSED; // need the userconfirm method to update pause state @@ -982,7 +982,7 @@ void AnycubicTFTClass::PausePrint() { } void AnycubicTFTClass::ResumePrint() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA #if ENABLED(FILAMENT_RUNOUT_SENSOR) if (READ(FIL_RUNOUT1_PIN)) { #if ENABLED(ANYCUBIC_LCD_DEBUG) @@ -1018,7 +1018,7 @@ void AnycubicTFTClass::ResumePrint() { } void AnycubicTFTClass::StopPrint() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA mediaPrintingState = AMPRINTSTATE_STOP_REQUESTED; mediaPauseState = AMPAUSESTATE_NOT_PAUSED; SENDLINE_DBG_PGM("J16", "TFT Serial Debug: SD print stop called... J16"); diff --git a/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp index 0eb95bb041ba..977de4f6bb3f 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp @@ -227,7 +227,7 @@ void DGUSDisplay::ProcessRx() { } } -size_t DGUSDisplay::GetFreeTxBuffer() { return SERIAL_GET_TX_BUFFER_FREE(); } +size_t DGUSDisplay::GetFreeTxBuffer() { return LCD_SERIAL_TX_BUFFER_FREE(); } void DGUSDisplay::WriteHeader(uint16_t adr, uint8_t cmd, uint8_t payloadlen) { LCD_SERIAL.write(DGUS_HEADER1); diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 37543a237c0b..1d13048ca543 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -52,7 +52,7 @@ bool DGUSScreenHandler::ScreenComplete; void (*DGUSScreenHandler::confirm_action_cb)() = nullptr; -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA int16_t DGUSScreenHandler::top_file = 0, DGUSScreenHandler::file_to_print = 0; ExtUI::FileList filelist; @@ -275,7 +275,7 @@ void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) #endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA void DGUSScreenHandler::ScreenChangeHookIfSD(DGUS_VP_Variable &var, void *val_ptr) { // default action executed when there is a SD card, but not printing @@ -347,7 +347,7 @@ void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) GotoScreen(DGUSLCD_SCREEN_POPUP); } -#endif // SDSUPPORT +#endif // HAS_MEDIA void DGUSScreenHandler::ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr) { DGUS_VP_Variable ramcopy; diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandlerBase.h b/Marlin/src/lcd/extui/dgus/DGUSScreenHandlerBase.h index 07a108e84663..a343a28a62ee 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandlerBase.h +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandlerBase.h @@ -113,7 +113,7 @@ class DGUSScreenHandler { static void HandleFilamentLoadUnload(DGUS_VP_Variable &var); #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA // Callback for VP "Display wants to change screen when there is a SD card" static void ScreenChangeHookIfSD(DGUS_VP_Variable &var, void *val_ptr); // Scroll buttons on the file listing screen. @@ -183,7 +183,7 @@ class DGUSScreenHandler { if (!var.memadr) return; union { unsigned char tmp[sizeof(T)]; T t; } x; unsigned char *ptr = (unsigned char*)val_ptr; - LOOP_L_N(i, sizeof(T)) x.tmp[i] = ptr[sizeof(T) - i - 1]; + for (uint8_t i = 0; i < sizeof(T); ++i) x.tmp[i] = ptr[sizeof(T) - i - 1]; *(T*)var.memadr = x.t; } @@ -232,7 +232,7 @@ class DGUSScreenHandler { static uint16_t ConfirmVP; //< context for confirm screen (VP that will be emulated-sent on "OK"). - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA static int16_t top_file; //< file on top of file chooser static int16_t file_to_print; //< touched file to be confirmed #endif diff --git a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp index b041687a14fa..b40cd5cab574 100644 --- a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp +++ b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp @@ -48,11 +48,11 @@ namespace ExtUI { while (!ScreenHandler.loop()); // Wait while anything is left to be sent } - void onMediaInserted() { TERN_(SDSUPPORT, ScreenHandler.SDCardInserted()); } - void onMediaError() { TERN_(SDSUPPORT, ScreenHandler.SDCardError()); } - void onMediaRemoved() { TERN_(SDSUPPORT, ScreenHandler.SDCardRemoved()); } + void onMediaInserted() { TERN_(HAS_MEDIA, ScreenHandler.SDCardInserted()); } + void onMediaError() { TERN_(HAS_MEDIA, ScreenHandler.SDCardError()); } + void onMediaRemoved() { TERN_(HAS_MEDIA, ScreenHandler.SDCardRemoved()); } - void onPlayTone(const uint16_t frequency, const uint16_t duration) {} + void onPlayTone(const uint16_t frequency, const uint16_t duration/*=0*/) {} void onPrintTimerStarted() {} void onPrintTimerPaused() {} void onPrintTimerStopped() {} @@ -102,20 +102,22 @@ namespace ExtUI { // Called after loading or resetting stored settings } - void onSettingsStored(bool success) { + void onSettingsStored(const bool success) { // Called after the entire EEPROM has been written, // whether successful or not. } - void onSettingsLoaded(bool success) { + void onSettingsLoaded(const bool success) { // Called after the entire EEPROM has been read, // whether successful or not. } - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated } @@ -126,6 +128,12 @@ namespace ExtUI { #endif #if ENABLED(POWER_LOSS_RECOVERY) + void onSetPowerLoss(const bool onoff) { + // Called when power-loss is enabled/disabled + } + void onPowerLoss() { + // Called when power-loss state is detected + } void onPowerLossResume() { // Called on resume from power-loss IF_DISABLED(DGUS_LCD_UI_MKS, ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POWER_LOSS)); diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp index 0e825c9e7c33..9807e4540af8 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp @@ -320,7 +320,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), VPHELPER(VP_SCREENCHANGE_ASK, nullptr, ScreenHandler.ScreenChangeHookIfIdle, nullptr), - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), #endif VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), @@ -442,7 +442,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // SDCard File listing. - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index 1f72c685fb81..7c906bfba049 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -40,7 +40,7 @@ #include "../../../../feature/powerloss.h" #endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA extern ExtUI::FileList filelist; @@ -124,7 +124,7 @@ ) GotoScreen(DGUSLCD_SCREEN_MAIN); } -#endif // SDSUPPORT +#endif // HAS_MEDIA void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { uint8_t *tmp = (uint8_t*)val_ptr; @@ -190,7 +190,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!movevalue) { // homing - DEBUG_ECHOPGM(" homing ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" homing ", C(axiscode)); char buf[6] = "G28 X"; buf[4] = axiscode; //DEBUG_ECHOPGM(" ", buf); @@ -201,7 +201,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } else { // movement - DEBUG_ECHOPGM(" move ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" move ", C(axiscode)); bool old_relative_mode = relative_mode; if (!relative_mode) { //DEBUG_ECHOPGM(" G91"); @@ -237,7 +237,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { return; cannotmove: - DEBUG_ECHOLNPGM(" cannot move ", AS_CHAR(axiscode)); + DEBUG_ECHOLNPGM(" cannot move ", C(axiscode)); return; } diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp index 6e4c76ca68df..f51df20bd3e6 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp @@ -317,7 +317,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), VPHELPER(VP_SCREENCHANGE_ASK, nullptr, ScreenHandler.ScreenChangeHookIfIdle, nullptr), - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), #endif VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), @@ -435,7 +435,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // SDCard File listing. - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index f04bef2fd8da..e6ab4af2f81b 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -40,7 +40,7 @@ #include "../../../../feature/powerloss.h" #endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA extern ExtUI::FileList filelist; @@ -124,7 +124,7 @@ ) GotoScreen(DGUSLCD_SCREEN_MAIN); } -#endif // SDSUPPORT +#endif // HAS_MEDIA void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { uint8_t *tmp = (uint8_t*)val_ptr; @@ -190,7 +190,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!movevalue) { // homing - DEBUG_ECHOPGM(" homing ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" homing ", C(axiscode)); char buf[6] = "G28 X"; buf[4] = axiscode; //DEBUG_ECHOPGM(" ", buf); @@ -201,7 +201,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } else { // movement - DEBUG_ECHOPGM(" move ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" move ", C(axiscode)); bool old_relative_mode = relative_mode; if (!relative_mode) { //DEBUG_ECHOPGM(" G91"); @@ -237,7 +237,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { return; cannotmove: - DEBUG_ECHOLNPGM(" cannot move ", AS_CHAR(axiscode)); + DEBUG_ECHOLNPGM(" cannot move ", C(axiscode)); return; } diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index ae8d9565e3f5..ab5fa56bc133 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -502,7 +502,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), VPHELPER(VP_SCREENCHANGE_ASK, nullptr, ScreenHandler.ScreenChangeHookIfIdle, nullptr), - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), #endif VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), @@ -751,7 +751,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // SDCard File listing - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h index bdcd248dd6cd..a8701fa894fc 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h @@ -241,7 +241,6 @@ enum DGUSLCD_Screens : uint8_t { DGUSLCD_SCREEN_UNUSED = 255 }; - // Place for status messages. constexpr uint16_t VP_M117 = 0x7020; constexpr uint8_t VP_M117_LEN = 0x20; @@ -299,7 +298,6 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; constexpr uint16_t VP_MARLIN_VERSION = 0x1A00; constexpr uint8_t VP_MARLIN_VERSION_LEN = 16; // there is more space on the display, if needed. - constexpr uint16_t VP_SCREENCHANGE_ASK = 0x1500; constexpr uint16_t VP_SCREENCHANGE = 0x1501; // Key-Return button to new menu pressed. Data contains target screen in low byte and info in high byte. constexpr uint16_t VP_TEMP_ALL_OFF = 0x1502; // Turn all heaters off. Value arbitrary ;)= @@ -515,7 +513,6 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; constexpr uint16_t VP_TMC_E1_Current = 0x3442; constexpr uint16_t VP_TMC_Z1_Current = 0x3444; - constexpr uint16_t VP_PrintTime_H = 0x3500; constexpr uint16_t VP_PrintTime_M = 0x3502; constexpr uint16_t VP_PrintTime_S = 0x3504; @@ -591,7 +588,6 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; constexpr uint16_t VP_Level_Point_Five_X = 0x4110; constexpr uint16_t VP_Level_Point_Five_Y = 0x4112; - /* H43 Version */ constexpr uint16_t VP_MKS_H43_VERSION = 0x4A00; // MKS H43 V1.0.0 constexpr uint16_t VP_MKS_H43_VERSION_LEN = 16; @@ -630,7 +626,6 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; constexpr uint16_t VP_E0_Max_Acc_Speed_Dis = 0x5210; constexpr uint16_t VP_E1_Max_Acc_Speed_Dis = 0x5220; - constexpr uint16_t VP_PrintTime_Dis = 0x5470; constexpr uint16_t VP_E0_Temp_Dis = 0x5310; constexpr uint16_t VP_E1_Temp_Dis = 0x5320; @@ -641,12 +636,10 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; constexpr uint16_t VP_Min_Ex_Temp_Dis = 0x5380; - constexpr uint16_t VP_X_PARK_POS_Dis = 0x53E0; constexpr uint16_t VP_Y_PARK_POS_Dis = 0x53F0; constexpr uint16_t VP_Z_PARK_POS_Dis = 0x5400; - constexpr uint16_t VP_TravelAcc_Dis = 0x5440; constexpr uint16_t VP_FeedRateMin_Dis = 0x5450; constexpr uint16_t VP_TravelFeeRateMin_Dis = 0x5460; diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 36ab016b35a6..121d88c8a119 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -47,7 +47,7 @@ #include "../../../../feature/powerloss.h" #endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA extern ExtUI::FileList filelist; #endif @@ -146,7 +146,7 @@ void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { #endif } -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { uint16_t touched_nr = (int16_t)BE16_P(val_ptr) + top_file; @@ -268,7 +268,7 @@ void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { const uint16_t value = BE16_P(val_ptr); if (value == 0x0F) GotoScreen(DGUSLCD_SCREEN_MAIN); } -#endif // SDSUPPORT +#endif // HAS_MEDIA void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { uint8_t *tmp = (uint8_t*)val_ptr; @@ -429,7 +429,7 @@ void DGUSScreenHandlerMKS::LanguageChange(DGUS_VP_Variable &var, void *val_ptr) } #if ENABLED(MESH_BED_LEVELING) - uint8_t mesh_point_count = GRID_MAX_POINTS; + grid_count_t mesh_point_count = GRID_MAX_POINTS; #endif void DGUSScreenHandlerMKS::Level_Ctrl(DGUS_VP_Variable &var, void *val_ptr) { @@ -651,7 +651,7 @@ void DGUSScreenHandlerMKS::ManualAssistLeveling(DGUS_VP_Variable &var, void *val #define mks_min(a, b) ((a) < (b)) ? (a) : (b) #define mks_max(a, b) ((a) > (b)) ? (a) : (b) void DGUSScreenHandlerMKS::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) { - #if EITHER(HAS_TRINAMIC_CONFIG, HAS_STEALTHCHOP) + #if ANY(HAS_TRINAMIC_CONFIG, HAS_STEALTHCHOP) const uint16_t tmc_value = BE16_P(val_ptr); #endif @@ -825,7 +825,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!movevalue) { // homing - DEBUG_ECHOPGM(" homing ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" homing ", C(axiscode)); // char buf[6] = "G28 X"; // buf[4] = axiscode; @@ -847,7 +847,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } else { // movement - DEBUG_ECHOPGM(" move ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" move ", C(axiscode)); bool old_relative_mode = relative_mode; if (!relative_mode) { @@ -885,7 +885,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { return; cannotmove: - DEBUG_ECHOLNPGM(" cannot move ", AS_CHAR(axiscode)); + DEBUG_ECHOLNPGM(" cannot move ", C(axiscode)); return; } @@ -1181,7 +1181,7 @@ void DGUSScreenHandlerMKS::GetManualFilamentSpeed(DGUS_VP_Variable &var, void *v } void DGUSScreenHandlerMKS::FilamentLoadUnload(DGUS_VP_Variable &var, void *val_ptr, const int filamentDir) { - #if EITHER(HAS_MULTI_HOTEND, SINGLENOZZLE) + #if ANY(HAS_MULTI_HOTEND, SINGLENOZZLE) uint8_t swap_tool = 0; #else constexpr uint8_t swap_tool = 1; // T0 (or none at all) @@ -1202,7 +1202,7 @@ void DGUSScreenHandlerMKS::FilamentLoadUnload(DGUS_VP_Variable &var, void *val_p if (thermalManager.tooColdToExtrude(0)) hotend_too_cold = 1; else { - #if EITHER(HAS_MULTI_HOTEND, SINGLENOZZLE) + #if ANY(HAS_MULTI_HOTEND, SINGLENOZZLE) swap_tool = 1; #endif } @@ -1217,7 +1217,7 @@ void DGUSScreenHandlerMKS::FilamentLoadUnload(DGUS_VP_Variable &var, void *val_p break; } - #if BOTH(HAS_HOTEND, PREVENT_COLD_EXTRUSION) + #if ALL(HAS_HOTEND, PREVENT_COLD_EXTRUSION) if (hotend_too_cold) { if (thermalManager.targetTooColdToExtrude(hotend_too_cold - 1)) thermalManager.setTargetHotend(thermalManager.extrude_min_temp, hotend_too_cold - 1); sendinfoscreen(F("NOTICE"), nullptr, F("Please wait."), F("Nozzle heating!"), true, true, true, true); @@ -1229,7 +1229,7 @@ void DGUSScreenHandlerMKS::FilamentLoadUnload(DGUS_VP_Variable &var, void *val_p if (swap_tool) { char buf[30]; snprintf_P(buf, 30 - #if EITHER(HAS_MULTI_HOTEND, SINGLENOZZLE) + #if ANY(HAS_MULTI_HOTEND, SINGLENOZZLE) , PSTR("M1002T%cE%dF%d"), char('0' + swap_tool - 1) #else , PSTR("M1002E%dF%d") @@ -1245,7 +1245,7 @@ void DGUSScreenHandlerMKS::FilamentLoadUnload(DGUS_VP_Variable &var, void *val_p * within the G-code execution window for best concurrency. */ void GcodeSuite::M1002() { - #if EITHER(HAS_MULTI_HOTEND, SINGLENOZZLE) + #if ANY(HAS_MULTI_HOTEND, SINGLENOZZLE) { char buf[3]; sprintf_P(buf, PSTR("T%c"), char('0' + parser.intval('T'))); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index 823ed4297cd0..69ded29ffbc7 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -83,7 +83,7 @@ class DGUSScreenHandlerMKS : public DGUSScreenHandler { static void GetManualFilamentSpeed(DGUS_VP_Variable &var, void *val_ptr); #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA // Marlin informed us about SD print completion. static void SDPrintingFinished(); #else diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp index 0115d3b8c13b..c895030d7613 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp @@ -128,7 +128,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), VPHELPER(VP_SCREENCHANGE_ASK, nullptr, ScreenHandler.ScreenChangeHookIfIdle, nullptr), - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), #endif VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), @@ -243,7 +243,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // SDCard File listing. - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index aaa8b72e1182..b717fa607bb9 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -40,7 +40,7 @@ #include "../../../../feature/powerloss.h" #endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA extern ExtUI::FileList filelist; @@ -124,7 +124,7 @@ ) GotoScreen(DGUSLCD_SCREEN_MAIN); } -#endif // SDSUPPORT +#endif // HAS_MEDIA void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { uint8_t *tmp = (uint8_t*)val_ptr; @@ -190,7 +190,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!movevalue) { // homing - DEBUG_ECHOPGM(" homing ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" homing ", C(axiscode)); char buf[6] = "G28 X"; buf[4] = axiscode; //DEBUG_ECHOPGM(" ", buf); @@ -201,7 +201,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } else { // movement - DEBUG_ECHOPGM(" move ", AS_CHAR(axiscode)); + DEBUG_ECHOPGM(" move ", C(axiscode)); bool old_relative_mode = relative_mode; if (!relative_mode) { //DEBUG_ECHOPGM(" G91"); @@ -237,7 +237,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { return; cannotmove: - DEBUG_ECHOLNPGM(" cannot move ", AS_CHAR(axiscode)); + DEBUG_ECHOLNPGM(" cannot move ", C(axiscode)); return; } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp index 15b3f5adcde4..d3b6b43a1b13 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp @@ -366,8 +366,8 @@ void DGUSDisplay::ProcessRx() { } size_t DGUSDisplay::GetFreeTxBuffer() { - #ifdef LCD_SERIAL_GET_TX_BUFFER_FREE - return LCD_SERIAL_GET_TX_BUFFER_FREE(); + #ifdef LCD_SERIAL_TX_BUFFER_FREE + return LCD_SERIAL_TX_BUFFER_FREE(); #else return SIZE_MAX; #endif diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h index c4e3645f28c9..b566a2a6e6db 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h @@ -47,13 +47,13 @@ class DGUSDisplay { enum DGUS_ControlType : uint8_t { VARIABLE_DATA_INPUT = 0x00, - POPUP_WINDOW = 0x01, - INCREMENTAL_ADJUST = 0x02, - SLIDER_ADJUST = 0x03, - RTC_SETTINGS = 0x04, - RETURN_KEY_CODE = 0x05, - TEXT_INPUT = 0x06, - FIRMWARE_SETTINGS = 0x07 + POPUP_WINDOW = 0x01, + INCREMENTAL_ADJUST = 0x02, + SLIDER_ADJUST = 0x03, + RTC_SETTINGS = 0x04, + RETURN_KEY_CODE = 0x05, + TEXT_INPUT = 0x06, + FIRMWARE_SETTINGS = 0x07 }; DGUSDisplay() = default; @@ -121,7 +121,7 @@ class DGUSDisplay { } src, dst; src.val = value; - LOOP_L_N(i, sizeof(T)) dst.byte[i] = src.byte[sizeof(T) - i - 1]; + for (uint8_t i = 0; i < sizeof(T); ++i) dst.byte[i] = src.byte[sizeof(T) - i - 1]; return dst.val; } @@ -154,7 +154,7 @@ class DGUSDisplay { }; enum dgus_system_addr : uint16_t { - DGUS_VERSION = 0x000f // OS/GUI version + DGUS_VERSION = 0x000F // OS/GUI version }; static void WriteHeader(uint16_t addr, uint8_t command, uint8_t len); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp index ce03ab6b8340..8ecca34514fb 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp @@ -46,7 +46,7 @@ void DGUSRxHandler::ScreenChange(DGUS_VP &vp, void *data_ptr) { const DGUS_Screen screen = (DGUS_Screen)((uint8_t*)data_ptr)[1]; if (vp.addr == DGUS_Addr::SCREENCHANGE_SD) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA IF_DISABLED(HAS_SD_DETECT, card.mount()); if (!ExtUI::isMediaInserted()) { @@ -76,7 +76,7 @@ void DGUSRxHandler::ScreenChange(DGUS_VP &vp, void *data_ptr) { dgus_screen_handler.TriggerScreenChange(screen); } -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA void DGUSRxHandler::Scroll(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); @@ -154,7 +154,7 @@ void DGUSRxHandler::ScreenChange(DGUS_VP &vp, void *data_ptr) { ExtUI::printFile(dgus_screen_handler.filelist.shortFilename()); dgus_screen_handler.TriggerScreenChange(DGUS_Screen::PRINT_STATUS); } -#endif // SDSUPPORT +#endif // HAS_MEDIA void DGUSRxHandler::PrintAbort(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h index 4cad11fc0b0b..d6d5855b9d8b 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h @@ -28,7 +28,7 @@ namespace DGUSRxHandler { void ScreenChange(DGUS_VP &, void *); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA void Scroll(DGUS_VP &, void *); void SelectFile(DGUS_VP &, void *); void PrintFile(DGUS_VP &, void *); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp index 0b584fac3bce..48b9e2b8a446 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp @@ -34,7 +34,7 @@ uint8_t DGUSScreenHandler::debug_count = 0; -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA ExtUI::FileList DGUSScreenHandler::filelist; uint16_t DGUSScreenHandler::filelist_offset = 0; int16_t DGUSScreenHandler::filelist_selected = -1; @@ -138,7 +138,7 @@ void DGUSScreenHandler::Loop() { if (current_screen == DGUS_Screen::LEVELING_PROBING && IsPrinterIdle()) { dgus_display.PlaySound(3); - SetStatusMessage(ExtUI::getMeshValid() ? F("Probing successful") : F("Probing failed")); + SetStatusMessage(ExtUI::getLevelingIsValid() ? F("Probing successful") : F("Probing failed")); MoveToScreen(DGUS_Screen::LEVELING_AUTOMATIC); return; @@ -200,7 +200,7 @@ void DGUSScreenHandler::StoreSettings(char *buff) { data.initialized = true; data.volume = dgus_display.GetVolume(); data.brightness = dgus_display.GetBrightness(); - data.abl_okay = (ExtUI::getLevelingActive() && ExtUI::getMeshValid()); + data.abl_okay = (ExtUI::getLevelingActive() && ExtUI::getLevelingIsValid()); memcpy(buff, &data, sizeof(data)); } @@ -216,7 +216,7 @@ void DGUSScreenHandler::LoadSettings(const char *buff) { dgus_display.SetBrightness(data.initialized ? data.brightness : DGUS_DEFAULT_BRIGHTNESS); if (data.initialized) { - leveling_active = (data.abl_okay && ExtUI::getMeshValid()); + leveling_active = (data.abl_okay && ExtUI::getLevelingIsValid()); ExtUI::setLevelingActive(leveling_active); } } @@ -257,7 +257,7 @@ void DGUSScreenHandler::MeshUpdate(const int8_t xpos, const int8_t ypos) { uint8_t point = ypos * GRID_MAX_POINTS_X + xpos; probing_icons[point < 16 ? 0 : 1] |= (1U << (point % 16)); - if (xpos >= GRID_MAX_POINTS_X - 1 && ypos >= GRID_MAX_POINTS_Y - 1 && !ExtUI::getMeshValid()) + if (xpos >= GRID_MAX_POINTS_X - 1 && ypos >= GRID_MAX_POINTS_Y - 1 && !ExtUI::getLevelingIsValid()) probing_icons[0] = probing_icons[1] = 0; TriggerFullUpdate(); @@ -290,7 +290,7 @@ void DGUSScreenHandler::FilamentRunout(const ExtUI::extruder_t extruder) { dgus_display.PlaySound(3); } -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA void DGUSScreenHandler::SDCardInserted() { if (current_screen == DGUS_Screen::HOME) @@ -308,7 +308,7 @@ void DGUSScreenHandler::FilamentRunout(const ExtUI::extruder_t extruder) { TriggerScreenChange(DGUS_Screen::HOME); } -#endif // SDSUPPORT +#endif // HAS_MEDIA #if ENABLED(POWER_LOSS_RECOVERY) diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h index cc59bda6d7fa..4beb358b4c3b 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h @@ -52,7 +52,7 @@ class DGUSScreenHandler { static void PrintTimerStopped(); static void FilamentRunout(const ExtUI::extruder_t extruder); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA /// Marlin informed us that a new SD has been inserted. static void SDCardInserted(); /// Marlin informed us that the SD Card has been removed(). @@ -87,7 +87,7 @@ class DGUSScreenHandler { static uint8_t debug_count; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA static ExtUI::FileList filelist; static uint16_t filelist_offset; static int16_t filelist_selected; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp index 090d53c92e77..8ff215603a30 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp @@ -31,7 +31,7 @@ #include "../../../gcode/queue.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA bool DGUSSetupHandler::Print() { dgus_screen_handler.filelist.refresh(); @@ -148,7 +148,7 @@ bool DGUSSetupHandler::LevelingOffset() { } bool DGUSSetupHandler::LevelingAutomatic() { - if (ExtUI::getMeshValid()) { + if (ExtUI::getLevelingIsValid()) { dgus_screen_handler.leveling_active = true; ExtUI::setLevelingActive(true); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.h index 9e3866467fc0..10063446b770 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.h @@ -23,7 +23,7 @@ namespace DGUSSetupHandler { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA bool Print(); #endif bool PrintStatus(); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp index 1837a0c93ab2..6fc1934f650c 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp @@ -36,7 +36,7 @@ #include "../../../feature/pause.h" #endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA void DGUSTxHandler::SetFileControlState(int file, bool state) { DGUS_Control control; @@ -177,7 +177,7 @@ dgus_display.WriteString((uint16_t)vp.addr, dgus_screen_handler.filelist.filename(), vp.size); } -#endif // SDSUPPORT +#endif // HAS_MEDIA void DGUSTxHandler::PositionZ(DGUS_VP &vp) { float position = ExtUI::isAxisPositionKnown(ExtUI::Z) ? diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h index 7d1b46773b25..2a6ab1d094da 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h @@ -28,7 +28,7 @@ namespace DGUSTxHandler { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA void SetFileControlState(int, bool); void FileType(DGUS_VP &); void FileName(DGUS_VP &); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h index 39e97156d083..3fd6d16f5bbd 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h @@ -21,153 +21,153 @@ */ #pragma once -constexpr uint8_t DGUS_LINE_LEN = 32; -constexpr uint8_t DGUS_STATUS_LEN = 32; -constexpr uint8_t DGUS_FILE_COUNT = 5; -constexpr uint8_t DGUS_FILENAME_LEN = 32; -constexpr uint8_t DGUS_ELLAPSED_LEN = 15; -constexpr uint8_t DGUS_LEVEL_GRID_SIZE = 25; -constexpr uint8_t DGUS_MACHINE_LEN = 24; -constexpr uint8_t DGUS_BUILDVOLUME_LEN = 24; -constexpr uint8_t DGUS_VERSION_LEN = 16; -constexpr uint8_t DGUS_PRINTTIME_LEN = 24; -constexpr uint8_t DGUS_LONGESTPRINT_LEN = 24; -constexpr uint8_t DGUS_FILAMENTUSED_LEN = 24; -constexpr uint8_t DGUS_GCODE_LEN = 32; +#define DGUS_LINE_LEN 32 +#define DGUS_STATUS_LEN 32 +#define DGUS_FILE_COUNT 5 +#define DGUS_FILENAME_LEN 32 +#define DGUS_ELAPSED_LEN 15 +#define DGUS_LEVEL_GRID_SIZE 25 +#define DGUS_MACHINE_LEN 24 +#define DGUS_BUILDVOLUME_LEN 24 +#define DGUS_VERSION_LEN 16 +#define DGUS_PRINTTIME_LEN 24 +#define DGUS_LONGESTPRINT_LEN 24 +#define DGUS_FILAMENTUSED_LEN 24 +#define DGUS_GCODE_LEN 32 enum class DGUS_Addr : uint16_t { - MESSAGE_Line1 = 0x1100, // 0x1100 - 0x111F - MESSAGE_Line2 = 0x1120, // 0x1120 - 0x113F - MESSAGE_Line3 = 0x1140, // 0x1140 - 0x115F - MESSAGE_Line4 = 0x1160, // 0x1160 - 0x117F + MESSAGE_Line1 = 0x1100, // 0x1100 - 0x111F + MESSAGE_Line2 = 0x1120, // 0x1120 - 0x113F + MESSAGE_Line3 = 0x1140, // 0x1140 - 0x115F + MESSAGE_Line4 = 0x1160, // 0x1160 - 0x117F // READ-ONLY VARIABLES - SCREENCHANGE = 0x2000, // Screen change request. Data contains target screen in low byte. - SCREENCHANGE_SD = 0x2001, // Only change if SD card present. - SCREENCHANGE_Idle = 0x2002, // Only change if not printing. - SCREENCHANGE_Printing = 0x2003, // Only change if printing. - SD_SelectFile = 0x2004, // Data: file index (0-4) - SD_Scroll = 0x2005, // Data: DGUS_Data::Scroll - SD_Print = 0x2006, - STATUS_Abort = 0x2007, // Popup / Data: DGUS_Data::Popup - STATUS_Pause = 0x2008, // Popup / Data: DGUS_Data::Popup - STATUS_Resume = 0x2009, // Popup / Data: DGUS_Data::Popup - ADJUST_SetFeedrate = 0x200A, // Type: Integer (16 bits signed) - ADJUST_SetFlowrate_CUR = 0x200B, // Type: Integer (16 bits signed) + SCREENCHANGE = 0x2000, // Screen change request. Data contains target screen in low byte. + SCREENCHANGE_SD = 0x2001, // Only change if SD card present. + SCREENCHANGE_Idle = 0x2002, // Only change if not printing. + SCREENCHANGE_Printing = 0x2003, // Only change if printing. + SD_SelectFile = 0x2004, // Data: file index (0-4) + SD_Scroll = 0x2005, // Data: DGUS_Data::Scroll + SD_Print = 0x2006, + STATUS_Abort = 0x2007, // Popup / Data: DGUS_Data::Popup + STATUS_Pause = 0x2008, // Popup / Data: DGUS_Data::Popup + STATUS_Resume = 0x2009, // Popup / Data: DGUS_Data::Popup + ADJUST_SetFeedrate = 0x200A, // Type: Integer (16 bits signed) + ADJUST_SetFlowrate_CUR = 0x200B, // Type: Integer (16 bits signed) #if HAS_MULTI_EXTRUDER - ADJUST_SetFlowrate_E0 = 0x200C, // Type: Integer (16 bits signed) - ADJUST_SetFlowrate_E1 = 0x200D, // Type: Integer (16 bits signed) + ADJUST_SetFlowrate_E0 = 0x200C, // Type: Integer (16 bits signed) + ADJUST_SetFlowrate_E1 = 0x200D, // Type: Integer (16 bits signed) #endif - ADJUST_SetBabystep = 0x200E, // Type: Fixed point, 2 decimals (16 bits signed) - ADJUST_Babystep = 0x200F, // Data: DGUS_Data::Adjust - TEMP_Preset = 0x2010, // Popup / Data: DGUS_Data::TempPreset - TEMP_SetTarget_Bed = 0x2011, // Type: Integer (16 bits signed) - TEMP_SetTarget_H0 = 0x2012, // Type: Integer (16 bits signed) + ADJUST_SetBabystep = 0x200E, // Type: Fixed point, 2 decimals (16 bits signed) + ADJUST_Babystep = 0x200F, // Data: DGUS_Data::Adjust + TEMP_Preset = 0x2010, // Popup / Data: DGUS_Data::TempPreset + TEMP_SetTarget_Bed = 0x2011, // Type: Integer (16 bits signed) + TEMP_SetTarget_H0 = 0x2012, // Type: Integer (16 bits signed) #if HAS_MULTI_HOTEND - TEMP_SetTarget_H1 = 0x2013, // Type: Integer (16 bits signed) + TEMP_SetTarget_H1 = 0x2013, // Type: Integer (16 bits signed) #endif - TEMP_Cool = 0x2014, // Data: DGUS_Data::Heater - STEPPER_Control = 0x2015, // Popup / Data: DGUS_Data::Control - LEVEL_OFFSET_Set = 0x2016, // Type: Fixed point, 2 decimals (16 bits signed) - LEVEL_OFFSET_Step = 0x2017, // Data: DGUS_Data::Adjust - LEVEL_OFFSET_SetStep = 0x2018, // Data: DGUS_Data::StepSize - LEVEL_MANUAL_Point = 0x2019, // Data: point index (1-5) - LEVEL_AUTO_Probe = 0x201A, - LEVEL_AUTO_Disable = 0x201B, - FILAMENT_Select = 0x201C, // Data: DGUS_Data::Extruder - FILAMENT_SetLength = 0x201D, // Type: Integer (16 bits unsigned) - FILAMENT_Move = 0x201E, // Data: DGUS_Data::FilamentMove - MOVE_Home = 0x201F, // Data: DGUS_Data::Axis - MOVE_SetX = 0x2020, // Type: Fixed point, 1 decimal (16 bits signed) - MOVE_SetY = 0x2021, // Type: Fixed point, 1 decimal (16 bits signed) - MOVE_SetZ = 0x2022, // Type: Fixed point, 1 decimal (16 bits signed) - MOVE_Step = 0x2023, // Data: DGUS_Data::MoveDirection - MOVE_SetStep = 0x2024, // Data: DGUS_Data::StepSize - GCODE_Clear = 0x2025, - GCODE_Execute = 0x2026, - EEPROM_Reset = 0x2027, // Popup / Data: DGUS_Data::Popup - SETTINGS2_Extra = 0x2028, // Data: DGUS_Data::Extra - PID_Select = 0x2029, // Data: DGUS_Data::Heater - PID_SetTemp = 0x202A, // Type: Integer (16 bits unsigned) - PID_Run = 0x202B, - POWERLOSS_Abort = 0x202C, // Popup / Data: DGUS_Data::Popup - POWERLOSS_Resume = 0x202D, // Popup / Data: DGUS_Data::Popup - WAIT_Abort = 0x202E, // Popup / Data: DGUS_Data::Popup - WAIT_Continue = 0x202F, + TEMP_Cool = 0x2014, // Data: DGUS_Data::Heater + STEPPER_Control = 0x2015, // Popup / Data: DGUS_Data::Control + LEVEL_OFFSET_Set = 0x2016, // Type: Fixed point, 2 decimals (16 bits signed) + LEVEL_OFFSET_Step = 0x2017, // Data: DGUS_Data::Adjust + LEVEL_OFFSET_SetStep = 0x2018, // Data: DGUS_Data::StepSize + LEVEL_MANUAL_Point = 0x2019, // Data: point index (1-5) + LEVEL_AUTO_Probe = 0x201A, + LEVEL_AUTO_Disable = 0x201B, + FILAMENT_Select = 0x201C, // Data: DGUS_Data::Extruder + FILAMENT_SetLength = 0x201D, // Type: Integer (16 bits unsigned) + FILAMENT_Move = 0x201E, // Data: DGUS_Data::FilamentMove + MOVE_Home = 0x201F, // Data: DGUS_Data::Axis + MOVE_SetX = 0x2020, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_SetY = 0x2021, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_SetZ = 0x2022, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_Step = 0x2023, // Data: DGUS_Data::MoveDirection + MOVE_SetStep = 0x2024, // Data: DGUS_Data::StepSize + GCODE_Clear = 0x2025, + GCODE_Execute = 0x2026, + EEPROM_Reset = 0x2027, // Popup / Data: DGUS_Data::Popup + SETTINGS2_Extra = 0x2028, // Data: DGUS_Data::Extra + PID_Select = 0x2029, // Data: DGUS_Data::Heater + PID_SetTemp = 0x202A, // Type: Integer (16 bits unsigned) + PID_Run = 0x202B, + POWERLOSS_Abort = 0x202C, // Popup / Data: DGUS_Data::Popup + POWERLOSS_Resume = 0x202D, // Popup / Data: DGUS_Data::Popup + WAIT_Abort = 0x202E, // Popup / Data: DGUS_Data::Popup + WAIT_Continue = 0x202F, // WRITE-ONLY VARIABLES - MESSAGE_Status = 0x3000, // 0x3000 - 0x301F - SD_Type = 0x3020, // 0x3020 - 0x3024 / Data: DGUS_Data::SDType - SD_FileName0 = 0x3025, // 0x3025 - 0x3044 - SD_FileName1 = 0x3045, // 0x3045 - 0x3064 - SD_FileName2 = 0x3065, // 0x3065 - 0x3084 - SD_FileName3 = 0x3085, // 0x3085 - 0x30A4 - SD_FileName4 = 0x30A5, // 0x30A5 - 0x30C4 - SD_ScrollIcons = 0x30C5, // Bits: DGUS_Data::ScrollIcon - SD_SelectedFileName = 0x30C6, // 0x30C6 - 0x30E5 - STATUS_PositionZ = 0x30E6, // Type: Fixed point, 1 decimal (16 bits signed) - STATUS_Ellapsed = 0x30E7, // 0x30E7 - 0x30F5 - STATUS_Percent = 0x30F6, // Type: Integer (16 bits unsigned) - STATUS_Icons = 0x30F7, // Bits: DGUS_Data::StatusIcon - ADJUST_Feedrate = 0x30F8, // Type: Integer (16 bits signed) - ADJUST_Flowrate_CUR = 0x30F9, // Type: Integer (16 bits signed) + MESSAGE_Status = 0x3000, // 0x3000 - 0x301F + SD_Type = 0x3020, // 0x3020 - 0x3024 / Data: DGUS_Data::SDType + SD_FileName0 = 0x3025, // 0x3025 - 0x3044 + SD_FileName1 = 0x3045, // 0x3045 - 0x3064 + SD_FileName2 = 0x3065, // 0x3065 - 0x3084 + SD_FileName3 = 0x3085, // 0x3085 - 0x30A4 + SD_FileName4 = 0x30A5, // 0x30A5 - 0x30C4 + SD_ScrollIcons = 0x30C5, // Bits: DGUS_Data::ScrollIcon + SD_SelectedFileName = 0x30C6, // 0x30C6 - 0x30E5 + STATUS_PositionZ = 0x30E6, // Type: Fixed point, 1 decimal (16 bits signed) + STATUS_Ellapsed = 0x30E7, // 0x30E7 - 0x30F5 + STATUS_Percent = 0x30F6, // Type: Integer (16 bits unsigned) + STATUS_Icons = 0x30F7, // Bits: DGUS_Data::StatusIcon + ADJUST_Feedrate = 0x30F8, // Type: Integer (16 bits signed) + ADJUST_Flowrate_CUR = 0x30F9, // Type: Integer (16 bits signed) #if HAS_MULTI_EXTRUDER - ADJUST_Flowrate_E0 = 0x30FA, // Type: Integer (16 bits signed) - ADJUST_Flowrate_E1 = 0x30FB, // Type: Integer (16 bits signed) + ADJUST_Flowrate_E0 = 0x30FA, // Type: Integer (16 bits signed) + ADJUST_Flowrate_E1 = 0x30FB, // Type: Integer (16 bits signed) #endif - TEMP_Current_Bed = 0x30FC, // Type: Integer (16 bits signed) - TEMP_Target_Bed = 0x30FD, // Type: Integer (16 bits signed) - TEMP_Max_Bed = 0x30FE, // Type: Integer (16 bits unsigned) - TEMP_Current_H0 = 0x30FF, // Type: Integer (16 bits signed) - TEMP_Target_H0 = 0x3100, // Type: Integer (16 bits signed) - TEMP_Max_H0 = 0x3101, // Type: Integer (16 bits unsigned) + TEMP_Current_Bed = 0x30FC, // Type: Integer (16 bits signed) + TEMP_Target_Bed = 0x30FD, // Type: Integer (16 bits signed) + TEMP_Max_Bed = 0x30FE, // Type: Integer (16 bits unsigned) + TEMP_Current_H0 = 0x30FF, // Type: Integer (16 bits signed) + TEMP_Target_H0 = 0x3100, // Type: Integer (16 bits signed) + TEMP_Max_H0 = 0x3101, // Type: Integer (16 bits unsigned) #if HAS_MULTI_HOTEND - TEMP_Current_H1 = 0x3102, // Type: Integer (16 bits signed) - TEMP_Target_H1 = 0x3103, // Type: Integer (16 bits signed) - TEMP_Max_H1 = 0x3104, // Type: Integer (16 bits unsigned) + TEMP_Current_H1 = 0x3102, // Type: Integer (16 bits signed) + TEMP_Target_H1 = 0x3103, // Type: Integer (16 bits signed) + TEMP_Max_H1 = 0x3104, // Type: Integer (16 bits unsigned) #endif - STEPPER_Status = 0x3105, // Data: DGUS_Data::Status - LEVEL_OFFSET_Current = 0x3106, // Type: Fixed point, 2 decimals (16 bits signed) - LEVEL_OFFSET_StepIcons = 0x3107, // Bits: DGUS_Data::StepIcon - LEVEL_AUTO_DisableIcon = 0x3108, // Data: DGUS_Data::Status - LEVEL_AUTO_Grid = 0x3109, // 0x3109 - 0x3121 / Type: Fixed point, 3 decimals (16 bits signed) - LEVEL_PROBING_Icons1 = 0x3122, // Type: Integer (16 bits unsigned) / Each bit represents a grid point - LEVEL_PROBING_Icons2 = 0x3123, // Type: Integer (16 bits unsigned) / Each bit represents a grid point - FILAMENT_ExtruderIcons = 0x3124, // Data: DGUS_Data::ExtruderIcon - FILAMENT_Length = 0x3125, // Type: Integer (16 bits unsigned) - MOVE_CurrentX = 0x3126, // Type: Fixed point, 1 decimal (16 bits signed) - MOVE_CurrentY = 0x3127, // Type: Fixed point, 1 decimal (16 bits signed) - MOVE_CurrentZ = 0x3128, // Type: Fixed point, 1 decimal (16 bits signed) - MOVE_StepIcons = 0x3129, // Bits: DGUS_Data::StepIcon - SETTINGS2_BLTouch = 0x312A, // Data: DGUS_Data::Status - PID_HeaterIcons = 0x312B, // Data: DGUS_Data::HeaterIcon - PID_Temp = 0x312C, // Type: Integer (16 bits unsigned) - PID_Kp = 0x312D, // Type: Fixed point, 2 decimals (32 bits signed) - PID_Ki = 0x312F, // Type: Fixed point, 2 decimals (32 bits signed) - PID_Kd = 0x3131, // Type: Fixed point, 2 decimals (32 bits signed) - INFOS_Machine = 0x3133, // 0x3133 - 0x314A - INFOS_BuildVolume = 0x314B, // 0x314B - 0x3162 - INFOS_Version = 0x3163, // 0x3163 - 0x3172 - INFOS_TotalPrints = 0x3173, // Type: Integer (16 bits unsigned) - INFOS_FinishedPrints = 0x3174, // Type: Integer (16 bits unsigned) - INFOS_PrintTime = 0x3175, // 0x3175 - 0x318C - INFOS_LongestPrint = 0x318D, // 0x318D - 0x31A4 - INFOS_FilamentUsed = 0x31A5, // 0x31A5 - 0x31BC - WAIT_Icons = 0x31BD, // Bits: DGUS_Data::WaitIcon + STEPPER_Status = 0x3105, // Data: DGUS_Data::Status + LEVEL_OFFSET_Current = 0x3106, // Type: Fixed point, 2 decimals (16 bits signed) + LEVEL_OFFSET_StepIcons = 0x3107, // Bits: DGUS_Data::StepIcon + LEVEL_AUTO_DisableIcon = 0x3108, // Data: DGUS_Data::Status + LEVEL_AUTO_Grid = 0x3109, // 0x3109 - 0x3121 / Type: Fixed point, 3 decimals (16 bits signed) + LEVEL_PROBING_Icons1 = 0x3122, // Type: Integer (16 bits unsigned) / Each bit represents a grid point + LEVEL_PROBING_Icons2 = 0x3123, // Type: Integer (16 bits unsigned) / Each bit represents a grid point + FILAMENT_ExtruderIcons = 0x3124, // Data: DGUS_Data::ExtruderIcon + FILAMENT_Length = 0x3125, // Type: Integer (16 bits unsigned) + MOVE_CurrentX = 0x3126, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_CurrentY = 0x3127, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_CurrentZ = 0x3128, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_StepIcons = 0x3129, // Bits: DGUS_Data::StepIcon + SETTINGS2_BLTouch = 0x312A, // Data: DGUS_Data::Status + PID_HeaterIcons = 0x312B, // Data: DGUS_Data::HeaterIcon + PID_Temp = 0x312C, // Type: Integer (16 bits unsigned) + PID_Kp = 0x312D, // Type: Fixed point, 2 decimals (32 bits signed) + PID_Ki = 0x312F, // Type: Fixed point, 2 decimals (32 bits signed) + PID_Kd = 0x3131, // Type: Fixed point, 2 decimals (32 bits signed) + INFOS_Machine = 0x3133, // 0x3133 - 0x314A + INFOS_BuildVolume = 0x314B, // 0x314B - 0x3162 + INFOS_Version = 0x3163, // 0x3163 - 0x3172 + INFOS_TotalPrints = 0x3173, // Type: Integer (16 bits unsigned) + INFOS_FinishedPrints = 0x3174, // Type: Integer (16 bits unsigned) + INFOS_PrintTime = 0x3175, // 0x3175 - 0x318C + INFOS_LongestPrint = 0x318D, // 0x318D - 0x31A4 + INFOS_FilamentUsed = 0x31A5, // 0x31A5 - 0x31BC + WAIT_Icons = 0x31BD, // Bits: DGUS_Data::WaitIcon // READ-WRITE VARIABLES - FAN0_Speed = 0x4000, // Type: Integer (16 bits unsigned) / Data: fan speed as percent (0-100) - GCODE_Data = 0x4001, // 0x4001 - 0x4020 - PID_Cycles = 0x4021, // Type: Integer (16 bits unsigned) - VOLUME_Level = 0x4022, // Type: Integer (16 bits unsigned) / Data: volume as percent (0-100) - BRIGHTNESS_Level = 0x4023, // Type: Integer (16 bits unsigned) / Data: brightness as percent (0-100) + FAN0_Speed = 0x4000, // Type: Integer (16 bits unsigned) / Data: fan speed as percent (0-100) + GCODE_Data = 0x4001, // 0x4001 - 0x4020 + PID_Cycles = 0x4021, // Type: Integer (16 bits unsigned) + VOLUME_Level = 0x4022, // Type: Integer (16 bits unsigned) / Data: volume as percent (0-100) + BRIGHTNESS_Level = 0x4023, // Type: Integer (16 bits unsigned) / Data: brightness as percent (0-100) // SPECIAL CASES - STATUS_Percent_Complete = 0x5000, // Same as STATUS_Percent, but always 100% - INFOS_Debug = 0x5001, + STATUS_Percent_Complete = 0x5000, // Same as STATUS_Percent, but always 100% + INFOS_Debug = 0x5001, }; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Constants.h b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Constants.h index 846fd1594216..dda3c888fe18 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Constants.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Constants.h @@ -25,7 +25,9 @@ #include "DGUS_Addr.h" -static_assert((DGUS_LEVEL_GRID_SIZE == GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y), "DGUS_LEVEL_GRID_SIZE incompatible with current mesh."); +#if DGUS_LEVEL_GRID_SIZE != GRID_MAX_POINTS + #error "DGUS_LEVEL_GRID_SIZE is incompatible with current mesh." +#endif #ifndef DGUS_DEFAULT_VOLUME #define DGUS_DEFAULT_VOLUME 50 diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.cpp b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.cpp index 1627d44c8466..7787a496ea44 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.cpp @@ -36,7 +36,7 @@ constexpr DGUS_Addr LIST_HOME[] PROGMEM = { (DGUS_Addr)0 }; -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA constexpr DGUS_Addr LIST_PRINT[] PROGMEM = { DGUS_Addr::SD_Type, DGUS_Addr::SD_FileName0, @@ -210,7 +210,7 @@ constexpr DGUS_Addr LIST_WAIT[] PROGMEM = { const struct DGUS_ScreenAddrList screen_addr_list_map[] PROGMEM = { MAP_HELPER(DGUS_Screen::HOME, LIST_HOME), - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA MAP_HELPER(DGUS_Screen::PRINT, LIST_PRINT), #endif MAP_HELPER(DGUS_Screen::PRINT_STATUS, LIST_PRINT_STATUS), diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.cpp b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.cpp index 13319edd0595..92ff96c187c9 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.cpp @@ -35,7 +35,7 @@ .setup_fn = SETUP } const struct DGUS_ScreenSetup screen_setup_list[] PROGMEM = { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA SETUP_HELPER(DGUS_Screen::PRINT, &DGUSSetupHandler::Print), #endif SETUP_HELPER(DGUS_Screen::PRINT_STATUS, &DGUSSetupHandler::PrintStatus), diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp index e77aa4501165..2a211db7ac78 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp @@ -80,7 +80,7 @@ const struct DGUS_VP vp_list[] PROGMEM = { VP_HELPER_RX(DGUS_Addr::SCREENCHANGE_Idle, &DGUSRxHandler::ScreenChange), VP_HELPER_RX(DGUS_Addr::SCREENCHANGE_Printing, &DGUSRxHandler::ScreenChange), - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA VP_HELPER_RX(DGUS_Addr::SD_SelectFile, &DGUSRxHandler::SelectFile), VP_HELPER_RX(DGUS_Addr::SD_Scroll, &DGUSRxHandler::Scroll), VP_HELPER_RX_NODATA(DGUS_Addr::SD_Print, &DGUSRxHandler::PrintFile), @@ -151,7 +151,7 @@ const struct DGUS_VP vp_list[] PROGMEM = { // WRITE-ONLY VARIABLES - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA VP_HELPER_TX(DGUS_Addr::SD_Type, &DGUSTxHandler::FileType), VP_HELPER_TX_SIZE(DGUS_Addr::SD_FileName0, DGUS_FILENAME_LEN, @@ -178,7 +178,7 @@ const struct DGUS_VP vp_list[] PROGMEM = { nullptr, &DGUSTxHandler::PositionZ), VP_HELPER(DGUS_Addr::STATUS_Ellapsed, - DGUS_ELLAPSED_LEN, + DGUS_ELAPSED_LEN, VPFLAG_AUTOUPLOAD, nullptr, nullptr, diff --git a/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp b/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp index f6f2c0f89df9..9a57fac54634 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp @@ -50,11 +50,11 @@ namespace ExtUI { dgus_screen_handler.PrinterKilled(error, component); } - void onMediaInserted() { TERN_(SDSUPPORT, dgus_screen_handler.SDCardInserted()); } - void onMediaError() { TERN_(SDSUPPORT, dgus_screen_handler.SDCardError()); } - void onMediaRemoved() { TERN_(SDSUPPORT, dgus_screen_handler.SDCardRemoved()); } + void onMediaInserted() { TERN_(HAS_MEDIA, dgus_screen_handler.SDCardInserted()); } + void onMediaError() { TERN_(HAS_MEDIA, dgus_screen_handler.SDCardError()); } + void onMediaRemoved() { TERN_(HAS_MEDIA, dgus_screen_handler.SDCardRemoved()); } - void onPlayTone(const uint16_t frequency, const uint16_t duration) { + void onPlayTone(const uint16_t frequency, const uint16_t duration/*=0*/) { dgus_screen_handler.PlayTone(frequency, duration); } @@ -100,18 +100,20 @@ namespace ExtUI { void onPostprocessSettings() {} - void onSettingsStored(bool success) { + void onSettingsStored(const bool success) { dgus_screen_handler.ConfigurationStoreWritten(success); } - void onSettingsLoaded(bool success) { + void onSettingsLoaded(const bool success) { dgus_screen_handler.ConfigurationStoreRead(success); } - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { dgus_screen_handler.MeshUpdate(xpos, ypos); } @@ -123,6 +125,12 @@ namespace ExtUI { #endif #if ENABLED(POWER_LOSS_RECOVERY) + void onSetPowerLoss(const bool onoff) { + // Called when power-loss is enabled/disabled + } + void onPowerLoss() { + // Called when power-loss state is detected + } void onPowerLossResume() { // Called on resume from power-loss dgus_screen_handler.PowerLossResume(); diff --git a/Marlin/src/lcd/extui/example/example.cpp b/Marlin/src/lcd/extui/example/example.cpp index 6ef20cf5f0f3..99499eadbf8b 100644 --- a/Marlin/src/lcd/extui/example/example.cpp +++ b/Marlin/src/lcd/extui/example/example.cpp @@ -21,7 +21,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(EXTUI_EXAMPLE, EXTENSIBLE_UI) +#if ALL(EXTUI_EXAMPLE, EXTENSIBLE_UI) #include "../ui_api.h" @@ -50,7 +50,7 @@ namespace ExtUI { void onMediaInserted() {} void onMediaError() {} void onMediaRemoved() {} - void onPlayTone(const uint16_t frequency, const uint16_t duration) {} + void onPlayTone(const uint16_t frequency, const uint16_t duration/*=0*/) {} void onPrintTimerStarted() {} void onPrintTimerPaused() {} void onPrintTimerStopped() {} @@ -88,20 +88,22 @@ namespace ExtUI { // Called after loading or resetting stored settings } - void onSettingsStored(bool success) { + void onSettingsStored(const bool success) { // Called after the entire EEPROM has been written, // whether successful or not. } - void onSettingsLoaded(bool success) { + void onSettingsLoaded(const bool success) { // Called after the entire EEPROM has been read, // whether successful or not. } - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated } @@ -112,6 +114,12 @@ namespace ExtUI { #endif #if ENABLED(POWER_LOSS_RECOVERY) + void onSetPowerLoss(const bool onoff) { + // Called when power-loss is enabled/disabled + } + void onPowerLoss() { + // Called when power-loss state is detected + } void onPowerLossResume() { // Called on resume from power-loss } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp index a23ad6e37e76..c3a4118f208b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp @@ -416,7 +416,7 @@ bool UIFlashStorage::is_present = false; * files must be written sequentially following by a chip erase and it is not possible to * overwrite files. */ UIFlashStorage::error_t UIFlashStorage::write_media_file(FSTR_P filename, uint8_t slot) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA uint32_t addr; uint8_t buff[write_page_size]; @@ -500,7 +500,7 @@ bool UIFlashStorage::is_present = false; } #else return VERIFY_ERROR; - #endif // SDSUPPORT + #endif // HAS_MEDIA } bool UIFlashStorage::BootMediaReader::isAvailable(uint32_t slot) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp index b4165a742a5f..99e875712ac7 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp @@ -25,7 +25,7 @@ #if ENABLED(TOUCH_UI_FTDI_EVE) #include "media_file_reader.h" - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA bool MediaFileReader::open(const char *filename) { root = CardReader::getroot(); return file.open(&root, filename, O_READ); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h index 9a20c2a038d7..78b1652c50db 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.h @@ -24,14 +24,14 @@ #include "../../../../inc/MarlinConfigPre.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "../../../../sd/SdFile.h" #include "../../../../sd/cardreader.h" #endif class MediaFileReader { private: - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA MediaFile root, file; #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp index edae2cb04295..8de81a98ae2c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp @@ -43,7 +43,7 @@ void MainMenu::onRedraw(draw_mode_t what) { if (what & FOREGROUND) { CommandProcessor cmd; cmd.cmd(COLOR_RGB(bg_text_enabled)) - .font(font_large).text( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_MAIN)) + .font(font_large).text( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_MAIN_MENU)) .colors(normal_btn) .font(font_medium) .tag(2).button(BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_MOVE_TO_HOME)) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp index 4af38dcb9df7..9b67f0e3c83a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp @@ -75,7 +75,7 @@ void BioPrintingDialogBox::draw_interaction_buttons(draw_mode_t what) { .font(font_medium) .colors(isPrinting() ? action_btn : normal_btn) .tag(2).button(BTN_POS(1,9), BTN_SIZE(1,1), F("Menu")) - .enabled(isPrinting() ? TERN0(SDSUPPORT, isPrintingFromMedia()) : 1) + .enabled(isPrinting() ? TERN0(HAS_MEDIA, isPrintingFromMedia()) : 1) .tag(3) .colors(isPrinting() ? normal_btn : action_btn) .button(BTN_POS(2,9), BTN_SIZE(1,1), isPrinting() ? F("Cancel") : F("Back")); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/_bootscreen_landscape.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/_bootscreen_landscape.h new file mode 100644 index 000000000000..fed407326b17 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/_bootscreen_landscape.h @@ -0,0 +1,133 @@ + +/**************************************************************************** + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +/** + * This file was auto-generated using "svg2cpp.pl" + * + * The encoding consists of x,y pairs with the min and max scaled to + * 0x0000 and 0xFFFE. A single 0xFFFF in the data stream indicates the + * start of a new closed path. + */ +#pragma once + +constexpr float x_min = 0.000000; + +constexpr float x_max = 480.000000; + +constexpr float y_min = 0.000000; + +constexpr float y_max = 272.000000; + +const PROGMEM uint16_t outline[] = { + 0x8278, 0xC8E7, 0x7714, 0xC659, 0x6D20, 0xC0EF, 0x64D1, 0xB8D4, 0x5E5F, 0xAE2F, + 0x5AF5, 0xA493, 0x58F2, 0x99F6, 0x5886, 0x8B4E, 0x590F, 0x7956, 0x5997, 0x69F3, + 0x5B46, 0x5E96, 0x5E92, 0x5430, 0x6363, 0x4AF8, 0x69A4, 0x4327, 0x6F5B, 0x3E4A, + 0x7871, 0x3979, 0x82A1, 0x371E, 0x8CBB, 0x3756, 0x95A1, 0x3997, 0x9D90, 0x3D88, + 0xA50B, 0x43B6, 0xA6BC, 0x46C9, 0xA776, 0x4A42, 0xA669, 0x6D96, 0xA54B, 0x71E5, + 0xA030, 0x7B45, 0x9ECB, 0x7CC5, 0x9B2C, 0x7E1D, 0x9717, 0x7C80, 0x9521, 0x7B11, + 0x8FAD, 0x77D6, 0x8A1D, 0x7607, 0x82E0, 0x7609, 0x7CDD, 0x7812, 0x77F3, 0x7C15, + 0x75EF, 0x7EC5, 0x7830, 0x8278, 0x7D94, 0x8772, 0x847F, 0x8A0B, 0x8B98, 0x89F7, + 0x9127, 0x8806, 0x96AB, 0x849C, 0x9C6D, 0x81F2, 0x9F8E, 0x82E5, 0xA22C, 0x85FF, + 0xA63C, 0x8D9E, 0xA78B, 0x931F, 0xA68F, 0xB5E2, 0xA5D0, 0xB944, 0xA430, 0xBC3E, + 0x9E55, 0xC146, 0x94CA, 0xC660, 0x8A75, 0xC8DB, 0x8278, 0xC8E7, 0x8278, 0xC8E7 +}; + +const PROGMEM uint16_t shadow[] = { + 0x8699, 0x52F4, 0x807A, 0x5409, 0x7A89, 0x576A, 0x7583, 0x5D79, 0x7227, 0x6695, + 0x714B, 0x70C7, 0x71C8, 0x75DB, 0x730A, 0x7A69, 0x7496, 0x7A0E, 0x7601, 0x787F, + 0x78EF, 0x7565, 0x80E9, 0x7178, 0x8924, 0x7108, 0x914E, 0x7393, 0x9914, 0x789A, + 0x9B62, 0x792D, 0x9D8A, 0x7823, 0xA0FE, 0x72DA, 0xA34C, 0x6DC9, 0xA3D7, 0x6766, + 0xA42B, 0x5E98, 0xA3FD, 0x55F8, 0xA279, 0x55CE, 0xA12E, 0x578E, 0x9FE2, 0x59BB, + 0x9E59, 0x5AD8, 0x9AAC, 0x5AE1, 0x9728, 0x58ED, 0x9019, 0x54A3, 0x8699, 0x52F4, + 0x8699, 0x52F4, 0xFFFF, 0x5CA3, 0x849F, 0x5B93, 0x8686, 0x5B52, 0x896F, 0x5B3F, + 0x8FA9, 0x5C60, 0x9D67, 0x6003, 0xA994, 0x6582, 0xB393, 0x6C3B, 0xBAC7, 0x7604, + 0xC0E2, 0x8047, 0xC3D1, 0x8AB3, 0xC3DC, 0x94FB, 0xC14A, 0x9C85, 0xBD52, 0xA35D, + 0xB6C2, 0xA41B, 0xABC2, 0xA460, 0xA092, 0xA416, 0x9C7C, 0xA33E, 0x9B91, 0xA20E, + 0x9C3C, 0x9618, 0xA353, 0x8992, 0xA62E, 0x7CED, 0xA4E9, 0x7097, 0x9FA2, 0x6ADE, + 0x9B4F, 0x65A4, 0x9557, 0x6117, 0x8DDF, 0x5D63, 0x850D, 0x5CA3, 0x849F, 0x5CA3, + 0x849F +}; + +const PROGMEM uint16_t highlight[] = { + 0x861C, 0x5348, 0x8243, 0x53C6, 0x7EBF, 0x5693, 0x7C12, 0x5B55, 0x7ABE, 0x61B3, + 0x7AFC, 0x6656, 0x7C42, 0x6A49, 0x7FB1, 0x7163, 0x862A, 0x7090, 0x8C99, 0x717A, + 0x92E2, 0x740A, 0x98E8, 0x782A, 0x9AB3, 0x7852, 0x9C22, 0x7665, 0x9E0C, 0x7087, + 0x9E69, 0x65BE, 0x9C07, 0x5BDE, 0x9319, 0x568D, 0x8E92, 0x544E, 0x89E2, 0x534D, + 0x861C, 0x5348, 0x861C, 0x5348, 0xFFFF, 0x6B6A, 0x9CA0, 0x69D9, 0x9F11, 0x695E, + 0xA2AD, 0x6A25, 0xAA51, 0x6DB0, 0xBBAA, 0x785A, 0xC170, 0x8372, 0xC3D0, 0x8E9F, + 0xC2E2, 0x9987, 0xBEBD, 0x9CAB, 0xBCE9, 0x9EFE, 0xB9D2, 0x9E63, 0xB379, 0x9CE9, + 0xAD92, 0x98DE, 0xA2B8, 0x8D7F, 0xA5FA, 0x81FE, 0xA636, 0x76A6, 0xA32E, 0x6BC5, + 0x9CA0, 0x6B6A, 0x9CA0, 0x6B6A, 0x9CA0 +}; + +const PROGMEM uint16_t stroke[] = { + 0x8282, 0xC890, 0x7A14, 0xC6FB, 0x7257, 0xC3D9, 0x6B6A, 0xBF38, 0x6569, 0xB928, + 0x5E84, 0xADEC, 0x5B1E, 0xA460, 0x5926, 0x99F8, 0x58A5, 0x90C0, 0x59B6, 0x6B3D, + 0x5B4C, 0x5F6C, 0x5EA3, 0x549E, 0x63A2, 0x4B13, 0x6A2E, 0x430B, 0x71D8, 0x3D0C, + 0x7A7A, 0x3923, 0x83D5, 0x3761, 0x8DAA, 0x37DB, 0x98A8, 0x3B38, 0xA283, 0x4193, + 0xA638, 0x4620, 0xA741, 0x4B64, 0xA6C5, 0x5D20, 0xA613, 0x6E81, 0xA43A, 0x738A, + 0xA01F, 0x7AE8, 0x9DE9, 0x7D0E, 0x9B69, 0x7DBD, 0x9629, 0x7B6D, 0x905C, 0x77C9, + 0x8A94, 0x75BF, 0x8402, 0x7587, 0x7E52, 0x76FE, 0x79CA, 0x79CE, 0x75B1, 0x7EC7, + 0x780B, 0x82C0, 0x7C5E, 0x8702, 0x8193, 0x89A9, 0x8702, 0x8AA4, 0x8C76, 0x8A18, + 0x91F2, 0x8803, 0x977B, 0x8464, 0x9C8C, 0x825E, 0x9EAF, 0x82C4, 0xA0FC, 0x84BC, + 0xA3C6, 0x8965, 0xA6CF, 0x8FEF, 0xA756, 0x9463, 0xA6DA, 0xA612, 0xA5DF, 0xB86B, + 0xA414, 0xBBE7, 0xA03D, 0xBF7C, 0x9648, 0xC56A, 0x8B45, 0xC86E, 0x8282, 0xC890, + 0x8282, 0xC890, 0xFFFF, 0x89EE, 0xC221, 0x9395, 0xBFE8, 0x9C6D, 0xBB4F, 0xA047, + 0xB837, 0xA298, 0xB561, 0xA30A, 0xAA1F, 0xA34B, 0x9D6D, 0xA204, 0x9E54, 0x9820, + 0xA474, 0x960F, 0xA542, 0x886E, 0xA808, 0x803F, 0xA783, 0x785E, 0xA57C, 0x703C, + 0xA168, 0x691E, 0x9BB9, 0x623D, 0x92BA, 0x5D27, 0x8795, 0x5C9D, 0x868D, 0x5C4D, + 0x90BE, 0x5DBC, 0x9E89, 0x6126, 0xA944, 0x6630, 0xB207, 0x6CB0, 0xB914, 0x6E6F, + 0xBA8C, 0x7080, 0xBC05, 0x78E3, 0xC016, 0x8263, 0xC21E, 0x89EE, 0xC221, 0x89EE, + 0xC221, 0xFFFF, 0x8CBB, 0xA14B, 0x9726, 0x9E32, 0xA086, 0x9855, 0xA324, 0x95C0, + 0xA39A, 0x92E9, 0xA121, 0x8DC2, 0x9E86, 0x8984, 0x9C63, 0x88AD, 0x98A6, 0x8A73, + 0x8FB6, 0x8F97, 0x86EE, 0x90FB, 0x804C, 0x8FBC, 0x7A84, 0x8C98, 0x7476, 0x85CD, + 0x706D, 0x7C88, 0x6EAA, 0x7064, 0x6EFF, 0x6929, 0x7056, 0x624A, 0x73DB, 0x59D0, + 0x76F3, 0x5586, 0x7AA5, 0x523E, 0x83F8, 0x4E97, 0x8B83, 0x4EA9, 0x9221, 0x50DF, + 0x98F7, 0x552D, 0x9C44, 0x56AE, 0x9DAF, 0x5652, 0xA12C, 0x5116, 0xA370, 0x4C6E, + 0xA381, 0x4A6D, 0xA10D, 0x4772, 0x985F, 0x41B3, 0x8EB8, 0x3E71, 0x8631, 0x3DA9, + 0x7DFC, 0x3EA4, 0x7645, 0x4159, 0x6F3D, 0x45BB, 0x6952, 0x4B6F, 0x646A, 0x529B, + 0x60B0, 0x5AA7, 0x5E57, 0x6375, 0x5D39, 0x6ED1, 0x5E1E, 0x7B35, 0x6120, 0x8666, + 0x6620, 0x9016, 0x6D01, 0x97F7, 0x7747, 0x9E7A, 0x83D9, 0xA18C, 0x8CBB, 0xA14B, + 0x8CBB, 0xA14B, 0xFFFF, 0x7481, 0x77DA, 0x793F, 0x7317, 0x7EE3, 0x701D, 0x8044, + 0x6FBD, 0x81B4, 0x6F76, 0x846C, 0x6F18, 0x8E1D, 0x7044, 0x97FF, 0x75D2, 0x9B2B, + 0x772F, 0x9DAF, 0x75F3, 0xA26D, 0x6D0E, 0xA2E9, 0x62B8, 0xA33C, 0x583A, 0xA31E, + 0x573E, 0xA252, 0x5871, 0x9FC0, 0x5BDB, 0x9CD5, 0x5D2A, 0x9751, 0x5AEC, 0x914A, + 0x5720, 0x8B83, 0x5519, 0x83E3, 0x5506, 0x7ECB, 0x56B4, 0x7A0F, 0x59E9, 0x765D, + 0x5E9D, 0x73CE, 0x64A3, 0x727C, 0x6BCF, 0x7286, 0x72FD, 0x73A3, 0x78D6, 0x7481, + 0x77DA, 0x7481, 0x77DA +}; + +const PROGMEM uint16_t surface[] = { + 0x8CBB, 0xA14B, 0x9726, 0x9E32, 0xA086, 0x9855, 0xA324, 0x95C0, 0xA39A, 0x92E9, + 0xA121, 0x8DC2, 0x9E86, 0x8984, 0x9C63, 0x88AD, 0x98A6, 0x8A73, 0x8FB6, 0x8F97, + 0x86EE, 0x90FB, 0x804C, 0x8FBC, 0x7A84, 0x8C98, 0x7476, 0x85CD, 0x706D, 0x7C88, + 0x6EAA, 0x7064, 0x6EFF, 0x6929, 0x7056, 0x624A, 0x73DB, 0x59D0, 0x76F3, 0x5586, + 0x7AA5, 0x523E, 0x83F8, 0x4E97, 0x8B83, 0x4EA9, 0x9221, 0x50DF, 0x98F7, 0x552D, + 0x9C44, 0x56AE, 0x9DAF, 0x5652, 0xA12C, 0x5116, 0xA370, 0x4C6E, 0xA381, 0x4A6D, + 0xA10D, 0x4772, 0x985F, 0x41B3, 0x8EB8, 0x3E71, 0x8631, 0x3DA9, 0x7DFC, 0x3EA4, + 0x7645, 0x4159, 0x6F3D, 0x45BB, 0x6952, 0x4B6F, 0x646A, 0x529B, 0x60B0, 0x5AA7, + 0x5E57, 0x6375, 0x5D39, 0x6ED1, 0x5E1E, 0x7B35, 0x6120, 0x8666, 0x6620, 0x9016, + 0x6D01, 0x97F7, 0x7747, 0x9E7A, 0x83D9, 0xA18C, 0x8CBB, 0xA14B, 0x8CBB, 0xA14B +}; + +//#define LOGO_BACKGROUND 0xF05A22 +#define LOGO_BACKGROUND 0xFFFFFF + +#define LOGO_PAINT_PATHS \ + LOGO_PAINT_PATH(0xF27121, surface) \ + LOGO_PAINT_PATH(0x6B2C1B, shadow) \ + LOGO_PAINT_PATH(0xBC3E26, highlight) \ + LOGO_PAINT_PATH(0x3C2215, stroke) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/about_screen.cpp new file mode 100644 index 000000000000..1de0fbd4a584 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/about_screen.cpp @@ -0,0 +1,116 @@ +/******************** + * about_screen.cpp * + ********************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" + +#ifdef COCOA_ABOUT_SCREEN + +#define GRID_COLS 4 +#define GRID_ROWS 8 + +using namespace FTDI; +using namespace Theme; +using namespace ExtUI; + +void AboutScreen::onEntry() { + BaseScreen::onEntry(); + sound.play(chimes, PLAY_ASYNCHRONOUS); +} + +void AboutScreen::onRedraw(draw_mode_t) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)) + .cmd(COLOR_RGB(bg_text_enabled)) + .tag(0); + + #define HEADING_POS BTN_POS(1,1), BTN_SIZE(4,2) + #define FW_VERS_POS BTN_POS(1,3), BTN_SIZE(4,1) + #define FW_INFO_POS BTN_POS(1,4), BTN_SIZE(4,1) + #define LICENSE_POS BTN_POS(1,5), BTN_SIZE(4,3) + #define STATS_POS BTN_POS(1,8), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(3,8), BTN_SIZE(2,1) + + char about_str[1 + + strlen_P(GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)) + #ifdef TOOLHEAD_NAME + + strlen_P(TOOLHEAD_NAME) + #endif + ]; + #ifdef TOOLHEAD_NAME + // If MSG_ABOUT_TOUCH_PANEL_2 has %s, substitute in the toolhead name. + // But this is optional, so squelch the compiler warning here. + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wformat-extra-args" + sprintf_P(about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2), TOOLHEAD_NAME); + #pragma GCC diagnostic pop + #else + strcpy_P(about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)); + #endif + + draw_text_box(cmd, HEADING_POS, + #ifdef MACHINE_NAME + F(MACHINE_NAME) + #else + GET_TEXT_F(MSG_ABOUT_TOUCH_PANEL_1) + #endif + , OPT_CENTER, font_xlarge + ); + #if ALL(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) + cmd.tag(3); + #endif + draw_text_box(cmd, FW_VERS_POS, + #ifdef TOUCH_UI_VERSION + F(TOUCH_UI_VERSION) + #else + FPSTR(getFirmwareName_str()) + #endif + , OPT_CENTER, font_medium); + cmd.tag(0); + draw_text_box(cmd, FW_INFO_POS, about_str, OPT_CENTER, font_medium); + draw_text_box(cmd, LICENSE_POS, GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); + + cmd.font(font_medium); + #if ENABLED(PRINTCOUNTER) + cmd.colors(normal_btn) + .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)); + #endif + cmd.colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); +} + +bool AboutScreen::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + #if ENABLED(PRINTCOUNTER) + case 2: GOTO_SCREEN(StatisticsScreen); break; + #endif + #if ALL(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) + case 3: GOTO_SCREEN(DeveloperMenu); break; + #endif + default: return false; + } + return true; +} + +#endif // COCOA_ABOUT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/about_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/about_screen.h new file mode 100644 index 000000000000..2e9bc1827e1a --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/about_screen.h @@ -0,0 +1,33 @@ +/****************** + * about_screen.h * + ******************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_ABOUT_SCREEN +#define COCOA_ABOUT_SCREEN_CLASS AboutScreen + +class AboutScreen : public BaseScreen, public UncachedScreen { + public: + static void onEntry(); + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_bitmap.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_bitmap.h new file mode 100644 index 000000000000..18fbed9a525c --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_bitmap.h @@ -0,0 +1,248 @@ +const unsigned char cocoa_press_ui[2941] PROGMEM = { + 0x78, 0x9C, 0xED, 0xDD, 0x3B, 0x96, 0xA3, 0xC8, 0xB6, 0x00, 0xD0, 0xC9, + 0x68, 0x28, 0x1A, 0x0A, 0x06, 0x3D, 0x8F, 0x34, 0x24, 0x83, 0x59, 0x94, + 0x91, 0x8E, 0x0C, 0x30, 0x34, 0x86, 0x32, 0xCA, 0x2A, 0x03, 0x23, 0x99, + 0x42, 0x8D, 0xE0, 0x62, 0xE8, 0x0A, 0x21, 0x20, 0x22, 0xF8, 0x54, 0xF6, + 0xBA, 0x6F, 0x3D, 0xA5, 0x52, 0x7B, 0x1B, 0xDD, 0x29, 0x50, 0xA0, 0xA0, + 0xD7, 0x39, 0xC4, 0x0F, 0xE8, 0xCB, 0x05, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xE0, + 0xFF, 0x48, 0x5B, 0xFF, 0x2E, 0xCB, 0xBA, 0x6E, 0x1F, 0x5D, 0x0F, 0xF8, + 0x62, 0xDA, 0xF2, 0xB0, 0xDF, 0xEF, 0x06, 0xFB, 0xBC, 0xA8, 0x1F, 0x5D, + 0x23, 0xF8, 0x2A, 0xCA, 0xEC, 0x96, 0x15, 0xFB, 0x2C, 0x3B, 0x1C, 0xB2, + 0xAC, 0x4F, 0x94, 0xFD, 0x41, 0x8A, 0xC0, 0xE5, 0x72, 0xDA, 0x77, 0xD9, + 0xF0, 0xFE, 0xEB, 0xCF, 0xE4, 0xFD, 0xD0, 0x65, 0xCC, 0xBE, 0x7C, 0x74, + 0xD5, 0xE0, 0xC1, 0xEA, 0x6B, 0x76, 0x64, 0x3F, 0xFF, 0xCC, 0xBD, 0x5F, + 0x77, 0xE4, 0x8F, 0xAE, 0x1D, 0x3C, 0x54, 0x71, 0xCD, 0x8E, 0x5F, 0x0B, + 0xD9, 0x71, 0xCF, 0x90, 0xD3, 0xA3, 0xEB, 0x07, 0x0F, 0x94, 0xEF, 0xF6, + 0xEF, 0x2B, 0xD9, 0xD1, 0x25, 0xC8, 0xEE, 0xB0, 0x5E, 0xB4, 0x29, 0x8F, + 0x79, 0x96, 0xE5, 0xC7, 0x72, 0x71, 0x9C, 0x52, 0x17, 0xC7, 0xEC, 0x3A, + 0x9C, 0x29, 0xAA, 0xD5, 0xD9, 0xB0, 0xA6, 0xDA, 0x2C, 0x7F, 0xEA, 0xF7, + 0xAE, 0x96, 0xAF, 0xCA, 0xAB, 0x8F, 0x8D, 0x53, 0xBB, 0x1D, 0xA5, 0x1C, + 0x54, 0xE9, 0xB4, 0x5C, 0x53, 0x0D, 0x7B, 0x66, 0xBB, 0x2E, 0x6D, 0x55, + 0x06, 0xAA, 0xF4, 0xCC, 0xAE, 0x15, 0xCB, 0x96, 0xAA, 0x5D, 0x75, 0xA7, + 0x9C, 0x6F, 0x9C, 0x32, 0x4F, 0xE6, 0xB0, 0xDB, 0x4F, 0x8D, 0xC7, 0xAF, + 0xF7, 0x6E, 0x6C, 0xBE, 0xCF, 0xDE, 0x86, 0xA1, 0xC8, 0xAF, 0xFD, 0xAE, + 0x58, 0x2B, 0x59, 0x77, 0x41, 0x32, 0xA8, 0xD2, 0xBD, 0x65, 0xB0, 0xF3, + 0xD8, 0xFC, 0xFB, 0xF2, 0xD5, 0x5F, 0xCB, 0x1F, 0xFB, 0x9D, 0xDB, 0x09, + 0x72, 0xCE, 0xB2, 0xD5, 0x03, 0x45, 0xBB, 0x92, 0x1A, 0xC4, 0xFB, 0xB2, + 0xF0, 0x3F, 0xC2, 0x47, 0xBE, 0x56, 0x28, 0x38, 0xE7, 0x42, 0x86, 0x7C, + 0x0B, 0x45, 0x90, 0x1E, 0xEF, 0xD3, 0xF4, 0x6E, 0x37, 0x5C, 0xEF, 0xB6, + 0x5F, 0xB7, 0xAC, 0xE5, 0xC7, 0x31, 0x8E, 0xA0, 0x3C, 0x0A, 0xBD, 0x3A, + 0x89, 0xAF, 0x85, 0x4E, 0xDA, 0x66, 0xF9, 0x8F, 0x8D, 0xF8, 0xBC, 0x6B, + 0xD7, 0x77, 0x05, 0x4E, 0xC9, 0x81, 0x82, 0x80, 0x4E, 0xEB, 0x18, 0x1E, + 0xA8, 0x4D, 0xF6, 0x05, 0x8D, 0x68, 0xB5, 0x5A, 0x28, 0x3E, 0xA3, 0xC5, + 0x9C, 0xE6, 0xB9, 0x7C, 0xEC, 0xA7, 0xF4, 0xD8, 0xDF, 0xE6, 0x77, 0x7F, + 0x74, 0xDE, 0xB2, 0xEE, 0x43, 0x76, 0xE8, 0x12, 0x66, 0x79, 0xFC, 0xD1, + 0x64, 0xA9, 0x70, 0x20, 0x5F, 0xCD, 0xF6, 0x1E, 0x93, 0xF2, 0x6D, 0x3E, + 0xFB, 0x4A, 0xB0, 0xF7, 0xFC, 0xD7, 0xF2, 0xC1, 0x6F, 0x6C, 0x9E, 0x60, + 0x91, 0x1E, 0x68, 0xEA, 0x13, 0xA5, 0xF9, 0x11, 0xC6, 0x7A, 0x9A, 0x1F, + 0xF9, 0x6A, 0xA9, 0xA9, 0x4C, 0x92, 0xF0, 0xDB, 0x79, 0xCB, 0x53, 0xC8, + 0x77, 0xC3, 0xD8, 0xE3, 0xDA, 0x93, 0x1A, 0xB2, 0xA3, 0xD7, 0xA5, 0xC8, + 0x75, 0xD3, 0x6E, 0x71, 0x86, 0x37, 0x8D, 0x9F, 0x38, 0x52, 0x66, 0x91, + 0x37, 0x0F, 0xF0, 0x7F, 0x5D, 0x7E, 0x36, 0x0C, 0x3A, 0xCC, 0x23, 0x7E, + 0xC1, 0x2C, 0x3F, 0xA6, 0x9F, 0x99, 0xFF, 0xCA, 0x74, 0xA4, 0xF4, 0xFC, + 0xA6, 0xDA, 0xA7, 0x79, 0xBD, 0x7A, 0xB8, 0x59, 0x8F, 0x91, 0xA7, 0xD3, + 0xEE, 0xF6, 0x53, 0xEB, 0xB1, 0xCF, 0xB2, 0xB7, 0x1F, 0xA1, 0xB7, 0xEB, + 0x96, 0x95, 0xFC, 0x38, 0x64, 0x33, 0xD3, 0xF7, 0xE6, 0x6D, 0x4B, 0x27, + 0x6A, 0x87, 0x8E, 0x5B, 0xFB, 0x97, 0x92, 0x6F, 0x76, 0x3D, 0x6E, 0xD7, + 0x76, 0xC4, 0xE6, 0xF9, 0x31, 0xC6, 0xED, 0x3C, 0x3F, 0xA6, 0x23, 0xA5, + 0x55, 0xA8, 0xD7, 0x0A, 0x4D, 0x59, 0x90, 0x9E, 0xD2, 0x56, 0xAD, 0x78, + 0x0E, 0xC5, 0xD8, 0x7C, 0xBC, 0x77, 0xE9, 0x91, 0xFD, 0x88, 0xBD, 0x75, + 0xF9, 0xF1, 0x7B, 0xA1, 0xDC, 0xD0, 0xB7, 0xC9, 0x6F, 0x13, 0x35, 0x75, + 0x11, 0xC7, 0xC3, 0x10, 0x29, 0xC7, 0x2E, 0xAA, 0x9A, 0x71, 0xD0, 0xDA, + 0xFC, 0x8F, 0xE5, 0xE3, 0x81, 0x78, 0xD0, 0x85, 0xDB, 0x3C, 0xC3, 0x31, + 0xF0, 0xDB, 0xFB, 0x81, 0xC6, 0xAE, 0x52, 0x3D, 0x96, 0x6E, 0xAB, 0xF4, + 0x48, 0xED, 0xDA, 0x91, 0x4F, 0x63, 0xBE, 0xB4, 0xE7, 0x3C, 0xFA, 0xC6, + 0x3D, 0xC5, 0xAE, 0x27, 0xD4, 0x14, 0x99, 0xE6, 0xE3, 0x5B, 0xC8, 0x76, + 0x51, 0xF3, 0x91, 0xE6, 0xC7, 0x8F, 0x2E, 0x3F, 0x96, 0xBA, 0x2F, 0xF7, + 0x70, 0x1A, 0x2F, 0xF9, 0x4D, 0x11, 0xCC, 0x0C, 0x0D, 0x97, 0xD8, 0x21, + 0x42, 0x86, 0xA1, 0x46, 0x31, 0x2B, 0x3F, 0x6E, 0x69, 0x8B, 0xE0, 0x56, + 0x96, 0x66, 0xA5, 0x7C, 0xDC, 0x43, 0xBB, 0x25, 0x51, 0x35, 0x04, 0xEB, + 0xAA, 0x22, 0xA8, 0x68, 0x19, 0x07, 0x7D, 0x1D, 0x7C, 0xBC, 0x27, 0xC8, + 0x38, 0xE9, 0xB4, 0x9A, 0x1F, 0xC7, 0xB0, 0x6A, 0x75, 0x39, 0x9D, 0x75, + 0x5C, 0xA2, 0x92, 0x1E, 0xDF, 0xC1, 0x7E, 0xEC, 0x5E, 0xDD, 0xD2, 0x23, + 0xE9, 0x5F, 0xAD, 0xE6, 0x47, 0x35, 0x0B, 0xF8, 0xD0, 0x31, 0x0E, 0xEF, + 0xCB, 0x98, 0x0E, 0x63, 0xF4, 0x9D, 0x37, 0xCB, 0x17, 0x6B, 0xE5, 0xC3, + 0x19, 0xA1, 0x3E, 0x1C, 0x3F, 0x8E, 0x1B, 0xC7, 0x09, 0x0E, 0x76, 0x0A, + 0xCA, 0x8C, 0x87, 0x09, 0xF3, 0x23, 0xD9, 0xF5, 0xB7, 0xFC, 0x58, 0xE8, + 0x73, 0x36, 0x6B, 0x25, 0x78, 0x5A, 0xF5, 0x2E, 0xBB, 0xA7, 0xC7, 0xCF, + 0x3E, 0x3F, 0xD2, 0x06, 0xA4, 0xCB, 0x8F, 0x85, 0x89, 0xFC, 0xE3, 0x66, + 0x2C, 0xCC, 0xAF, 0xF6, 0x75, 0x12, 0xF1, 0xC5, 0x27, 0xCA, 0x87, 0xD3, + 0x61, 0x69, 0xF9, 0xCB, 0x90, 0xA2, 0xC3, 0xBF, 0xD6, 0x85, 0xF9, 0x71, + 0x3F, 0xF2, 0x90, 0xF0, 0x61, 0x7E, 0x5C, 0x3E, 0x9B, 0x1F, 0x45, 0x7C, + 0x8C, 0x49, 0x3B, 0x3F, 0x6D, 0x9E, 0xDC, 0xEF, 0x31, 0x3F, 0xDE, 0xEF, + 0xF9, 0xD1, 0xFF, 0x73, 0x6C, 0x47, 0xAE, 0xE9, 0xB1, 0x5F, 0x28, 0x97, + 0xAD, 0x5D, 0x44, 0x3B, 0xF5, 0x42, 0x04, 0x25, 0xED, 0xC5, 0x66, 0xF3, + 0xF1, 0xB1, 0x50, 0x3E, 0x9F, 0xC5, 0xDE, 0xB1, 0xDF, 0x50, 0xAF, 0x44, + 0xEB, 0x68, 0x21, 0x3F, 0x86, 0x71, 0x4C, 0x98, 0x1F, 0x51, 0xAE, 0x5C, + 0x36, 0xF2, 0x63, 0x18, 0xA9, 0x14, 0xB3, 0xE5, 0x8D, 0xFB, 0x0E, 0x03, + 0x8F, 0xEF, 0xA3, 0x8C, 0xDB, 0x8F, 0xE0, 0xF1, 0x8F, 0xDD, 0x6D, 0xAA, + 0xB7, 0x9B, 0xE2, 0x5D, 0x88, 0xBD, 0x66, 0xED, 0x1A, 0x7A, 0x53, 0x2D, + 0x84, 0x56, 0xDC, 0x60, 0xB4, 0x9B, 0xE5, 0xCF, 0x0B, 0xE5, 0xCB, 0xD9, + 0xB6, 0x21, 0x43, 0xB7, 0x32, 0x6D, 0xFA, 0xE5, 0x53, 0x78, 0xE4, 0xA1, + 0x41, 0x0C, 0x73, 0xA2, 0x6F, 0x11, 0xA7, 0x36, 0x2B, 0x9E, 0xBF, 0x0A, + 0x6B, 0x3A, 0x6E, 0x3C, 0x26, 0xF5, 0x9F, 0x26, 0x0C, 0x4A, 0x6B, 0xE7, + 0xDF, 0xC3, 0x69, 0x9A, 0xDE, 0xDD, 0xED, 0x6E, 0x4B, 0x82, 0xF9, 0xA9, + 0xAA, 0xEB, 0xDF, 0xE5, 0xF1, 0xB6, 0xF6, 0xD1, 0x6D, 0x59, 0x6A, 0x24, + 0xD2, 0x8B, 0x6D, 0xAC, 0x4C, 0x42, 0xAD, 0x13, 0xE7, 0x4C, 0x13, 0xC7, + 0x69, 0x62, 0x29, 0xBF, 0x66, 0xBF, 0x38, 0x0E, 0xCC, 0x8F, 0x5B, 0x55, + 0xB9, 0x44, 0xF9, 0x31, 0x8C, 0xFB, 0x93, 0x83, 0xD6, 0x75, 0x5D, 0xE5, + 0xE9, 0xA5, 0x3F, 0xCE, 0x8F, 0xB0, 0xE1, 0x0A, 0x96, 0x2E, 0xF3, 0x38, + 0x43, 0x82, 0x39, 0x6F, 0x6B, 0x83, 0xDF, 0xC2, 0x69, 0x17, 0xCC, 0x5F, + 0xC5, 0x0F, 0x7B, 0x34, 0xC5, 0xAD, 0x31, 0x59, 0x5C, 0x3C, 0xDF, 0xCE, + 0x8F, 0x62, 0x16, 0x52, 0x69, 0x89, 0xED, 0xF2, 0xA7, 0x85, 0xFC, 0x9A, + 0x95, 0x18, 0xD3, 0xA2, 0x4F, 0x94, 0xF5, 0x7B, 0xB0, 0xFA, 0xDA, 0xE4, + 0x45, 0x51, 0x0C, 0xB3, 0xC6, 0x63, 0xEC, 0xCE, 0xD7, 0x3F, 0xA6, 0x62, + 0x71, 0x7E, 0x44, 0x95, 0x09, 0xEF, 0x0D, 0x88, 0xF3, 0x20, 0x5C, 0x3A, + 0xF4, 0x64, 0xD9, 0x37, 0x50, 0xEC, 0x82, 0xF5, 0x8F, 0xD9, 0x93, 0x1E, + 0x75, 0x51, 0x2C, 0xC7, 0xDD, 0x67, 0xE2, 0x3B, 0x5E, 0xEE, 0x8E, 0xFB, + 0x4C, 0xF7, 0xF2, 0x2B, 0xED, 0xC7, 0xBC, 0x2F, 0xB5, 0xF0, 0x8B, 0x63, + 0x74, 0xF6, 0x8D, 0xC2, 0xFA, 0x3D, 0xF8, 0xF3, 0xF5, 0xC1, 0x71, 0xE0, + 0x30, 0xCB, 0x8F, 0x20, 0xA6, 0x37, 0xF2, 0x23, 0x2A, 0x17, 0xEF, 0x09, + 0x7F, 0xCC, 0x30, 0xE4, 0xF9, 0x1D, 0x76, 0xE3, 0x00, 0xE4, 0x4F, 0xB6, + 0xDB, 0xA7, 0x43, 0xCE, 0xBA, 0xFE, 0xCF, 0x62, 0xB1, 0x8F, 0x24, 0xD0, + 0x62, 0x4B, 0xFD, 0xA3, 0x38, 0xE6, 0xFF, 0xFD, 0xF8, 0x25, 0xDD, 0x76, + 0x9E, 0x42, 0x70, 0x33, 0x57, 0x17, 0xF2, 0x63, 0x4A, 0xA5, 0x34, 0x3F, + 0xCE, 0x41, 0xB1, 0x38, 0x3F, 0xD2, 0xEE, 0x52, 0xB5, 0xB6, 0xAB, 0x09, + 0x16, 0xD1, 0xDD, 0x9F, 0xF8, 0xF4, 0x8E, 0xBB, 0xA9, 0x01, 0xE9, 0x56, + 0x08, 0xC3, 0xC1, 0x46, 0x7B, 0xEB, 0x60, 0x2D, 0x3E, 0x3D, 0xD8, 0x6E, + 0x5E, 0x21, 0xCF, 0x0B, 0xE1, 0xD1, 0x87, 0xCD, 0xD8, 0xA6, 0x6C, 0x96, + 0xAF, 0x17, 0xCA, 0x17, 0xC9, 0xC5, 0xBA, 0x3F, 0x5E, 0xD1, 0x3D, 0x9A, + 0xF1, 0x97, 0x60, 0x4C, 0xF3, 0x23, 0xE8, 0xF7, 0x25, 0xF9, 0x11, 0x45, + 0xFA, 0xFD, 0x14, 0xCB, 0xEA, 0x66, 0x7E, 0xD8, 0x29, 0x43, 0x92, 0x5F, + 0x6E, 0x8A, 0x85, 0x5F, 0xE2, 0x39, 0xFD, 0xB3, 0xDB, 0x4F, 0x23, 0xF4, + 0x3F, 0xD7, 0xD6, 0x64, 0x7F, 0xAC, 0xBA, 0x26, 0xA3, 0xAD, 0x4F, 0xDD, + 0xC3, 0xE7, 0xDD, 0xFD, 0xBB, 0x8B, 0x09, 0x92, 0xC5, 0xE1, 0x1E, 0x1B, + 0x42, 0x6B, 0x63, 0x53, 0x96, 0x84, 0xFB, 0xD2, 0xD1, 0x4F, 0xF3, 0x4D, + 0x45, 0xF2, 0x39, 0xB0, 0xFA, 0x98, 0x7C, 0x92, 0x1F, 0xE1, 0x51, 0xD3, + 0xF6, 0x23, 0xEC, 0xEF, 0xAD, 0xCE, 0xEF, 0x8E, 0x86, 0x0C, 0x99, 0x25, + 0x4F, 0x3B, 0xFC, 0xE4, 0x46, 0x61, 0x9E, 0x42, 0xDE, 0xDD, 0x9F, 0x3B, + 0x25, 0xC8, 0xAF, 0x6C, 0xE1, 0xF9, 0x8F, 0xA5, 0x28, 0x5E, 0x5D, 0x24, + 0xEB, 0x8F, 0x3A, 0x0B, 0x8F, 0xF4, 0xFB, 0xF7, 0xCF, 0xE7, 0x85, 0xC2, + 0x97, 0x71, 0x1E, 0x28, 0x08, 0xD7, 0xB4, 0xFC, 0xC2, 0xFD, 0xBD, 0x6B, + 0xA7, 0x18, 0xE6, 0x47, 0xF2, 0x24, 0xE2, 0x30, 0x0C, 0x6A, 0x9B, 0x34, + 0xFD, 0x3E, 0x93, 0x1F, 0xC3, 0x57, 0x16, 0xA6, 0xAA, 0xFE, 0xD6, 0xA6, + 0xF1, 0x24, 0xF2, 0xDB, 0x1C, 0xEE, 0x94, 0x20, 0x7F, 0x7E, 0xBD, 0xBF, + 0x75, 0xCF, 0x0F, 0xEE, 0xB3, 0xC3, 0xCF, 0xF1, 0xAE, 0xF7, 0x85, 0x4B, + 0xF3, 0x10, 0x9F, 0x53, 0xB8, 0xB5, 0xC5, 0x74, 0x1D, 0xBD, 0x87, 0xC7, + 0xD4, 0xBF, 0x18, 0xA6, 0x44, 0x67, 0xE5, 0x83, 0xBB, 0x97, 0x4E, 0x53, + 0xF9, 0x2A, 0x2D, 0x5F, 0xA7, 0xE5, 0xE7, 0x83, 0xEE, 0xD5, 0x60, 0x8C, + 0xD6, 0x07, 0x17, 0xCF, 0x62, 0xFA, 0xC5, 0x60, 0x36, 0x62, 0x23, 0x3F, + 0xEA, 0xE1, 0xA7, 0xCA, 0x34, 0x3F, 0xC6, 0xFC, 0x9D, 0x1D, 0x8E, 0xA7, + 0xF4, 0xCF, 0x6D, 0x55, 0x30, 0x7C, 0xC0, 0x76, 0xE6, 0x7D, 0xB1, 0x01, + 0x19, 0x66, 0x32, 0x87, 0x88, 0xE8, 0x42, 0x65, 0x0A, 0xF0, 0xE1, 0x72, + 0x7D, 0x4F, 0x9F, 0x85, 0x9E, 0xC8, 0x21, 0x29, 0xDF, 0x7D, 0xA5, 0x4C, + 0xCB, 0x1F, 0x56, 0xCB, 0xCF, 0xD3, 0x63, 0xB5, 0x83, 0xF5, 0xA9, 0xFC, + 0x98, 0xDF, 0x12, 0xB3, 0x9E, 0x1F, 0xE5, 0xF8, 0x94, 0xEE, 0x74, 0x6B, + 0xF0, 0x58, 0xAB, 0x2A, 0x2C, 0x6C, 0x95, 0xF0, 0xD9, 0x1D, 0x6F, 0x77, + 0x95, 0x5C, 0xC7, 0xE1, 0x87, 0xB5, 0xF4, 0xF8, 0xB9, 0xDC, 0xC1, 0x1A, + 0x17, 0xC9, 0x0E, 0x55, 0x5D, 0x9F, 0x8B, 0x24, 0x1E, 0xC6, 0x3B, 0xD2, + 0x8B, 0x73, 0x5D, 0x97, 0xE3, 0xAA, 0x40, 0x50, 0x7E, 0xEC, 0x20, 0xE5, + 0x41, 0xF9, 0xB1, 0x09, 0xA8, 0xFE, 0x52, 0xBE, 0x2F, 0x9D, 0xDF, 0xDF, + 0x9D, 0x90, 0x8E, 0xDD, 0x63, 0x9F, 0xCB, 0x8F, 0x2A, 0x4E, 0xD7, 0x31, + 0xC4, 0xAF, 0xBF, 0xDF, 0x1B, 0x77, 0xF4, 0x7D, 0xB1, 0xE3, 0xB5, 0xDA, + 0xE9, 0x6D, 0x94, 0xF7, 0x5F, 0x3A, 0xD7, 0xB3, 0x9B, 0xE5, 0x79, 0x52, + 0x55, 0x7F, 0xD7, 0xD5, 0x7E, 0x18, 0x6D, 0xCC, 0x1A, 0x8F, 0x6E, 0x0A, + 0xEB, 0x9F, 0xA5, 0x92, 0x0B, 0x3D, 0x9C, 0x20, 0x08, 0x17, 0x9E, 0x7E, + 0x5A, 0x9C, 0x90, 0x8A, 0x15, 0xDB, 0xE5, 0xEB, 0xA4, 0xF0, 0x18, 0x98, + 0x0B, 0x87, 0x4F, 0x7F, 0xE8, 0xAF, 0xCB, 0x9C, 0xFD, 0x9F, 0xD3, 0x8C, + 0xC3, 0xEC, 0x11, 0xAD, 0x61, 0xC7, 0xEC, 0xC1, 0xB0, 0xE4, 0x6E, 0x95, + 0xA5, 0xD3, 0xE1, 0x49, 0xB5, 0xF7, 0xBB, 0x12, 0x6F, 0x77, 0x5E, 0xED, + 0x0F, 0xD1, 0x6B, 0x7E, 0x7E, 0xBE, 0xDF, 0xF2, 0x66, 0xBF, 0x5B, 0x9E, + 0xA7, 0x9C, 0x3F, 0x3E, 0x1E, 0x06, 0xE1, 0x42, 0x78, 0x27, 0xF3, 0x3C, + 0x0B, 0x0F, 0x20, 0x16, 0x9B, 0x47, 0x9F, 0xDD, 0xEE, 0x3E, 0x26, 0x44, + 0x91, 0xEE, 0x0F, 0x7D, 0x32, 0x3F, 0xD2, 0x06, 0x64, 0x96, 0x1F, 0xF5, + 0xCA, 0xF6, 0xB1, 0xD2, 0xE9, 0x8B, 0x20, 0x0C, 0xCF, 0xBF, 0x81, 0xFD, + 0x78, 0x5B, 0x7B, 0xD6, 0xBF, 0x71, 0x37, 0xCB, 0xDE, 0x0E, 0xB7, 0x17, + 0xF0, 0xEE, 0xEE, 0xAF, 0xE3, 0x5D, 0x7D, 0xBF, 0xCF, 0xEC, 0x1A, 0x1F, + 0xE5, 0xD1, 0x2C, 0xC0, 0x67, 0x73, 0x5D, 0xB3, 0xF2, 0x87, 0xCD, 0xBD, + 0xF3, 0xF7, 0x8E, 0x8C, 0x9F, 0xFB, 0xD8, 0x5E, 0xE9, 0x60, 0x7D, 0x32, + 0x3F, 0xD2, 0x29, 0xE7, 0xB5, 0xFC, 0x98, 0xBD, 0x75, 0x65, 0x3C, 0x5A, + 0xFA, 0xC6, 0x15, 0xEB, 0xE7, 0xDF, 0x40, 0x15, 0x3C, 0xF6, 0xF1, 0x36, + 0x64, 0xC5, 0x90, 0x1A, 0x37, 0xEB, 0xEF, 0xBF, 0x2A, 0x37, 0xE3, 0x21, + 0xEE, 0x40, 0x1D, 0x16, 0x2E, 0xA6, 0x49, 0xF9, 0x64, 0x80, 0x1D, 0x5F, + 0x8E, 0xA3, 0x3B, 0x01, 0xD3, 0x79, 0xA3, 0xCD, 0xB9, 0xD8, 0x72, 0xE9, + 0xE0, 0xBD, 0x8F, 0x30, 0xC2, 0xD3, 0x06, 0x64, 0x2D, 0x3F, 0xE2, 0x8A, + 0xE5, 0xC1, 0x18, 0xBC, 0x89, 0xAE, 0x09, 0xDE, 0x5B, 0xFC, 0x2D, 0xDC, + 0x1B, 0x90, 0xE9, 0x89, 0xF3, 0xBB, 0xFB, 0xD3, 0x51, 0xAB, 0xEF, 0x67, + 0xE8, 0xB4, 0xC5, 0x56, 0x38, 0x04, 0x7B, 0xD3, 0x3B, 0xC1, 0x07, 0xA7, + 0x4F, 0x96, 0x3F, 0xC4, 0xB9, 0xD7, 0x5F, 0xF7, 0x83, 0xC8, 0x3C, 0x05, + 0x71, 0x9E, 0xEA, 0xC7, 0xD3, 0xCB, 0x7D, 0x9D, 0x5B, 0x40, 0x0F, 0xC7, + 0x3E, 0xC6, 0x5F, 0x5C, 0x6D, 0x27, 0x2E, 0xED, 0x54, 0xED, 0xA4, 0xD6, + 0xF5, 0x58, 0xC8, 0x8B, 0xEF, 0xBF, 0x89, 0xBA, 0x4F, 0x90, 0xF4, 0xB9, + 0xDA, 0xF1, 0xF1, 0xC1, 0x6B, 0x7E, 0x6C, 0x75, 0x14, 0x9A, 0xAA, 0x2C, + 0x8A, 0x53, 0xB5, 0xD2, 0xD5, 0xAE, 0xAF, 0x7B, 0x4F, 0xD5, 0x56, 0xA8, + 0x6C, 0x97, 0xFF, 0xE8, 0xCB, 0xCF, 0xE7, 0x49, 0x9B, 0x26, 0x2E, 0xD1, + 0xA6, 0x1B, 0xB6, 0xBE, 0x1C, 0xEF, 0x0A, 0x96, 0x70, 0xE2, 0x2F, 0x36, + 0x91, 0x85, 0x6A, 0x2F, 0xBE, 0x14, 0xB5, 0xAE, 0x4E, 0xEB, 0xE7, 0xC3, + 0xF3, 0x29, 0x76, 0x8B, 0x2F, 0x66, 0xF8, 0x64, 0x7E, 0xC0, 0x37, 0xD7, + 0x27, 0xC8, 0x72, 0x7E, 0xBC, 0xAD, 0xBD, 0xBF, 0x04, 0x5E, 0x45, 0x97, + 0x20, 0xFB, 0xB5, 0x0E, 0xD6, 0x75, 0xC4, 0xFE, 0xE8, 0xFA, 0xC1, 0x43, + 0x75, 0xFF, 0x7B, 0x9C, 0xE5, 0x04, 0xC9, 0x36, 0x5E, 0x4F, 0x0D, 0xAF, + 0xA2, 0xB8, 0xBD, 0x8D, 0x3A, 0x4E, 0x91, 0xB7, 0xFE, 0xFD, 0xBB, 0x46, + 0x1F, 0x70, 0xE9, 0x9F, 0x36, 0x1F, 0x16, 0x3D, 0xEE, 0x2B, 0x21, 0xFB, + 0xDC, 0xD8, 0x03, 0x6E, 0x9A, 0x22, 0x0F, 0xFF, 0xF7, 0x1F, 0xBB, 0xFD, + 0x3F, 0x9A, 0x0E, 0x88, 0xD4, 0x65, 0x51, 0x1C, 0x8B, 0xA2, 0xD8, 0x5C, + 0xB4, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0xBE, 0x8A, 0xB6, 0x69, 0xDA, 0x47, 0xD7, 0x01, 0xBE, 0xA2, 0xB6, + 0x3A, 0x66, 0x37, 0x87, 0xB2, 0x79, 0x74, 0x5D, 0xE0, 0x6B, 0x69, 0x8B, + 0x2C, 0x3B, 0x56, 0xF5, 0x55, 0xD5, 0xFD, 0xA5, 0x15, 0x81, 0x49, 0x99, + 0x65, 0xD5, 0xF4, 0xE9, 0x9C, 0x65, 0xA7, 0xC7, 0xD5, 0x05, 0xBE, 0x98, + 0x63, 0x56, 0xC6, 0x1B, 0xAA, 0xEC, 0xF8, 0x98, 0x9A, 0xC0, 0x97, 0x73, + 0xC8, 0xEA, 0x74, 0x53, 0x93, 0xE5, 0xFA, 0x58, 0x70, 0xE9, 0x5A, 0x8F, + 0x71, 0x40, 0x7E, 0xCE, 0xF3, 0x7B, 0xC3, 0xD1, 0xE6, 0x87, 0x47, 0xD5, + 0x07, 0xBE, 0x90, 0x32, 0x68, 0x3D, 0xBA, 0xF9, 0xAB, 0xA2, 0xFF, 0xB3, + 0x19, 0xFE, 0x80, 0x17, 0xD6, 0x04, 0x23, 0xF3, 0xFA, 0x36, 0xBF, 0x7B, + 0xFF, 0x70, 0x9E, 0xF7, 0xBA, 0xE0, 0xD5, 0x1C, 0xF3, 0xE9, 0xEF, 0xA6, + 0xCB, 0x8F, 0x71, 0x64, 0x7E, 0xD4, 0xC3, 0xE2, 0xD5, 0x7D, 0x44, 0xAD, + 0x44, 0x91, 0x05, 0xE3, 0xF2, 0x0F, 0x0D, 0x08, 0xAF, 0xAE, 0xC8, 0xA3, + 0x8F, 0x4D, 0x98, 0x12, 0x47, 0x23, 0x10, 0x5E, 0x5C, 0xBA, 0xF2, 0x11, + 0xAA, 0xB2, 0xFF, 0xBF, 0x7A, 0xC0, 0x17, 0xD4, 0x64, 0x1F, 0xD3, 0xDF, + 0x1F, 0x75, 0x5D, 0x55, 0x55, 0xB8, 0x53, 0x07, 0x8B, 0x97, 0x76, 0x9E, + 0x9A, 0x88, 0xA6, 0xBF, 0x3D, 0x31, 0x5C, 0x38, 0x0F, 0x6F, 0x3A, 0x81, + 0xD7, 0x53, 0x4E, 0xC3, 0x8F, 0x2A, 0xCF, 0xBB, 0xFC, 0x08, 0x53, 0xC2, + 0x00, 0x84, 0xD7, 0x76, 0x0A, 0x9B, 0x8B, 0x8F, 0x2E, 0x3F, 0xC2, 0xDB, + 0x4A, 0x0A, 0xF9, 0xC1, 0x4B, 0x2B, 0xC2, 0xFC, 0x28, 0xAF, 0xE9, 0x11, + 0x4D, 0x67, 0xC9, 0x0F, 0x5E, 0x5B, 0x19, 0xE6, 0xC3, 0x61, 0xBA, 0xBB, + 0xA4, 0xA7, 0x7F, 0xC5, 0x6B, 0x8B, 0xA6, 0x70, 0xBB, 0xF1, 0x47, 0x34, + 0x63, 0xB5, 0x35, 0xF9, 0x0B, 0xDF, 0x5F, 0x1D, 0x8C, 0x37, 0xEA, 0xB4, + 0x7B, 0x75, 0x31, 0xBF, 0xCB, 0x8B, 0x0B, 0xE6, 0xAB, 0x8A, 0xE0, 0xE6, + 0xC4, 0x9B, 0xDA, 0xFA, 0x20, 0x2F, 0xEE, 0x38, 0x0D, 0xD0, 0xBB, 0xEE, + 0x55, 0x79, 0x39, 0x4F, 0x0B, 0x86, 0x85, 0x87, 0x08, 0x79, 0x71, 0xE7, + 0xB1, 0x83, 0xD5, 0x76, 0xB3, 0xBB, 0xCD, 0x25, 0x9B, 0x1A, 0x0D, 0xCB, + 0x83, 0xBC, 0xBC, 0x71, 0xC6, 0xAA, 0x1F, 0x7E, 0x04, 0x8F, 0xA2, 0x9F, + 0x74, 0xAF, 0x78, 0x79, 0xE7, 0xE1, 0xE9, 0xDA, 0x6E, 0xF5, 0xE3, 0x50, + 0x4C, 0x23, 0xF4, 0x56, 0xF3, 0x01, 0x97, 0xC3, 0x3D, 0x23, 0xAA, 0xDB, + 0xED, 0x57, 0xF9, 0x6C, 0x3B, 0xBC, 0xB2, 0x76, 0xB8, 0x25, 0xB1, 0x1B, + 0x9F, 0x1F, 0xC6, 0xE9, 0xDE, 0x22, 0xF3, 0x1A, 0x45, 0xE8, 0x06, 0x1E, + 0x7D, 0x82, 0xB4, 0xA7, 0x62, 0x5A, 0xEF, 0x28, 0xAC, 0x7D, 0xC0, 0x4D, + 0x9D, 0xE5, 0x49, 0x5B, 0xD1, 0x1E, 0xA5, 0x07, 0xDC, 0x35, 0x79, 0xFC, + 0x42, 0xD1, 0x32, 0xD3, 0xB9, 0x82, 0xC9, 0x75, 0x70, 0x3E, 0x74, 0xAE, + 0xEA, 0x22, 0x73, 0xDF, 0x15, 0xC4, 0xCA, 0x6C, 0x54, 0x7A, 0xB5, 0x28, + 0xA4, 0xDA, 0xBA, 0x3A, 0x9D, 0xCA, 0x5A, 0xCF, 0x0A, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x57, 0xF4, 0x5F, 0xC3, 0x54, 0x94, + 0x5A +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h index 5704371131c6..6219f825dbe3 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h @@ -1,52 +1,32 @@ -/**************************************************************************** - * This program is free software: you can redistribute it and/or modify * - * it under the terms of the GNU General Public License as published by * - * the Free Software Foundation, either version 3 of the License, or * - * (at your option) any later version. * - * * - * This program is distributed in the hope that it will be useful, * - * but WITHOUT ANY WARRANTY; without even the implied warranty of * - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * - * GNU General Public License for more details. * - * * - * To view a copy of the GNU General Public License, go to the following * - * location: . * - ****************************************************************************/ - -/** - * This file was auto-generated using "svg2cpp.py" - * - * The encoding consists of x,y pairs with the min and max scaled to - * 0x0000 and 0xFFFE. A single 0xFFFF in the data stream indicates the - * start of a new closed path. - */ -#pragma once - -constexpr float x_min = 0.000000; -constexpr float x_max = 480.000000; -constexpr float y_min = 0.000000; -constexpr float y_max = 272.000000; - -const PROGMEM uint16_t menu_btn[] = {0x0AAA, 0x0E1E, 0x6D54, 0x0E1E, 0x6D54, 0x2F0E, 0x0AAA, 0x2F0E, 0x0AAA, 0x0E1E}; -const PROGMEM uint16_t print_btn[] = {0x47FF, 0xCF0D, 0x7FFF, 0xCF0D, 0x7FFF, 0xEFFE, 0x47FF, 0xEFFE, 0x47FF, 0xCF0D}; -const PROGMEM uint16_t load_chocolate_btn[] = {0x0AAA, 0x3878, 0x6D54, 0x3878, 0x6D54, 0x5968, 0x0AAA, 0x5968, 0x0AAA, 0x3878}; -const PROGMEM uint16_t extrude_btn[] = {0x0AAA, 0x5E1D, 0x6D54, 0x5E1D, 0x6D54, 0x7F0E, 0x0AAA, 0x7F0E, 0x0AAA, 0x5E1D}; -const PROGMEM uint16_t preheat_chocolate_btn[] = {0x0AAA, 0x83C2, 0x6D54, 0x83C2, 0x6D54, 0xA4B3, 0x0AAA, 0xA4B3, 0x0AAA, 0x83C2}; -const PROGMEM uint16_t media_btn[] = {0x0AAA, 0xCF0D, 0x42AA, 0xCF0D, 0x42AA, 0xEFFE, 0x0AAA, 0xEFFE, 0x0AAA, 0xCF0D}; -const PROGMEM uint16_t pause_btn[] = {0x8554, 0xCF0D, 0xBD53, 0xCF0D, 0xBD53, 0xEFFE, 0x8554, 0xEFFE, 0x8554, 0xCF0D}; -const PROGMEM uint16_t print_time_hms[] = {0xC59E, 0xAEA0, 0xF510, 0xAEA0, 0xF510, 0xC52D, 0xC59E, 0xC52D, 0xC59E, 0xAEA0}; -const PROGMEM uint16_t file_name[] = {0x0B0E, 0xAECD, 0xBCEF, 0xAECD, 0xBCEF, 0xC4AB, 0x0B0E, 0xC4AB, 0x0B0E, 0xAECD}; -const PROGMEM uint16_t chocolate_label[] = {0x75C1, 0x1369, 0xF4FE, 0x1369, 0xF4FE, 0x2AB1, 0x75C1, 0x2AB1, 0x75C1, 0x1369}; -const PROGMEM uint16_t h0_label[] = {0x8304, 0x4BEB, 0xB271, 0x4BEB, 0xB271, 0x63B0, 0x8304, 0x63B0, 0x8304, 0x4BEB}; -const PROGMEM uint16_t h0_temp[] = {0x8304, 0x7190, 0xB271, 0x7190, 0xB271, 0x8955, 0x8304, 0x8955, 0x8304, 0x7190}; -const PROGMEM uint16_t h1_label[] = {0xBB04, 0x4BEB, 0xEA71, 0x4BEB, 0xEA71, 0x63B0, 0xBB04, 0x63B0, 0xBB04, 0x4BEB}; -const PROGMEM uint16_t h1_temp[] = {0xBB04, 0x7190, 0xEA71, 0x7190, 0xEA71, 0x8956, 0xBB04, 0x8956, 0xBB04, 0x7190}; -const PROGMEM uint16_t stop_btn[] = {0xC2A9, 0xCF0D, 0xF553, 0xCF0D, 0xF553, 0xEFFE, 0xC2A9, 0xEFFE, 0xC2A9, 0xCF0D}; -const PROGMEM uint16_t load_screen_extrude[] = {0x382C, 0x8B02, 0x4188, 0x8B02, 0x4188, 0xAC4A, 0x4637, 0xAC4A, 0x3CDA, 0xBCEE, 0x337D, 0xAC4A, 0x382C, 0xAC4A, 0x382C, 0x8B02}; -const PROGMEM uint16_t load_screen_retract[] = {0x382C, 0x7A5D, 0x4188, 0x7A5D, 0x4188, 0x5915, 0x4637, 0x5915, 0x3CDA, 0x4871, 0x337E, 0x5915, 0x382C, 0x5915, 0x382C, 0x7A5D}; -const PROGMEM uint16_t load_screen_back_btn[] = {0x1555, 0xCA58, 0xEAA8, 0xCA58, 0xEAA8, 0xEFFE, 0x1555, 0xEFFE, 0x1555, 0xCA58}; -const PROGMEM uint16_t load_screen_unload_btn[] = {0x67FF, 0x70F0, 0xEAA8, 0x70F0, 0xEAA8, 0x9695, 0x67FF, 0x9695, 0x67FF, 0x70F0}; -const PROGMEM uint16_t load_screen_start_stop_btn[] = {0x67FF, 0x9B4A, 0xEAA8, 0x9B4A, 0xEAA8, 0xC0EF, 0x67FF, 0xC0EF, 0x67FF, 0x9B4A}; -const PROGMEM uint16_t load_screen_load_btn[] = {0x67FF, 0x4696, 0xEAA8, 0x4696, 0xEAA8, 0x6C3B, 0x67FF, 0x6C3B, 0x67FF, 0x4696}; -const PROGMEM uint16_t load_screen_continuous[] = {0x67FF, 0x1787, 0xEAA8, 0x1787, 0xEAA8, 0x3D2C, 0x67FF, 0x3D2C, 0x67FF, 0x1787}; -const PROGMEM uint16_t load_screen_increment[] = {0x1555, 0x1787, 0x62A9, 0x1787, 0x62A9, 0x3D2C, 0x1555, 0x3D2C, 0x1555, 0x1787}; +const PROGMEM uint16_t menu_btn[] = {0x0AAC, 0x0DF3, 0x6D54, 0x0DF3, 0x6D54, 0x2E89, 0x0AAC, 0x2E89, 0x0AAC, 0x0DF3}; +const PROGMEM uint16_t print_btn[] = {0x4800, 0xCCCC, 0x7FFF, 0xCCCC, 0x7FFF, 0xED62, 0x4800, 0xED62, 0x4800, 0xCCCC}; +const PROGMEM uint16_t load_chocolate_btn[] = {0x0AAC, 0x37D8, 0x6D54, 0x37D8, 0x6D54, 0x586E, 0x0AAC, 0x586E, 0x0AAC, 0x37D8}; +const PROGMEM uint16_t preheat_chocolate_btn[] = {0x0AAC, 0x5D15, 0x6D54, 0x5D15, 0x6D54, 0x7DAB, 0x0AAC, 0x7DAB, 0x0AAC, 0x5D15}; +const PROGMEM uint16_t extrude_btn[] = {0x0AAC, 0x8252, 0x6D54, 0x8252, 0x6D54, 0xA2E8, 0x0AAC, 0xA2E8, 0x0AAC, 0x8252}; +const PROGMEM uint16_t media_btn[] = {0x0AAC, 0xCCCC, 0x42AA, 0xCCCC, 0x42AA, 0xED62, 0x0AAC, 0xED62, 0x0AAC, 0xCCCC}; +const PROGMEM uint16_t pause_btn[] = {0x8554, 0xCCCC, 0xBD53, 0xCCCC, 0xBD53, 0xED62, 0x8554, 0xED62, 0x8554, 0xCCCC}; +const PROGMEM uint16_t print_time_hms[] = {0xAB02, 0x82EE, 0xE4F8, 0x82EE, 0xE4F8, 0xA24C, 0xAB02, 0xA24C, 0xAB02, 0x82EE}; +const PROGMEM uint16_t print_time_pct[] = {0x7386, 0x82E2, 0xA500, 0x82E2, 0xA500, 0xA258, 0x7386, 0xA258, 0x7386, 0x82E2}; +const PROGMEM uint16_t file_name[] = {0x0B08, 0xA830, 0xF4F5, 0xA830, 0xF4F5, 0xC784, 0x0B08, 0xC784, 0x0B08, 0xA830}; +const PROGMEM uint16_t h0_label[] = {0x85B6, 0x3884, 0xAF9B, 0x3884, 0xAF9B, 0x57C1, 0x85B6, 0x57C1, 0x85B6, 0x3884}; +const PROGMEM uint16_t h0_temp[] = {0x85B6, 0x5DC1, 0xAF9B, 0x5DC1, 0xAF9B, 0x7CFF, 0x85B6, 0x7CFF, 0x85B6, 0x5DC1}; +const PROGMEM uint16_t h1_label[] = {0xBB0B, 0x3884, 0xE4EF, 0x3884, 0xE4EF, 0x57C1, 0xBB0B, 0x57C1, 0xBB0B, 0x3884}; +const PROGMEM uint16_t h1_temp[] = {0xBB0B, 0x5DC1, 0xE4EF, 0x5DC1, 0xE4EF, 0x7CFF, 0xBB0B, 0x7CFF, 0xBB0B, 0x5DC1}; +const PROGMEM uint16_t stop_btn[] = {0xC2A8, 0xCCCC, 0xF551, 0xCCCC, 0xF551, 0xED62, 0xC2A8, 0xED62, 0xC2A8, 0xCCCC}; +const PROGMEM uint16_t z_wizard_heading[] = {0x5332, 0x0FFF, 0xB331, 0x0FFF, 0xB331, 0x2AAA, 0x5332, 0x2AAA, 0x5332, 0x0FFF}; +const PROGMEM uint16_t z_wizard_plus_btn[] = {0x9CCB, 0x3AAA, 0xAFFE, 0x3AAA, 0xAFFE, 0x5554, 0x9CCB, 0x5554, 0x9CCB, 0x3AAA}; +const PROGMEM uint16_t z_wizard_edit_box[] = {0x0CCC, 0x9FFE, 0x5332, 0x9FFE, 0x5332, 0xC553, 0x0CCC, 0xC553, 0x0CCC, 0x9FFE}; +const PROGMEM uint16_t z_wizard_inc1_btn[] = {0x5998, 0xA016, 0x8998, 0xA016, 0x8998, 0xC553, 0x5998, 0xC553, 0x5998, 0xA016}; +const PROGMEM uint16_t z_wizard_inc2_btn[] = {0x8FFE, 0xA016, 0xBFFE, 0xA016, 0xBFFE, 0xC553, 0x8FFE, 0xC553, 0x8FFE, 0xA016}; +const PROGMEM uint16_t z_wizard_inc3_btn[] = {0xC664, 0xA016, 0xF664, 0xA016, 0xF664, 0xC553, 0xC664, 0xC553, 0xC664, 0xA016}; +const PROGMEM uint16_t z_wizard_done_btn[] = {0xBFFE, 0xCFFE, 0xF664, 0xCFFE, 0xF664, 0xF553, 0xBFFE, 0xF553, 0xBFFE, 0xCFFE}; +const PROGMEM uint16_t z_wizard_neg_btn[] = {0x9CCB, 0x5FFF, 0xAFFE, 0x5FFF, 0xAFFE, 0x7AA9, 0x9CCB, 0x7AA9, 0x9CCB, 0x5FFF}; +const PROGMEM uint16_t z_wizard_diagram[] = {0x6D65, 0x4DBE, 0x6D65, 0x6015, 0x7ADB, 0x6015, 0x7F1F, 0x6C6A, 0x8303, 0x6C6A, 0x8747, 0x6015, 0x94BE, 0x6015, 0x94BE, 0x4DBE, 0x6D65, 0x4DBE, 0xFFFF, 0x0D06, 0x8527, 0x0D06, 0x9554, 0xF664, 0x9554, 0xF664, 0x8527, 0x0D06, 0x8527}; +const PROGMEM uint16_t load_screen_extrude[] = {0x382D, 0x897E, 0x4189, 0x897E, 0x4189, 0xAA6A, 0x4638, 0xAA6A, 0x3CDB, 0xBAE0, 0x337F, 0xAA6A, 0x382D, 0xAA6A, 0x382D, 0x897E}; +const PROGMEM uint16_t load_screen_retract[] = {0x382D, 0x7908, 0x4189, 0x7908, 0x4189, 0x581C, 0x4638, 0x581C, 0x3CDB, 0x47A6, 0x337F, 0x581C, 0x382D, 0x581C, 0x382D, 0x7908}; +const PROGMEM uint16_t load_screen_back_btn[] = {0x1556, 0xC825, 0xEAA7, 0xC825, 0xEAA7, 0xED62, 0x1556, 0xED62, 0x1556, 0xC825}; +const PROGMEM uint16_t load_screen_unload_btn[] = {0x67FF, 0x6FB4, 0xEAA7, 0x6FB4, 0xEAA7, 0x94F1, 0x67FF, 0x94F1, 0x67FF, 0x6FB4}; +const PROGMEM uint16_t load_screen_start_stop_btn[] = {0x67FF, 0x9998, 0xEAA7, 0x9998, 0xEAA7, 0xBED6, 0x67FF, 0xBED6, 0x67FF, 0x9998}; +const PROGMEM uint16_t load_screen_load_btn[] = {0x67FF, 0x45CF, 0xEAA7, 0x45CF, 0xEAA7, 0x6B0C, 0x67FF, 0x6B0C, 0x67FF, 0x45CF}; +const PROGMEM uint16_t load_screen_continuous[] = {0x67FF, 0x1743, 0xEAA7, 0x1743, 0xEAA7, 0x3C80, 0x67FF, 0x3C80, 0x67FF, 0x1743}; +const PROGMEM uint16_t load_screen_increment[] = {0x1556, 0x1743, 0x62AA, 0x1743, 0x62AA, 0x3C80, 0x1556, 0x3C80, 0x1556, 0x1743}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/files_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/files_screen.cpp index 581c3374288b..f7c7035761fd 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/files_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/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(); @@ -171,13 +171,10 @@ void FilesScreen::drawFooter() { cmd.colors(normal_btn) .font(font_medium) .colors(normal_btn) - .enabled(!mydata.flags.is_root) - .tag(245).button(BTN2_POS, F("Up Dir")) + .tag(mydata.flags.is_root ? 240 : 245).button(BTN2_POS, F("Back")) .colors(action_btn); - if (mydata.flags.is_empty) - cmd.tag(240).button(BTN1_POS, GET_TEXT_F(MSG_BUTTON_DONE)); - else if (has_selection && mydata.flags.is_dir) + if (has_selection && mydata.flags.is_dir) cmd.tag(244).button(BTN1_POS, GET_TEXT_F(MSG_BUTTON_OPEN)); else cmd.tag(241).enabled(has_selection).button(BTN1_POS, F("Select")); @@ -214,12 +211,9 @@ void FilesScreen::gotoPage(uint8_t page) { bool FilesScreen::onTouchEnd(uint8_t tag) { switch (tag) { - case 240: // Done button, always select first file - { - FileList files; - files.seek(0); - GOTO_PREVIOUS(); - } + case 240: // Back button + card.filename[0] = card.longFilename[0] = '\0'; // Clear file selection + GOTO_PREVIOUS(); return true; case 241: // Select highlighted file GOTO_PREVIOUS(); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp index be18c0348388..820594acaba8 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp @@ -25,24 +25,31 @@ #if ENABLED(COCOA_LEVELING_MENU) -#if BOTH(HAS_BED_PROBE, BLTOUCH) - #include "../../../../feature/bltouch.h" -#endif - using namespace FTDI; using namespace ExtUI; using namespace Theme; -#define GRID_COLS 3 -#define GRID_ROWS 5 -#define BED_MESH_TITLE_POS BTN_POS(1,1), BTN_SIZE(3,1) -#define PROBE_BED_POS BTN_POS(1,2), BTN_SIZE(1,1) -#define SHOW_MESH_POS BTN_POS(2,2), BTN_SIZE(1,1) -#define EDIT_MESH_POS BTN_POS(3,2), BTN_SIZE(1,1) -#define BLTOUCH_TITLE_POS BTN_POS(1,3), BTN_SIZE(3,1) -#define BLTOUCH_RESET_POS BTN_POS(1,4), BTN_SIZE(1,1) -#define BLTOUCH_TEST_POS BTN_POS(2,4), BTN_SIZE(1,1) -#define BACK_POS BTN_POS(1,5), BTN_SIZE(3,1) +#if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) + #define GRID_COLS 3 + #define GRID_ROWS 6 + #define BED_MESH_TITLE_POS BTN_POS(1,1), BTN_SIZE(3,1) + #define WARNING_POS BTN_POS(1,2), BTN_SIZE(3,2) + #define PROBE_BED_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define SHOW_MESH_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define EDIT_MESH_POS BTN_POS(3,4), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,6), BTN_SIZE(3,1) +#else + #define GRID_COLS 2 + #define GRID_ROWS 6 + #define BED_MESH_TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define WARNING_POS BTN_POS(1,2), BTN_SIZE(2,2) + #define PROBE_BED_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define SHOW_MESH_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,6), BTN_SIZE(2,1) + + // Hide the editor button if motion to grid point not supported + #define EDIT_MESH_POS BTN_POS(4,7), BTN_SIZE(1,1) +#endif void LevelingMenu::onRedraw(draw_mode_t what) { if (what & BACKGROUND) { @@ -57,38 +64,26 @@ void LevelingMenu::onRedraw(draw_mode_t what) { cmd.font(font_large) .cmd(COLOR_RGB(bg_text_enabled)) .text(BED_MESH_TITLE_POS, GET_TEXT_F(MSG_BED_LEVELING)) - #if ENABLED(BLTOUCH) - .text(BLTOUCH_TITLE_POS, GET_TEXT_F(MSG_BLTOUCH)) - #endif .font(font_medium).colors(normal_btn) .tag(2).button(PROBE_BED_POS, GET_TEXT_F(MSG_PROBE_BED)) .enabled(ENABLED(HAS_MESH)) .tag(3).button(SHOW_MESH_POS, GET_TEXT_F(MSG_MESH_VIEW)) .enabled(ENABLED(HAS_MESH)) .tag(4).button(EDIT_MESH_POS, GET_TEXT_F(MSG_EDIT_MESH)) - #undef GRID_COLS - #define GRID_COLS 2 - #if ENABLED(BLTOUCH) - .tag(5).button(BLTOUCH_RESET_POS, GET_TEXT_F(MSG_BLTOUCH_RESET)) - .tag(6).button(BLTOUCH_TEST_POS, GET_TEXT_F(MSG_BLTOUCH_SELFTEST)) - #endif - #undef GRID_COLS - #define GRID_COLS 3 .colors(action_btn) - .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)) + .cmd(COLOR_RGB(bg_text_enabled)) + .tag(0); + draw_text_box(cmd, WARNING_POS, F("Remove chocolate cartridge before probing. This reduces the possibility of damaging a part."), OPT_CENTER, font_medium); } } bool LevelingMenu::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); break; - case 2: BedMeshViewScreen::doProbe(); break; + case 2: SaveSettingsDialogBox::settingsChanged(); injectCommands(F(BED_LEVELING_COMMANDS)); break; case 3: BedMeshViewScreen::show(); break; - case 4: BedMeshEditScreen::show(); break; - #if ENABLED(BLTOUCH) - case 5: injectCommands(F("M280 P0 S60")); break; - case 6: SpinnerDialogBox::enqueueAndWait(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; - #endif + case 4: SaveSettingsDialogBox::settingsChanged(); BedMeshEditScreen::show(); break; default: return false; } return true; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp index 95ddf7d387f7..c7870eeaf8c4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp @@ -54,11 +54,10 @@ void LoadChocolateScreen::draw_buttons(draw_mode_t what) { cmd.tag(3).colors(mydata.repeat_tag == 6 ? action_btn : normal_btn).button(x, y, h, v, GET_TEXT_F(MSG_LOAD)); ui.bounds(POLY(load_screen_start_stop_btn), x, y, h, v); - if(mydata.repeat_tag == 0) { - cmd.colors(normal_btn).enabled(false); - } else { - cmd.colors(mydata.repeating ? action_btn : normal_btn).enabled(true); - } + if (mydata.repeat_tag == 0) + cmd.colors(normal_btn).enabled(false); + else + cmd.colors(mydata.repeating ? action_btn : normal_btn).enabled(true); cmd.tag(4).button(x, y, h, v, GET_TEXT_F(MSG_START_STOP)); ui.bounds(POLY(load_screen_back_btn), x, y, h, v); @@ -115,24 +114,16 @@ void LoadChocolateScreen::onRedraw(draw_mode_t what) { } bool LoadChocolateScreen::onTouchStart(uint8_t tag) { - if(tag != 4) { - mydata.repeating = false; - } + if (tag != 4) mydata.repeating = false; return true; } bool LoadChocolateScreen::onTouchEnd(uint8_t tag) { using namespace ExtUI; switch (tag) { - case 2: - mydata.repeat_tag = 5; - break; - case 3: - mydata.repeat_tag = 6; - break; - case 4: - mydata.repeating = !mydata.repeating; - break; + case 2: mydata.repeat_tag = 5; break; + case 3: mydata.repeat_tag = 6; break; + case 4: mydata.repeating = !mydata.repeating; break; case 1: GOTO_PREVIOUS(); break; } return true; @@ -153,12 +144,8 @@ bool LoadChocolateScreen::onTouchHeld(uint8_t tag) { #define UI_INCREMENT_AXIS(axis) UI_INCREMENT(AxisPosition_mm, axis); #define UI_DECREMENT_AXIS(axis) UI_DECREMENT(AxisPosition_mm, axis); switch (tag) { - case 5: - UI_INCREMENT_AXIS(E0); - break; - case 6: - UI_DECREMENT_AXIS(E0); - break; + case 5: UI_INCREMENT_AXIS(E0); break; + case 6: UI_DECREMENT_AXIS(E0); break; default: return false; } #undef UI_DECREMENT_AXIS @@ -170,10 +157,10 @@ void LoadChocolateScreen::onIdle() { reset_menu_timeout(); if (mydata.repeating) onTouchHeld(mydata.repeat_tag); if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { - if (!EventLoop::is_touch_held()) - onRefresh(); + if (!EventLoop::is_touch_held()) onRefresh(); refresh_timer.start(); } BaseScreen::onIdle(); } + #endif // COCOA_LOAD_CHOCOLATE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp index ee299a7f64d6..14dc8c533fa7 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp @@ -23,6 +23,7 @@ #include "../config.h" #include "../screens.h" +#include "../../../../module/stepper.h" #ifdef COCOA_MAIN_MENU @@ -34,13 +35,13 @@ using namespace Theme; #define ZPROBE_ZOFFSET_POS BTN_POS(1,1), BTN_SIZE(1,1) #define MOVE_XYZ_POS BTN_POS(1,2), BTN_SIZE(1,1) -#define TEMPERATURE_POS BTN_POS(2,1), BTN_SIZE(1,1) +#define LEVELING_POS BTN_POS(2,1), BTN_SIZE(1,1) #define MOVE_E_POS BTN_POS(2,2), BTN_SIZE(1,1) #define SPEED_POS BTN_POS(1,3), BTN_SIZE(1,1) #define FLOW_POS BTN_POS(2,3), BTN_SIZE(1,1) -#define ADVANCED_SETTINGS_POS BTN_POS(1,4), BTN_SIZE(1,1) +#define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(1,1) #define DISABLE_STEPPERS_POS BTN_POS(2,4), BTN_SIZE(1,1) -#define LEVELING_POS BTN_POS(1,5), BTN_SIZE(1,1) +#define ADVANCED_SETTINGS_POS BTN_POS(1,5), BTN_SIZE(1,1) #define ABOUT_PRINTER_POS BTN_POS(2,5), BTN_SIZE(1,1) #define BACK_POS BTN_POS(1,6), BTN_SIZE(2,1) @@ -57,12 +58,16 @@ void MainMenu::onRedraw(draw_mode_t what) { .font(Theme::font_medium) .tag( 2).button(MOVE_XYZ_POS, GET_TEXT_F(MSG_XYZ_MOVE)) .tag( 3).button(TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE)) - .enabled(BOTH(HAS_LEVELING, HAS_BED_PROBE)) + .enabled(ALL(HAS_LEVELING, HAS_BED_PROBE)) .tag( 4).button(ZPROBE_ZOFFSET_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) .tag( 5).button(MOVE_E_POS, GET_TEXT_F(MSG_E_MOVE)) .tag( 6).button(SPEED_POS, GET_TEXT_F(MSG_PRINT_SPEED)) .tag( 7).button(FLOW_POS, GET_TEXT_F(MSG_FLOW)) .tag( 8).button(ADVANCED_SETTINGS_POS, GET_TEXT_F(MSG_ADVANCED_SETTINGS)) + .enabled(stepper.axis_is_enabled(X_AXIS) || + stepper.axis_is_enabled(Y_AXIS) || + stepper.axis_is_enabled(Z_AXIS) || + stepper.axis_is_enabled(E0_AXIS)) .tag( 9).button(DISABLE_STEPPERS_POS, GET_TEXT_F(MSG_DISABLE_STEPPERS)) .enabled(ENABLED(HAS_LEVELING)) .tag(10).button(LEVELING_POS, GET_TEXT_F(MSG_LEVELING)) @@ -79,7 +84,7 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; case 2: GOTO_SCREEN(MoveXYZScreen); break; case 3: GOTO_SCREEN(TemperatureScreen); break; - #if BOTH(HAS_LEVELING, HAS_BED_PROBE) + #if ALL(HAS_LEVELING, HAS_BED_PROBE) case 4: GOTO_SCREEN(ZOffsetScreen); break; #endif case 5: GOTO_SCREEN(MoveEScreen); break; @@ -97,4 +102,12 @@ bool MainMenu::onTouchEnd(uint8_t tag) { return true; } +void MainMenu::onIdle() { + if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { + if (!EventLoop::is_touch_held()) + onRefresh(); + refresh_timer.start(); + } +} + #endif // COCOA_MAIN_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.h index 460bb4b81a70..85dcbd07e6a5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.h @@ -30,4 +30,5 @@ class MainMenu : public BaseScreen, public CachedScreen { public: static void onRedraw(draw_mode_t); static bool onTouchEnd(uint8_t tag); + static void onIdle(); }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp index 2fabb81ee4db..ff11b6e0d9a8 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp @@ -32,40 +32,24 @@ using namespace Theme; #define GRID_ROWS 5 void PreheatMenu::onRedraw(draw_mode_t what) { - const int16_t w = TERN0(COCOA_PRESS_EXTRA_HEATER, has_extra_heater()) ? BTN_W(1) : BTN_W(2); - const int16_t h = BTN_H(1); - if (what & BACKGROUND) { CommandProcessor cmd; cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) .cmd(CLEAR(true,true,true)) - .tag(0) .cmd(COLOR_RGB(bg_text_enabled)) .font(Theme::font_medium) - .text( BTN_POS(1,1), w, h, GET_TEXT_F(MSG_SELECT_CHOCOLATE_TYPE)); - #if ENABLED(COCOA_PRESS_EXTRA_HEATER) - if (has_extra_heater()) { - cmd.text( BTN_POS(2,1), w, h, GET_TEXT_F(MSG_EXTERNAL)); - } - #endif + .tag(0).text( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_SELECT_CHOCOLATE_TYPE)); } if (what & FOREGROUND) { CommandProcessor cmd; cmd.font(Theme::font_medium) .colors(normal_btn) - .tag(2).button(BTN_POS(1,2), w, h, F("Dark Chocolate")) - .tag(3).button(BTN_POS(1,3), w, h, F("Milk Chocolate")) - .tag(4).button(BTN_POS(1,4), w, h, F("White Chocolate")); - #if ENABLED(COCOA_PRESS_EXTRA_HEATER) - if (has_extra_heater()) { - cmd.tag(5).button(BTN_POS(2,2), w, h, F("Dark Chocolate")) - .tag(6).button(BTN_POS(2,3), w, h, F("Milk Chocolate")) - .tag(7).button(BTN_POS(2,4), w, h, F("White Chocolate")); - } - #endif - cmd.colors(action_btn) - .tag(1) .button(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_DONE)); + .tag(2).button(BTN_POS(1,2), BTN_SIZE(2,1), F("Dark Chocolate")) + .tag(3).button(BTN_POS(1,3), BTN_SIZE(2,1), F("Milk Chocolate")) + .tag(4).button(BTN_POS(1,4), BTN_SIZE(2,1), F("White Chocolate")) + .colors(action_btn) + .tag(1).button(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_DONE)); } } @@ -73,38 +57,20 @@ bool PreheatMenu::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); break; case 2: - #ifdef COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_INT_SCRIPT - injectCommands(F(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_INT_SCRIPT)); + #ifdef COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_SCRIPT + injectCommands(F(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_SCRIPT)); #endif GOTO_SCREEN(PreheatTimerScreen); break; case 3: - #ifdef COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_INT_SCRIPT - injectCommands(F(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_INT_SCRIPT)); + #ifdef COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_SCRIPT + injectCommands(F(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_SCRIPT)); #endif GOTO_SCREEN(PreheatTimerScreen); break; case 4: - #ifdef COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_INT_SCRIPT - injectCommands(F(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_INT_SCRIPT)); - #endif - GOTO_SCREEN(PreheatTimerScreen); - break; - case 5: - #ifdef COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_EXT_SCRIPT - injectCommands(F(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_EXT_SCRIPT)); - #endif - GOTO_SCREEN(PreheatTimerScreen); - break; - case 6: - #ifdef COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_EXT_SCRIPT - injectCommands(F(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_EXT_SCRIPT)); - #endif - GOTO_SCREEN(PreheatTimerScreen); - break; - case 7: - #ifdef COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_EXT_SCRIPT - injectCommands(F(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_EXT_SCRIPT)); + #ifdef COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_SCRIPT + injectCommands(F(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_SCRIPT)); #endif GOTO_SCREEN(PreheatTimerScreen); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp index c4e9d971f6a7..9641b1f9c6a4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp @@ -89,20 +89,20 @@ void PreheatTimerScreen::draw_adjuster(draw_mode_t what, uint8_t tag, FSTR_P lab cmd.tag(0) .font(font_small); if (what & BACKGROUND) { - cmd.text( SUB_POS(1,1), SUB_SIZE(9,1), label) - .button(SUB_POS(1,2), SUB_SIZE(5,1), F(""), OPT_FLAT); + cmd.text( SUB_POS(1,1), SUB_SIZE(9,1), label) + .button(SUB_POS(1,2), SUB_SIZE(5,1), F(""), OPT_FLAT); } if (what & FOREGROUND) { - char str[32]; - dtostrf(value, 5, 1, str); - strcat_P(str, PSTR(" ")); - strcat_P(str, (const char*) GET_TEXT_F(MSG_UNITS_C)); - - cmd.text(SUB_POS(1,2), SUB_SIZE(5,1), str) - .font(font_medium) - .tag(tag ).button(SUB_POS(6,2), SUB_SIZE(2,1), F("-")) - .tag(tag+1).button(SUB_POS(8,2), SUB_SIZE(2,1), F("+")); + char str[32]; + dtostrf(value, 5, 1, str); + strcat_P(str, PSTR(" ")); + strcat_P(str, (const char*) GET_TEXT_F(MSG_UNITS_C)); + + cmd.text(SUB_POS(1,2), SUB_SIZE(5,1), str) + .font(font_medium) + .tag(tag ).button(SUB_POS(6,2), SUB_SIZE(2,1), F("-")) + .tag(tag+1).button(SUB_POS(8,2), SUB_SIZE(2,1), F("+")); } } @@ -116,7 +116,9 @@ void PreheatTimerScreen::onRedraw(draw_mode_t what) { draw_interaction_buttons(what); draw_adjuster(what, 2, GET_TEXT_F(MSG_NOZZLE), getTargetTemp_celsius(E0), NOZZLE_ADJ_POS); draw_adjuster(what, 4, GET_TEXT_F(MSG_BODY), getTargetTemp_celsius(E1), BODY_ADJ_POS); - draw_adjuster(what, 6, GET_TEXT_F(MSG_CHAMBER), getTargetTemp_celsius(CHAMBER), CHAMBER_ADJ_POS); + #if HAS_HEATED_CHAMBER + draw_adjuster(what, 6, GET_TEXT_F(MSG_CHAMBER), getTargetTemp_celsius(CHAMBER), CHAMBER_ADJ_POS); + #endif } bool PreheatTimerScreen::onTouchHeld(uint8_t tag) { @@ -126,8 +128,10 @@ bool PreheatTimerScreen::onTouchHeld(uint8_t tag) { case 3: UI_INCREMENT(TargetTemp_celsius, E0); break; case 4: UI_DECREMENT(TargetTemp_celsius, E1); break; case 5: UI_INCREMENT(TargetTemp_celsius, E1); break; - case 6: UI_DECREMENT(TargetTemp_celsius, CHAMBER); break; - case 7: UI_INCREMENT(TargetTemp_celsius, CHAMBER); break; + #if HAS_HEATED_CHAMBER + case 6: UI_DECREMENT(TargetTemp_celsius, CHAMBER); break; + case 7: UI_INCREMENT(TargetTemp_celsius, CHAMBER); break; + #endif default: return false; } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h index 5276f64f4429..162c32b9562b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h @@ -22,7 +22,6 @@ #pragma once - /********************************* DL CACHE SLOTS ******************************/ // In order to reduce SPI traffic, we cache display lists (DL) in RAMG. This @@ -84,7 +83,6 @@ enum { #include "../generic/base_numeric_adjustment_screen.h" #include "../generic/dialog_box_base_class.h" #include "../generic/boot_screen.h" -#include "../generic/about_screen.h" #include "../generic/kill_screen.h" #include "../generic/alert_dialog_box.h" #include "../generic/spinner_dialog_box.h" @@ -105,13 +103,10 @@ enum { #include "../generic/lock_screen.h" #include "../generic/endstop_state_screen.h" #include "../generic/display_tuning_screen.h" -#include "../generic/statistics_screen.h" #include "../generic/stepper_current_screen.h" -#include "../generic/z_offset_screen.h" #include "../generic/bed_mesh_base.h" #include "../generic/bed_mesh_view_screen.h" #include "../generic/bed_mesh_edit_screen.h" -#include "../generic/case_light_screen.h" #include "../generic/linear_advance_screen.h" #include "../generic/move_axis_screen.h" #include "../generic/flow_percent_screen.h" @@ -132,3 +127,7 @@ enum { #include "move_e_screen.h" #include "files_screen.h" #include "confirm_start_print_dialog_box.h" +#include "z_offset_screen.h" +#include "z_offset_wizard.h" +#include "about_screen.h" +#include "statistics_screen.h" diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/statistics_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/statistics_screen.cpp new file mode 100644 index 000000000000..df29ac4d2309 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/statistics_screen.cpp @@ -0,0 +1,82 @@ +/************************* + * statistics_screen.cpp * + *************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" + +#ifdef COCOA_STATISTICS_SCREEN + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +#define GRID_COLS 4 +#define GRID_ROWS 7 + +void StatisticsScreen::onRedraw(draw_mode_t what) { + CommandProcessor cmd; + + if (what & BACKGROUND) { + char buffer[21]; + + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)) + .cmd(COLOR_RGB(bg_text_enabled)) + .tag(0) + + .font(Theme::font_medium) + .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INFO_STATS_MENU)) + .font(Theme::font_small) + .tag(0) + .text(BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_PRINT_COUNT), OPT_RIGHTX | OPT_CENTERY) + .text(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_COMPLETED_PRINTS), OPT_RIGHTX | OPT_CENTERY) + .text(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_PRINT_TIME), OPT_RIGHTX | OPT_CENTERY) + .text(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_PRINT_LONGEST), OPT_RIGHTX | OPT_CENTERY) + .text(BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_PRINT_FILAMENT), OPT_RIGHTX | OPT_CENTERY); + // Don't chain the following, it causes strange issues with evaluation ordering! + cmd.text(BTN_POS(3,2), BTN_SIZE(2,1), getTotalPrints_str(buffer)); + cmd.text(BTN_POS(3,3), BTN_SIZE(2,1), getFinishedPrints_str(buffer)); + cmd.text(BTN_POS(3,4), BTN_SIZE(2,1), getTotalPrintTime_str(buffer)); + cmd.text(BTN_POS(3,5), BTN_SIZE(2,1), getLongestPrint_str(buffer)); + + // Express in grams of chocolate rather than mm + const printStatistics stats = print_job_timer.getStats(); + const long gramsChocolate = stats.filamentUsed * 0.53; // 1mm of extrusion is 0.53g + sprintf_P(buffer, PSTR("%ldg"), gramsChocolate); + cmd.text(BTN_POS(3,6), BTN_SIZE(2,1), buffer); + } + + if (what & FOREGROUND) { + cmd.font(Theme::font_medium) + .colors(action_btn) + .tag(1).button(BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BUTTON_DONE)); + } +} + +bool StatisticsScreen::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); return true; + default: return false; + } +} + +#endif // COCOA_STATISTICS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/statistics_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/statistics_screen.h new file mode 100644 index 000000000000..9e533570318d --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/statistics_screen.h @@ -0,0 +1,32 @@ +/*********************** + * statistics_screen.h * + ***********************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_STATISTICS_SCREEN +#define COCOA_STATISTICS_SCREEN_CLASS StatisticsScreen + +class StatisticsScreen : public BaseScreen, public UncachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp index eddf36723977..421d90bf7ffa 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp @@ -23,22 +23,30 @@ #include "../config.h" #include "../screens.h" +#include "../screen_data.h" #ifdef COCOA_STATUS_SCREEN #include "cocoa_press_ui.h" +#include "cocoa_press_bitmap.h" #define POLY(A) PolyUI::poly_reader_t(A, sizeof(A)/sizeof(A[0])) #define ICON_POS(x,y,w,h) x, y, h, h #define TEXT_POS(x,y,w,h) x + h, y, w - h, h -const uint8_t shadow_depth = 5; - using namespace FTDI; using namespace Theme; using namespace ExtUI; -float StatusScreen::increment; +const uint8_t shadow_depth = 5; + +constexpr static StatusScreenData &mydata = screen_data.StatusScreen; + +// Format for background image + +constexpr uint8_t format = RGB332; +constexpr uint16_t bitmap_w = 800; +constexpr uint16_t bitmap_h = 480; void StatusScreen::_format_time(char *outstr, uint32_t time) { const uint8_t hrs = time / 3600, @@ -69,6 +77,64 @@ void StatusScreen::loadBitmaps() { #endif } +void StatusScreen::draw_bkgnd(draw_mode_t what) { + if (what & BACKGROUND) { + constexpr float scale_w = float(FTDI::display_width)/bitmap_w; + constexpr float scale_h = float(FTDI::display_height)/bitmap_h; + uint16_t linestride; + uint32_t color; + switch (format) { + case RGB565: linestride = bitmap_w * 2; color = 0xFFFFFF; break; + case RGB332: linestride = bitmap_w ; color = 0xFFFFFF; break; + case L1: linestride = bitmap_w/8 ; color = 0x000000; break; + case L2: linestride = bitmap_w/4 ; color = 0x000000; break; + case L4: linestride = bitmap_w/2 ; color = 0x000000; break; + case L8: linestride = bitmap_w ; color = 0x000000; break; + } + CommandProcessor cmd; + cmd.cmd(COLOR_RGB(color)) + .cmd(BITMAP_SOURCE(BACKGROUND_OFFSET)) + .tag(0) + .bitmap_layout(format, linestride, bitmap_h) + .bitmap_size(NEAREST, BORDER, BORDER, bitmap_w*scale_w, bitmap_h*scale_h) + .cmd(BITMAP_TRANSFORM_A(uint32_t(float(256)/scale_w))) + .cmd(BITMAP_TRANSFORM_E(uint32_t(float(256)/scale_h))) + .cmd(BEGIN(BITMAPS)) + .cmd(VERTEX2II(0, 0, 0, 0)) + .cmd(BITMAP_TRANSFORM_A(256)) + .cmd(BITMAP_TRANSFORM_E(256)) + .cmd(COLOR_RGB(bg_text_enabled)); + } +} + +void StatusScreen::send_buffer(CommandProcessor &cmd, const void *data, uint16_t len) { + const char *ptr = (const char*) data; + constexpr uint16_t block_size = 512; + char block[block_size]; + for (;len > 0;) { + const uint16_t nBytes = min(len, block_size); + memcpy_P(block, ptr, nBytes); + cmd.write((const void*)block, nBytes); + cmd.execute(); + if(cmd.has_fault()) { + SERIAL_ECHOLNPGM("Recovering from fault: "); + cmd.reset(); + delay(1000); + return; + } + ptr += nBytes; + len -= nBytes; + } +} + +void StatusScreen::load_background(const void *data, uint16_t len) { + CommandProcessor cmd; + cmd.inflate(BACKGROUND_OFFSET) + .execute(); + send_buffer(cmd, data, len); + cmd.wait(); +} + void StatusScreen::draw_time(draw_mode_t what) { CommandProcessor cmd; PolyUI ui(cmd, what); @@ -96,23 +162,27 @@ void StatusScreen::draw_time(draw_mode_t what) { } } - -void StatusScreen::draw_progress(draw_mode_t what) { +void StatusScreen::draw_percent(draw_mode_t what) { CommandProcessor cmd; PolyUI ui(cmd, what); int16_t x, y, w, h; - - cmd.cmd(COLOR_RGB(accent_color_1)); - cmd.font(font_medium); + ui.bounds(POLY(print_time_pct), x, y, w, h); if (what & FOREGROUND) { - // Draw progress bar - ui.bounds(POLY(file_name), x, y, w, h); - const uint16_t bar_width = w * getProgress_percent() / 100; - cmd.tag(8) - .cmd(COLOR_RGB(accent_color_5)) - .rectangle(x, y, bar_width, h); + const uint16_t current_progress = TERN(HAS_PRINT_PROGRESS_PERMYRIAD, getProgress_permyriad(), getProgress_percent() * 100); + char progress_str[10]; + sprintf_P(progress_str, + #if ENABLED(PRINT_PROGRESS_SHOW_DECIMALS) + PSTR("%3d.%02d%%"), uint8_t(current_progress / 100), current_progress % 100 + #else + PSTR("%3d%%"), uint8_t(current_progress / 100) + #endif + ); + + cmd.font(font_medium) + .cmd(COLOR_RGB(bg_text_enabled)) + .text(TEXT_POS(x, y, w, h), progress_str); } } @@ -123,17 +193,8 @@ void StatusScreen::draw_temperature(draw_mode_t what) { int16_t x, y, w, h; if (what & BACKGROUND) { - cmd.cmd(COLOR_RGB(fluid_rgb)); - cmd.font(font_medium).tag(10); - - /*ui.bounds(POLY(temp_lbl), x, y, w, h); - cmd.text(x, y, w, h, F("Temp")); - - ui.bounds(POLY(set_lbl), x, y, w, h); - cmd.text(x, y, w, h, F("Set"));*/ - - ui.bounds(POLY(chocolate_label), x, y, w, h); - cmd.text(x, y, w, h, F("Cocoa Press")); + cmd.cmd(COLOR_RGB(bg_text_enabled)); + cmd.font(font_medium).tag(0); ui.bounds(POLY(h0_label), x, y, w, h); cmd.text(x, y, w, h, GET_TEXT_F(MSG_NOZZLE)); @@ -141,18 +202,6 @@ void StatusScreen::draw_temperature(draw_mode_t what) { ui.bounds(POLY(h1_label), x, y, w, h); cmd.text(x, y, w, h, GET_TEXT_F(MSG_BODY)); - #if ENABLED(COCOA_PRESS_EXTRA_HEATER) - if (has_extra_heater()) { - ui.bounds(POLY(h2_label), x, y, w, h); - cmd.text(x, y, w, h, GET_TEXT_F(MSG_EXTERNAL)); - } - #endif - - #if ENABLED(COCOA_PRESS_CHAMBER_COOLER) - ui.bounds(POLY(h3_label), x, y, w, h); - cmd.text(x, y, w, h, GET_TEXT_F(MSG_CHAMBER)); - #endif - #if ENABLED(TOUCH_UI_USE_UTF8) load_utf8_bitmaps(cmd); // Restore font bitmap handles #endif @@ -160,154 +209,125 @@ void StatusScreen::draw_temperature(draw_mode_t what) { if (what & FOREGROUND) { char str[15]; - cmd.cmd(COLOR_RGB(fluid_rgb)); - - cmd.font(font_large).tag(10); + cmd.font(font_medium).colors(normal_btn).tag(10); // Show the actual temperatures format_temp(str, getActualTemp_celsius(E0)); ui.bounds(POLY(h0_temp), x, y, w, h); - cmd.text(x, y, w, h, str); + cmd.button(x, y, w, h, str); format_temp(str, getActualTemp_celsius(E1)); ui.bounds(POLY(h1_temp), x, y, w, h); - cmd.text(x, y, w, h, str); - - #if ENABLED(COCOA_PRESS_EXTRA_HEATER) - if (has_extra_heater()) { - format_temp(str, getActualTemp_celsius(E2)); - ui.bounds(POLY(h2_temp), x, y, w, h); - cmd.text(x, y, w, h, str); - } - #endif - - #if ENABLED(COCOA_PRESS_CHAMBER_COOLER) - format_temp(str, getActualTemp_celsius(CHAMBER)); - ui.bounds(POLY(h3_temp), x, y, w, h); - cmd.text(x, y, w, h, str); - #endif - - /*// Show the set temperatures - format_temp(str, getTargetTemp_celsius(E0)); - ui.bounds(POLY(h0_set), x, y, w, h); - cmd.text(x, y, w, h, str); - - format_temp(str, getTargetTemp_celsius(E1)); - ui.bounds(POLY(h1_set), x, y, w, h); - cmd.text(x, y, w, h, str); - - #if ENABLED(COCOA_PRESS_EXTRA_HEATER) - if (has_extra_heater()) { - format_temp(str, getTargetTemp_celsius(E2)); - ui.bounds(POLY(h2_set), x, y, w, h); - cmd.text(x, y, w, h, str); - } - #endif - - #if ENABLED(COCOA_PRESS_CHAMBER_COOLER) - format_temp(str, getTargetTemp_celsius(CHAMBER)); - ui.bounds(POLY(h3_set), x, y, w, h); - cmd.text(x, y, w, h, str); - #endif*/ + cmd.button(x, y, w, h, str); } } void StatusScreen::draw_buttons(draw_mode_t what) { - int16_t x, y, w, h; + if (what & FOREGROUND) { + int16_t x, y, w, h; - const bool can_print = !isPrinting() && isMediaInserted() && isFileSelected(); - const bool can_select = !isPrinting() && isMediaInserted(); - const bool sdOrHostPrinting = ExtUI::isPrinting(); - const bool sdOrHostPaused = ExtUI::isPrintingPaused(); + const bool can_print = !isPrinting() && isMediaInserted() && isFileSelected(); + const bool can_select = !isPrinting() && isMediaInserted(); + const bool sdOrHostPrinting = ExtUI::isPrinting(); + const bool sdOrHostPaused = ExtUI::isPrintingPaused(); - CommandProcessor cmd; - PolyUI ui(cmd, what); + CommandProcessor cmd; + PolyUI ui(cmd, what); - cmd.font(font_medium).colors(normal_btn); + cmd.font(font_medium).colors(normal_btn); - ui.bounds(POLY(load_chocolate_btn), x, y, w, h); - cmd.tag(1).button(x, y, w, h, GET_TEXT_F(MSG_LOAD_UNLOAD)); + ui.bounds(POLY(load_chocolate_btn), x, y, w, h); + cmd.tag(1).button(x, y, w, h, GET_TEXT_F(MSG_LOAD_UNLOAD)); - ui.bounds(POLY(extrude_btn), x, y, w, h); - cmd.tag(2).button(x, y, w, h, GET_TEXT_F(MSG_EXTRUDE)); + ui.bounds(POLY(extrude_btn), x, y, w, h); + cmd.tag(2).button(x, y, w, h, GET_TEXT_F(MSG_EXTRUDE)); - ui.bounds(POLY(preheat_chocolate_btn), x, y, w, h); - cmd.tag(3).button(x, y, w, h, GET_TEXT_F(MSG_PREHEAT_CHOCOLATE)); + ui.bounds(POLY(preheat_chocolate_btn), x, y, w, h); + cmd.tag(3).button(x, y, w, h, GET_TEXT_F(MSG_PREHEAT_CHOCOLATE)); - ui.bounds(POLY(menu_btn), x, y, w, h); - cmd.tag(4).button(x, y, w, h, GET_TEXT_F(MSG_BUTTON_MENU)); + ui.bounds(POLY(menu_btn), x, y, w, h); + cmd.tag(4).button(x, y, w, h, GET_TEXT_F(MSG_BUTTON_MENU)); - ui.bounds(POLY(media_btn), x, y, w, h); - cmd.tag(5).enabled(can_select).button(x, y, w, h, GET_TEXT_F(MSG_BUTTON_MEDIA)); + ui.bounds(POLY(media_btn), x, y, w, h); + cmd.tag(5).enabled(can_select).button(x, y, w, h, GET_TEXT_F(MSG_BUTTON_MEDIA)); - ui.bounds(POLY(print_btn), x, y, w, h); - cmd.tag(6).colors(action_btn).enabled(can_print).button(x, y, w, h, GET_TEXT_F(MSG_BUTTON_PRINT)); + ui.bounds(POLY(print_btn), x, y, w, h); + cmd.tag(6).colors(action_btn).enabled(can_print).button(x, y, w, h, GET_TEXT_F(MSG_BUTTON_PRINT)); - ui.bounds(POLY(pause_btn), x, y, w, h); - cmd.tag(sdOrHostPaused ? 8 : 7).enabled(sdOrHostPrinting).button(x, y, w, h, sdOrHostPaused ? GET_TEXT_F(MSG_BUTTON_RESUME) : GET_TEXT_F(MSG_BUTTON_PAUSE)); + ui.bounds(POLY(pause_btn), x, y, w, h); + cmd.tag(sdOrHostPaused ? 8 : 7).enabled(sdOrHostPrinting).button(x, y, w, h, sdOrHostPaused ? GET_TEXT_F(MSG_BUTTON_RESUME) : GET_TEXT_F(MSG_BUTTON_PAUSE)); - ui.bounds(POLY(stop_btn), x, y, w, h); - cmd.tag(9).enabled(sdOrHostPrinting).button(x, y, w, h, GET_TEXT_F(MSG_BUTTON_STOP)); + ui.bounds(POLY(stop_btn), x, y, w, h); + cmd.tag(9).enabled(sdOrHostPrinting).button(x, y, w, h, GET_TEXT_F(MSG_BUTTON_STOP)); + } } +// When visible, the file name occupies the same space as the status +// message and must be drawn opaque. void StatusScreen::draw_file(draw_mode_t what) { - int16_t x, y, w, h; + if (mydata.gotMessage) return; - CommandProcessor cmd; - PolyUI ui(cmd, what); + if (what & FOREGROUND) { + int16_t x, y, w, h; - ui.bounds(POLY(file_name), x, y, w, h); + CommandProcessor cmd; + PolyUI ui(cmd, what); + ui.bounds(POLY(file_name), x, y, w, h); - if (what & BACKGROUND) { cmd.tag(5) - .cmd(COLOR_RGB(bg_text_enabled)) + .cmd (COLOR_RGB(bg_color)) + .rectangle(x, y, w, h) + .cmd (COLOR_RGB(bg_text_enabled)) .cmd (BITMAP_SOURCE(File_Icon_Info)) .cmd (BITMAP_LAYOUT(File_Icon_Info)) .cmd (BITMAP_SIZE (File_Icon_Info)) .icon(ICON_POS(x, y, w, h), File_Icon_Info, icon_scale); - } - - if (what & FOREGROUND) { - cmd.cmd(COLOR_RGB(bg_text_enabled)); - if(!isMediaInserted()) + if (!isMediaInserted()) draw_text_with_ellipsis(cmd, TEXT_POS(x, y, w, h), F("No media present"), OPT_CENTERY, font_small); - else if(isFileSelected()) { + else if (isFileSelected()) { FileList list; draw_text_with_ellipsis(cmd, TEXT_POS(x, y, w, h), list.filename(), OPT_CENTERY, font_small); - } else + } + else draw_text_with_ellipsis(cmd, TEXT_POS(x, y, w, h), F("No file selected"), OPT_CENTERY, font_small); } } +// The message will be drawn on the background and may be obscured by +// the filename. +void StatusScreen::draw_message(draw_mode_t what, const char *message) { + if (what & BACKGROUND) { + int16_t x, y, w, h; + + CommandProcessor cmd; + PolyUI ui(cmd, what); + ui.bounds(POLY(file_name), x, y, w, h); + + cmd.cmd(COLOR_RGB(bg_text_enabled)); + draw_text_box(cmd, TEXT_POS(x, y, w, h), message, OPT_CENTERY, font_small); + } +} + bool StatusScreen::isFileSelected() { - if(!isMediaInserted()) return false; + if (!isMediaInserted()) return false; FileList list; - if(list.isDir()) return false; + if (list.isDir()) return false; const char *filename = list.filename(); - if(filename[0] == '\0') return false; + if (filename[0] == '\0') return false; return true; } void StatusScreen::onRedraw(draw_mode_t what) { - if (what & BACKGROUND) { - CommandProcessor cmd; - cmd.cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)) - .tag(0); + if (what & FOREGROUND) { + draw_bkgnd(what); + draw_file(what); + draw_time(what); + draw_percent(what); + draw_temperature(what); + draw_buttons(what); } - - draw_file(what); - draw_time(what); - draw_progress(what); - draw_temperature(what); - draw_buttons(what); -} - -bool StatusScreen::onTouchStart(uint8_t) { - increment = 0; - return true; } bool StatusScreen::onTouchEnd(uint8_t tag) { @@ -352,24 +372,61 @@ bool StatusScreen::onTouchEnd(uint8_t tag) { bool StatusScreen::onTouchHeld(uint8_t tag) { if (tag == 2 && !ExtUI::isMoving()) { - LoadChocolateScreen::setManualFeedrateAndIncrement(1, increment); + float increment; + LoadChocolateScreen::setManualFeedrateAndIncrement(0.25, increment); UI_INCREMENT(AxisPosition_mm, E0); - current_screen.onRefresh(); } return false; } -void StatusScreen::setStatusMessage(FSTR_P) { +void StatusScreen::setStatusMessage(FSTR_P message) { + char buff[strlen_P((const char * const)message)+1]; + strcpy_P(buff, (const char * const) message); + setStatusMessage((const char *) buff); +} + +void StatusScreen::setStatusMessage(const char * const message) { + if (CommandProcessor::is_processing()) { + #if ENABLED(TOUCH_UI_DEBUG) + SERIAL_ECHO_MSG("Cannot update status message, command processor busy"); + #endif + return; + } + + CommandProcessor cmd; + cmd.cmd(CMD_DLSTART) + .cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)); + + const draw_mode_t what = BACKGROUND; + draw_bkgnd(what); + draw_message(what, message); + draw_time(what); + draw_percent(what); + draw_temperature(what); + draw_buttons(what); + + storeBackground(); + + #if ENABLED(TOUCH_UI_DEBUG) + SERIAL_ECHO_MSG("New status message: ", message); + #endif + + mydata.gotMessage = true; + + if (AT_SCREEN(StatusScreen)) + current_screen.onRefresh(); } -void StatusScreen::setStatusMessage(const char * const) { +void StatusScreen::onEntry() { + mydata.gotMessage = false; + load_background(cocoa_press_ui, sizeof(cocoa_press_ui)); } void StatusScreen::onIdle() { reset_menu_timeout(); if (refresh_timer.elapsed(STATUS_UPDATE_INTERVAL)) { - if (!EventLoop::is_touch_held()) - onRefresh(); + if (!EventLoop::is_touch_held()) onRefresh(); refresh_timer.start(); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h index 05f99e953d6c..57cf2308ab42 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h @@ -26,31 +26,35 @@ #define COCOA_STATUS_SCREEN #define COCOA_STATUS_SCREEN_CLASS StatusScreen -class StatusScreen : public BaseScreen, public CachedScreen { +struct StatusScreenData { + bool gotMessage; +}; + +class StatusScreen : public BaseScreen, public CachedScreen { private: static void _format_time(char *outstr, uint32_t time); - static float increment; - static bool jog_xy; - static bool fine_motion; - static void draw_time(draw_mode_t what); - static void draw_progress(draw_mode_t what); + static void draw_percent(draw_mode_t what); static void draw_temperature(draw_mode_t what); static void draw_buttons(draw_mode_t what); static void draw_file(draw_mode_t what); + static void draw_message(draw_mode_t what, const char *message); + static void draw_bkgnd(draw_mode_t what); + + static void send_buffer(CommandProcessor &cmd, const void *data, uint16_t len); + static void load_background(const void *data, uint16_t len); static bool isFileSelected(); public: static void loadBitmaps(); - static void unlockMotors(); static void setStatusMessage(const char *); static void setStatusMessage(FSTR_P); static void onRedraw(draw_mode_t); - static bool onTouchStart(uint8_t tag); + static void onEntry(); static bool onTouchHeld(uint8_t tag); static bool onTouchEnd(uint8_t tag); static void onIdle(); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/z_offset_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/z_offset_screen.cpp new file mode 100644 index 000000000000..aeff0d95f8f0 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/z_offset_screen.cpp @@ -0,0 +1,59 @@ +/*********************** + * z_offset_screen.cpp * + ***********************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" +#include "../screen_data.h" + +#ifdef COCOA_Z_OFFSET_SCREEN + +#include "z_offset_wizard.h" + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +void ZOffsetScreen::onRedraw(draw_mode_t what) { + widgets_t w(what); + w.precision(2, BaseNumericAdjustmentScreen::DEFAULT_MIDRANGE).units(GET_TEXT_F(MSG_UNITS_MM)); + + w.heading( GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); + w.color(z_axis).adjuster(4, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), getZOffset_mm()); + w.increments(); + w.button(2, GET_TEXT_F(MSG_PROBE_WIZARD), !isPrinting()); +} + +bool ZOffsetScreen::onTouchHeld(uint8_t tag) { + const int16_t steps = TERN(BABYSTEPPING, mmToWholeSteps(getIncrement(), Z), 0); + const float increment = TERN(BABYSTEPPING, mmFromWholeSteps(steps, Z), getIncrement()); + switch (tag) { + case 2: ZOffsetWizard::runWizard(); break; + case 4: UI_DECREMENT(ZOffset_mm); TERN(BABYSTEPPING, babystepAxis_steps(-steps, Z), UNUSED(steps)); break; + case 5: UI_INCREMENT(ZOffset_mm); TERN(BABYSTEPPING, babystepAxis_steps( steps, Z), UNUSED(steps)); break; + default: + return false; + } + SaveSettingsDialogBox::settingsChanged(); + return true; +} + +#endif // COCOA_Z_OFFSET_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/z_offset_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/z_offset_screen.h new file mode 100644 index 000000000000..93a364c109c6 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/z_offset_screen.h @@ -0,0 +1,32 @@ +/*********************** + * z_offset_screen.h * + ***********************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_Z_OFFSET_SCREEN +#define COCOA_Z_OFFSET_SCREEN_CLASS ZOffsetScreen + +class ZOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/z_offset_wizard.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/z_offset_wizard.cpp new file mode 100644 index 000000000000..9672e048d233 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/z_offset_wizard.cpp @@ -0,0 +1,162 @@ +/*********************** + * z_offset_screen.cpp * + ***********************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" +#include "../screen_data.h" + +#ifdef COCOA_Z_OFFSET_WIZARD + +#include "cocoa_press_ui.h" + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +#define POLY(A) PolyUI::poly_reader_t(A, sizeof(A)/sizeof(A[0])) +#define SHEET_THICKNESS 0.1 + +constexpr static ZOffsetWizardData &mydata = screen_data.ZOffsetWizard; + +void ZOffsetWizard::onEntry() { + mydata.increment = 242; + mydata.softEndstopState = getSoftEndstopState(); + BaseNumericAdjustmentScreen::onEntry(); + setSoftEndstopState(false); +} + +void ZOffsetWizard::onExit() { + setSoftEndstopState(mydata.softEndstopState); +} + +void ZOffsetWizard::onRedraw(draw_mode_t what) { + int16_t x, y, w, h; + + CommandProcessor cmd; + PolyUI ui(cmd, what); + + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)) + .tag(0) + .font(font_medium).colors(normal_btn); + + char b[32]; + dtostrf(getZOffset_mm(), 5, 2, b); + strcat_P(b, PSTR(" mm")); + ui.bounds(POLY(z_wizard_edit_box), x, y, w, h); + cmd.tag(0).fgcolor(z_axis).button(x, y, w, h, b); + + #define PREAMBLE(TAG) cmd.tag(TAG).colors(mydata.increment == TAG ? action_btn : normal_btn) + ui.bounds(POLY(z_wizard_inc1_btn), x, y, w, h); + PREAMBLE(241).button(x, y, w, h, F("0.01")); + + ui.bounds(POLY(z_wizard_inc2_btn), x, y, w, h); + PREAMBLE(242).button(x, y, w, h, F("0.1")); + + ui.bounds(POLY(z_wizard_inc3_btn), x, y, w, h); + PREAMBLE(243).button(x, y, w, h, F("1.0")); + + ui.bounds(POLY(z_wizard_neg_btn), x, y, w, h); + cmd.tag(4).colors(action_btn).button(x, y, w, h, F("")); + drawArrow(x, y, w, h, DOWN); + + ui.bounds(POLY(z_wizard_plus_btn), x, y, w, h); + cmd.tag(5).colors(action_btn).button(x, y, w, h, F("")); + drawArrow(x, y, w, h, UP); + + ui.bounds(POLY(z_wizard_done_btn), x, y, w, h); + cmd.tag(1).colors(action_btn).button(x, y, w, h, GET_TEXT_F(MSG_BUTTON_DONE)); + + cmd.tag(0); + ui.color(bg_text_enabled); + ui.fill(POLY(z_wizard_diagram)); + + ui.bounds(POLY(z_wizard_heading), x, y, w, h); + cmd.font(font_large) + .text(x, y, w, h, F("Z Probe Wizard")); +} + +float ZOffsetWizard::getIncrement() { + switch (mydata.increment) { + case 241: return 0.01; + case 242: return 0.1; + case 243: return 1.0; + default: return 0.0; + } +} + +void ZOffsetWizard::runWizard() { + // Restore the default Z offset + constexpr float offset[] = NOZZLE_TO_PROBE_OFFSET; + setZOffset_mm(offset[Z_AXIS]); + // Move above probe point + char cmd[64], str[10]; + strcpy_P(cmd, PSTR("G28 Z\nG0 F1000 X")); + dtostrf(TERN(Z_SAFE_HOMING,Z_SAFE_HOMING_X_POINT,X_CENTER), 3, 1, str); + strcat(cmd, str); + strcat_P(cmd, PSTR("Y")); + dtostrf(TERN(Z_SAFE_HOMING,Z_SAFE_HOMING_Y_POINT,Y_CENTER), 3, 1, str); + strcat(cmd, str); + strcat_P(cmd, PSTR("Z")); + dtostrf(SHEET_THICKNESS, 3, 1, str); + strcat(cmd, str); + injectCommands(cmd); + // Show instructions for user. + AlertDialogBox::show(F("\nOn the next screen, adjust the Z Offset so that a sheet of paper can pass between the nozzle and bed with slight resistance.\n\nOnce the printer stops moving, press Okay to begin.\n")); + // Set the destination screen after the dialog box. + current_screen.forget(); + PUSH_SCREEN(ZOffsetWizard); +} + +bool ZOffsetWizard::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: + GOTO_PREVIOUS(); + break; + case 4: + case 5: + return onTouchHeld(tag); + case 241 ... 243: + mydata.increment = tag; + break; + default: + return false; + } + return true; +} + +bool ZOffsetWizard::onTouchHeld(uint8_t tag) { + const float increment = TERN(BABYSTEPPING, + mmFromWholeSteps(mmToWholeSteps(getIncrement(), Z), Z), // Round increment to nearest steps + getIncrement() + ); + switch (tag) { + case 4: UI_DECREMENT(ZOffset_mm); UI_DECREMENT(AxisPosition_mm, Z); break; + case 5: UI_INCREMENT(ZOffset_mm); UI_INCREMENT(AxisPosition_mm, Z); break; + default: + return false; + } + SaveSettingsDialogBox::settingsChanged(); + return true; +} + +#endif // COCOA_Z_OFFSET_WIZARD diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/z_offset_wizard.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/z_offset_wizard.h new file mode 100644 index 000000000000..5c02f9803b73 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/z_offset_wizard.h @@ -0,0 +1,43 @@ +/*********************** + * z_offset_screen.h * + ***********************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_Z_OFFSET_WIZARD +#define COCOA_Z_OFFSET_WIZARD_CLASS ZOffsetWizard + +struct ZOffsetWizardData : public BaseNumericAdjustmentScreenData { + uint8_t increment; + bool softEndstopState; +}; + +class ZOffsetWizard : public BaseScreen, public UncachedScreen { + private: + static float getIncrement(); + public: + static void runWizard(); + static void onEntry(); + static void onExit(); + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); + static bool onTouchEnd(uint8_t tag); +}; 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 2ce9ed027e86..61476e30cad4 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 @@ -45,14 +45,14 @@ namespace ExtUI { } void onMediaInserted() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA sound.play(media_inserted, PLAY_ASYNCHRONOUS); StatusScreen::onMediaInserted(); #endif } void onMediaRemoved() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (isPrintingFromMedia()) { stopPrint(); InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FAILED); @@ -97,7 +97,7 @@ namespace ExtUI { void onLoadSettings(const char *buff) { InterfaceSettingsScreen::loadSettings(buff); } void onPostprocessSettings() {} // Called after loading or resetting stored settings - void onSettingsStored(bool success) { + void onSettingsStored(const bool success) { #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE if (success && InterfaceSettingsScreen::backupEEPROM()) { SERIAL_ECHOLNPGM("EEPROM backed up to SPI Flash"); @@ -106,9 +106,9 @@ namespace ExtUI { UNUSED(success); #endif } - void onSettingsLoaded(bool) {} + void onSettingsLoaded(const bool) {} - void onPlayTone(const uint16_t frequency, const uint16_t duration) { sound.play_tone(frequency, duration); } + void onPlayTone(const uint16_t frequency, const uint16_t duration/*=0*/) { sound.play_tone(frequency, duration); } void onUserConfirmRequired(const char * const msg) { if (msg) @@ -117,15 +117,26 @@ namespace ExtUI { ConfirmUserRequestAlertBox::hide(); } - #if HAS_LEVELING && HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + + #if HAS_MESH void onMeshUpdate(const int8_t x, const int8_t y, const_float_t val) { BedMeshViewScreen::onMeshUpdate(x, y, val); } void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { BedMeshViewScreen::onMeshUpdate(x, y, state); } #endif #if ENABLED(POWER_LOSS_RECOVERY) - void onPowerLossResume() {} // Called on resume from power-loss + void onSetPowerLoss(const bool onoff) { + // Called when power-loss is enabled/disabled + } + void onPowerLoss() { + // Called when power-loss state is detected + } + void onPowerLossResume() { + // Called on resume from power-loss + } #endif #if HAS_PID_HEATING diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h index 5168ef76af4a..b219bd88e166 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h @@ -248,7 +248,6 @@ #endif - /* this data is used to patch FT813 displays that use a GT911 as a touch-controller */ #ifdef PATCH_GT911 constexpr PROGMEM unsigned char GT911_data[] = { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp index 662753a1547c..24d99d7b45b5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp @@ -177,6 +177,14 @@ void CLCD::mem_write_pgm(uint32_t reg_address, const void *data, uint16_t len, u spi_ftdi_deselect(); } +// Write 3-Byte Address, Multiple Bytes, plus padding bytes, from PROGMEM, reversing bytes (suitable for loading XBM images) +void CLCD::mem_write_xbm(uint32_t reg_address, const void *data, uint16_t len, uint8_t padding) { + spi_ftdi_select(); + spi_write_addr(reg_address); + spi_write_bulk(data, len, padding); + spi_ftdi_deselect(); +} + // Write 3-Byte Address, Multiple Bytes, plus padding bytes, from PROGMEM, reversing bytes (suitable for loading XBM images) void CLCD::mem_write_xbm(uint32_t reg_address, FSTR_P data, uint16_t len, uint8_t padding) { spi_ftdi_select(); @@ -1208,7 +1216,7 @@ void CLCD::default_display_orientation() { + ENABLED(TOUCH_UI_INVERTED) * 1 ); cmd.execute(); - #elif EITHER(TOUCH_UI_PORTRAIT, TOUCH_UI_MIRRORED) + #elif ANY(TOUCH_UI_PORTRAIT, TOUCH_UI_MIRRORED) #error "PORTRAIT or MIRRORED orientation not supported on the FT800." #elif ENABLED(TOUCH_UI_INVERTED) mem_write_32(REG::ROTATE, 1); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h index 2e2657a83eec..80a2cece1792 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h @@ -118,6 +118,7 @@ class CLCD { static void mem_write_fill (uint32_t reg_address, uint8_t w_data, uint16_t len); static void mem_write_bulk (uint32_t reg_address, const void *data, uint16_t len, uint8_t padding = 0); static void mem_write_pgm (uint32_t reg_address, const void *data, uint16_t len, uint8_t padding = 0); + static void mem_write_xbm (uint32_t reg_address, const void *data, uint16_t len, uint8_t padding = 0); static void mem_write_bulk (uint32_t reg_address, FSTR_P str, uint16_t len, uint8_t padding = 0); static void mem_write_xbm (uint32_t reg_address, FSTR_P str, uint16_t len, uint8_t padding = 0); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index 6b2dc9eb4498..a9f77a518ba0 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -305,14 +305,11 @@ #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. - #define IF_ENABLED TERN_ #define IF_DISABLED(O,A) _TERN(_ENA_1(O),,A) #define ANY(V...) !DISABLED(V) - #define NONE(V...) DISABLED(V) - #define ALL(V...) ENABLED(V) - #define BOTH(V1,V2) ALL(V1,V2) - #define EITHER(V1,V2) ANY(V1,V2) + #define NONE DISABLED + #define ALL ENABLED // Remove compiler warning on an unused variable #ifndef UNUSED diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.cpp index 32cc37d2e2f7..7849b1e4616f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/circular_progress.cpp @@ -27,11 +27,11 @@ namespace FTDI { void draw_circular_progress(CommandProcessor& cmd, int x, int y, int w, int h, float percent, char *text, uint32_t bgcolor, uint32_t fgcolor) { const float rim = 0.3; - const float a = percent/100.0*2.0*PI; - const float a1 = min(PI/2, a); - const float a2 = min(PI/2, a-a1); - const float a3 = min(PI/2, a-a1-a2); - const float a4 = min(PI/2, a-a1-a2-a3); + const float a = percent/100.0*2.0*M_PI; + const float a1 = min(M_PI/2, a); + const float a2 = min(M_PI/2, a-a1); + const float a3 = min(M_PI/2, a-a1-a2); + const float a4 = min(M_PI/2, a-a1-a2-a3); const int ro = min(w,h) * 8; const int rr = ro * rim; @@ -69,21 +69,21 @@ namespace FTDI { cmd.cmd(VERTEX2F(cx + ro*sin(a1) + 16,cy - ro*cos(a1) + 8)); // Paint lower-right quadrant - if (a > PI/2) { + if (a > M_PI/2) { cmd.cmd(BEGIN(EDGE_STRIP_R)); cmd.cmd(VERTEX2F(cx, cy)); cmd.cmd(VERTEX2F(cx + ro*cos(a2),cy + ro*sin(a2) + 16)); } // Paint lower-left quadrant - if (a > PI) { + if (a > M_PI) { cmd.cmd(BEGIN(EDGE_STRIP_B)); cmd.cmd(VERTEX2F(cx, cy)); cmd.cmd(VERTEX2F(cx - ro*sin(a3) - 8,cy + ro*cos(a3))); } // Paint upper-left quadrant - if (a > 1.5*PI) { + if (a > 1.5*M_PI) { cmd.cmd(BEGIN(EDGE_STRIP_L)); cmd.cmd(VERTEX2F(cx, cy)); cmd.cmd(VERTEX2F(cx - ro*cos(a4),cy - ro*sin(a4))); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp index 7fccb309f56b..dd2e477d9f2c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp @@ -71,7 +71,6 @@ void UIData::set_persistent_data(uint8_t value) { flags.value = value & get_persistent_data_mask(); } - void UIData::enable_touch_sounds(bool enabled) { UIData::flags.bits.touch_start_sound = enabled; UIData::flags.bits.touch_end_sound = enabled; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp index 1c193ade4be1..2faa1c72e688 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp @@ -58,11 +58,11 @@ cyrillic_fm.stride = 20; cyrillic_fm.width = 40; cyrillic_fm.height = 49; - LOOP_L_N(i, 127) + for (uint8_t i = 0; i < 127; ++i) cyrillic_fm.char_widths[i] = 0; // For cyrillic characters, copy the character widths from the widths tables - LOOP_L_N(i, NUM_ELEMENTS(cyrillic_font_widths)) { + for (uint8_t i = 0; i < NUM_ELEMENTS(cyrillic_font_widths); ++i) { cyrillic_fm.char_widths[i] = cyrillic_font_widths[i]; } CLCD::mem_write_bulk(addr, &cyrillic_fm, 148); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h index 30b1f8439955..6a1a703e45a3 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h @@ -100,7 +100,6 @@ const uint8_t cyrillic_font_widths[] PROGMEM = { 21, // ё }; - /* This is a dump of "font_bitmaps/cyrillic_char_set_bitmap_31.png" * using the tool "bitmap2cpp.py". The tool converts the image into * 16-level grayscale and packs two pixels per byte. The resulting diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp index 0e251f7bb1c7..b229154e82a4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp @@ -21,7 +21,7 @@ #include "../ftdi_extended.h" -#if BOTH(FTDI_EXTENDED, TOUCH_UI_USE_UTF8) +#if ALL(FTDI_EXTENDED, TOUCH_UI_USE_UTF8) namespace FTDI { // Returns the height of a standard FTDI romfont diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp index d12bf9711907..5171ee508aff 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp @@ -21,7 +21,7 @@ #include "../ftdi_extended.h" -#if BOTH(FTDI_EXTENDED, TOUCH_UI_USE_UTF8) +#if ALL(FTDI_EXTENDED, TOUCH_UI_USE_UTF8) constexpr static uint8_t std_font = 31; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp index 6f189155f5de..c05d6577d04b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp @@ -21,7 +21,7 @@ #include "../ftdi_extended.h" -#if BOTH(FTDI_EXTENDED, TOUCH_UI_USE_UTF8) +#if ALL(FTDI_EXTENDED, TOUCH_UI_USE_UTF8) using namespace FTDI; @@ -66,14 +66,6 @@ * character (this is not the unicode codepoint) */ - utf8_char_t FTDI::get_utf8_char_and_inc(char *&c) { - utf8_char_t val = *(uint8_t*)c++; - if ((val & 0xC0) == 0xC0) - while ((*c & 0xC0) == 0x80) - val = (val << 8) | *(uint8_t*)c++; - return val; - } - utf8_char_t FTDI::get_utf8_char_and_inc(const char *&c) { utf8_char_t val = *(uint8_t*)c++; if ((val & 0xC0) == 0xC0) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h index 7818957fcc2d..83ab56df579e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.h @@ -47,7 +47,6 @@ namespace FTDI { * pointer to the next character */ utf8_char_t get_utf8_char_and_inc(const char *&c); - utf8_char_t get_utf8_char_and_inc(char *&c); /* Returns the next character in a UTF8 string, without incrementing */ diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp index 4fb2f8fdbf24..02a39cd01c87 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp @@ -342,11 +342,11 @@ alt_fm.stride = 19; alt_fm.width = 38; alt_fm.height = 49; - LOOP_L_N(i, 127) + for (uint8_t i = 0; i < 127; ++i) alt_fm.char_widths[i] = 0; // For special characters, copy the character widths from the char tables - LOOP_L_N(i, NUM_ELEMENTS(char_recipe)) { + for (uint8_t i = 0; i < NUM_ELEMENTS(char_recipe); ++i) { uint8_t std_char, alt_char, alt_data; get_char_data(i, std_char, alt_char, alt_data); if (std_char == 0) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py index 6aa8947b9858..1b84f171d954 100755 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/file2cpp.py @@ -30,7 +30,7 @@ def deflate(data): parser.add_argument("-d", "--deflate", action="store_true", help="Packs the data using the deflate algorithm") args = parser.parse_args() - varname = os.path.splitext(os.path.basename(args.input))[0]; + varname = os.path.splitext(os.path.basename(args.input))[0] with open(args.input, "rb") as in_file: data = in_file.read() diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/font2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/font2cpp.py index 0c4499e9aadf..1d11b9307a5b 100755 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/font2cpp.py +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/font2cpp.py @@ -77,7 +77,7 @@ def write(self): if len(self.values): self.blocks.append(self.values) - block_strs = []; + block_strs = [] for b in self.blocks: data = self.convert_to_4bpp(b) data = ', '.join(data) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py index 74be57430049..131141079a21 100755 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/img2cpp.py @@ -44,12 +44,12 @@ def add_bits_to_byte(self, value, size = 1): def append_rgb565(self, color): value = ((color[0] & 0xF8) << 8) + ((color[1] & 0xFC) << 3) + ((color[2] & 0xF8) >> 3) - self.values.append((value & 0x00FF) >> 0); - self.values.append((value & 0xFF00) >> 8); + self.values.append((value & 0x00FF) >> 0) + self.values.append((value & 0xFF00) >> 8) def append_rgb332(self, color): value = (color[0] & 0xE0) + ((color[1] & 0xE0) >> 3) + ((color[2] & 0xC0) >> 6) - self.values.append(value); + self.values.append(value) def append_grayscale(self, color, bits): luminance = int(0.2126 * color[0] + 0.7152 * color[1] + 0.0722 * color[2]) @@ -99,7 +99,7 @@ def write(self, varname, deflate): parser.add_argument("-m", "--mode", default="l1", help="Mode, can be l1, l2, l4, l8, rgb332 or rgb565") args = parser.parse_args() - varname = os.path.splitext(os.path.basename(args.input))[0]; + varname = os.path.splitext(os.path.basename(args.input))[0] writer = WriteSource(args.mode) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py old mode 100644 new mode 100755 index f6e4a3e39abe..0f39932c6a92 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/svg2cpp.py @@ -1,4 +1,4 @@ -#!/usr/bin/python +#!/usr/bin/python3 # Written By Marcio Teixeira 2018 - Aleph Objects, Inc. # @@ -18,6 +18,8 @@ from __future__ import print_function import argparse,re,sys +from html.parser import HTMLParser + usage = ''' This program extracts line segments from a SVG file and writes them as coordinates in a C array. The x and y values will be @@ -107,19 +109,16 @@ def write(self): print("constexpr float y_max = %f;" % self.y_max) print() - def from_svg_view_box(self, svg): - s = re.search(']+>', svg); - if s: - m = re.search('viewBox="([0-9-.]+) ([0-9-.]+) ([0-9-.]+) ([0-9-.]+)"', svg) - if m: - self.x_min = float(m[1]) - self.y_min = float(m[2]) - self.x_max = float(m[3]) - self.y_max = float(m[4]) - return True + def from_svg_view_box(self, viewbox): + m = re.search('([0-9-.]+) ([0-9-.]+) ([0-9-.]+) ([0-9-.]+)', viewbox) + if m: + self.x_min = float(m[1]) + self.y_min = float(m[2]) + self.x_max = float(m[3]) + self.y_max = float(m[4]) + return True return False -# op class WriteDataStructure: def __init__(self, bounding_box): self.bounds = bounding_box @@ -143,19 +142,29 @@ def path_finished(self, id): print("const PROGMEM uint16_t", id + "[] = {" + ", ".join (self.hex_words) + "};") self.hex_words = [] -class Parser: - def __init__(self, op): +class SVGParser(HTMLParser): + def __init__(self, args): + super().__init__() + self.args = args + self.tags = [] + self.groups = [] + self.op = None + self.restart() + + def set_consumer(self, op): self.op = op - self.reset() + if self.op: + self.op.reset() - def reset(self): + def restart(self): self.last_x = 0 self.last_y = 0 self.initial_x = 0 self.initial_y = 0 def process_svg_path_L_or_M(self, cmd, x, y): - self.op.command(cmd, x, y) + if self.op: + self.op.command(cmd, x, y) self.last_x = x self.last_y = y if cmd == "M": @@ -239,42 +248,71 @@ def process_svg_path_data(self, id, d): print("Syntax error:", d, "in path", id, "\n", file=sys.stderr) quit() - def process_svg_paths(self, svg): - self.op.reset() - for path in re.findall(']+>', svg): - id = "" - m = re.search(' id="(.*)"', path) - if m: - id = m[1] + def find_attr(attrs, what): + for attr, value in attrs: + if attr == what: + return value - m = re.search(' transform="(.*)"', path) - if m: + def layer_matches(self): + """ Are we in the correct layer?""" + if not self.args.layer: + return True + for l in self.groups: + if l and l.find(self.args.layer) != -1: + return True + return False + + def handle_starttag(self, tag, attrs): + self.tags.append(tag) + if tag == 'svg': + self.viewbox = SVGParser.find_attr(attrs, 'viewbox') + if tag == 'g': + label = SVGParser.find_attr(attrs, 'inkscape:label') + self.groups.append(label) + if label and self.layer_matches(): + print("Reading layer:", label, file=sys.stderr) + if tag == 'path' and self.layer_matches(): + id = SVGParser.find_attr(attrs, 'id') + transform = SVGParser.find_attr(attrs, 'transform') + if transform: print("Found transform in path", id, "! Cannot process file!", file=sys.stderr) quit() - - m = re.search(' d="(.*)"', path) - if m: - self.process_svg_path_data(id, m[1]) - self.op.path_finished(id) - self.reset() + d = SVGParser.find_attr(attrs, 'd') + if d: + self.process_svg_path_data(id, d) + if self.op: + self.op.path_finished(id) + self.restart() + + def handle_endtag(self, tag): + if tag == 'g': + self.groups.pop() + if tag != self.tags.pop(): + print("Error popping tag off list") if __name__ == "__main__": parser = argparse.ArgumentParser() parser.add_argument("filename") + parser.add_argument('--layer', help='only include layers which have this string in their names') args = parser.parse_args() f = open(args.filename, "r") data = f.read() - print(header) + # First pass to grab viewbox + p = SVGParser(args) + p.feed(data) b = ComputeBoundingBox() - if not b.from_svg_view_box(data): + if not b.from_svg_view_box(p.viewbox): # Can't find the view box, so use the bounding box of the elements themselves. - p = Parser(b) - p.process_svg_paths(data) - b.write() + p = SVGParser(args) + p.set_consumer(b) + p.feed(data) + b.write() + # Last pass to process paths w = WriteDataStructure(b) - p = Parser(w) - p.process_svg_paths(data) + p = SVGParser(args) + p.set_consumer(w) + p.feed(data) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp index 43e5c333651a..698f0d47b794 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp @@ -76,7 +76,7 @@ void AboutScreen::onRedraw(draw_mode_t) { #endif , OPT_CENTER, font_xlarge ); - #if BOTH(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) + #if ALL(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) cmd.tag(3); #endif draw_text_box(cmd, FW_VERS_POS, @@ -91,7 +91,7 @@ void AboutScreen::onRedraw(draw_mode_t) { draw_text_box(cmd, LICENSE_POS, GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); cmd.font(font_medium); - #if BOTH(PRINTCOUNTER, FTDI_STATISTICS_SCREEN) + #if ALL(PRINTCOUNTER, FTDI_STATISTICS_SCREEN) cmd.colors(normal_btn) .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)); #endif @@ -102,10 +102,10 @@ void AboutScreen::onRedraw(draw_mode_t) { bool AboutScreen::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); break; - #if BOTH(PRINTCOUNTER, FTDI_STATISTICS_SCREEN) + #if ALL(PRINTCOUNTER, FTDI_STATISTICS_SCREEN) case 2: GOTO_SCREEN(StatisticsScreen); break; #endif - #if BOTH(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) + #if ALL(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) case 3: GOTO_SCREEN(DeveloperMenu); break; #endif default: return false; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp index 8753b44e709b..4745ff99dc55 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp @@ -37,7 +37,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { } #if ENABLED(TOUCH_UI_PORTRAIT) - #if EITHER(HAS_MULTI_HOTEND, SENSORLESS_HOMING) + #if ANY(HAS_MULTI_HOTEND, SENSORLESS_HOMING) #define GRID_ROWS 9 #else #define GRID_ROWS 8 @@ -58,7 +58,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { #define BACKLASH_POS BTN_POS(2,7), BTN_SIZE(1,1) #define OFFSETS_POS BTN_POS(1,8), BTN_SIZE(1,1) #define TMC_HOMING_THRS_POS BTN_POS(2,8), BTN_SIZE(1,1) - #if EITHER(HAS_MULTI_HOTEND, SENSORLESS_HOMING) + #if ANY(HAS_MULTI_HOTEND, SENSORLESS_HOMING) #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) #else #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) @@ -99,7 +99,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(14).button(TMC_HOMING_THRS_POS, GET_TEXT_F(MSG_TMC_HOMING_THRS)) .enabled(ENABLED(HAS_MULTI_HOTEND)) .tag(4) .button(OFFSETS_POS, GET_TEXT_F(MSG_OFFSETS_MENU)) - .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) + .enabled(ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) .tag(11).button(FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) .tag(12).button(ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS)) .tag(15).button(DISPLAY_POS, GET_TEXT_F(MSG_DISPLAY_MENU)) @@ -133,7 +133,7 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { #endif case 9: GOTO_SCREEN(InterfaceSettingsScreen); LockScreen::check_passcode(); break; case 10: GOTO_SCREEN(RestoreFailsafeDialogBox); LockScreen::check_passcode(); break; - #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) + #if ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) case 11: GOTO_SCREEN(FilamentMenu); break; #endif case 12: GOTO_SCREEN(EndstopStatesScreen); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp index 37eb29a99d11..c894d017ebcd 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp @@ -95,7 +95,7 @@ void BedMeshEditScreen::setHighlightedValue(float value) { } void BedMeshEditScreen::moveToHighlightedValue() { - if (ExtUI::getMeshValid()) { + if (ExtUI::getLevelingIsValid()) { ExtUI::setLevelingActive(true); ExtUI::setSoftEndstopState(false); ExtUI::moveToMeshPoint(mydata.highlight, gaugeThickness + mydata.zAdjustment); @@ -174,11 +174,11 @@ bool BedMeshEditScreen::onTouchEnd(uint8_t tag) { case 1: // On Cancel, reload saved mesh, discarding changes GOTO_PREVIOUS(); - injectCommands(F("G29 L1")); + injectCommands(F(TERN(AUTO_BED_LEVELING_UBL, "G29 L1", "M501"))); return true; case 2: saveAdjustedHighlightedValue(); - injectCommands(F("G29 S1")); + injectCommands(F(TERN(AUTO_BED_LEVELING_UBL, "G29 S1", "M500"))); mydata.needSave = false; return true; case 3: @@ -191,7 +191,7 @@ bool BedMeshEditScreen::onTouchEnd(uint8_t tag) { void BedMeshEditScreen::show() { // On entry, always home (to account for possible Z offset changes) and save current mesh - SpinnerDialogBox::enqueueAndWait(F("G28\nG29 S1")); + SpinnerDialogBox::enqueueAndWait(F("G28\n" TERN(AUTO_BED_LEVELING_UBL, "G29 S1", "M500"))); // After the spinner, go to this screen. current_screen.forget(); PUSH_SCREEN(BedMeshEditScreen); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp index 7b4195ff5ce3..6030fd02a0e7 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp @@ -53,10 +53,7 @@ constexpr static float gaugeThickness = 0.25; #endif static float meshGetter(uint8_t x, uint8_t y, void*) { - xy_uint8_t pos; - pos.x = x; - pos.y = y; - return ExtUI::getMeshPoint(pos); + return ExtUI::getMeshPoint(xy_uint8_t({ x, y })); } void BedMeshViewScreen::onEntry() { @@ -125,7 +122,7 @@ void BedMeshViewScreen::onMeshUpdate(const int8_t x, const int8_t y, const ExtUI mydata.count = 0; break; case ExtUI::G29_FINISH: - if (mydata.count == GRID_MAX_POINTS && ExtUI::getMeshValid()) + if (mydata.count == GRID_MAX_POINTS && ExtUI::getLevelingIsValid()) mydata.message = GET_TEXT_F(MSG_BED_MAPPING_DONE); else mydata.message = GET_TEXT_F(MSG_BED_MAPPING_INCOMPLETE); @@ -158,7 +155,7 @@ void BedMeshViewScreen::doProbe() { } void BedMeshViewScreen::show() { - injectCommands(F("G29 L1")); + TERN_(AUTO_BED_LEVELING_UBL, injectCommands(F("G29 L1"))); GOTO_SCREEN(BedMeshViewScreen); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h index b9791fff7a15..3ec8e06adfaa 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h @@ -26,7 +26,7 @@ struct BedMeshViewScreenData { FSTR_P message; - uint8_t count; + grid_count_t count; xy_uint8_t highlight; }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp index c0940bed5ce4..b01e45948c7a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp @@ -30,7 +30,7 @@ #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) #if ENABLED(TOUCH_UI_PORTRAIT) - #include "../theme/bootscreen_logo_portrait.h" + #include "../theme/_bootscreen_portrait.h" #else #include "../theme/_bootscreen_landscape.h" #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.cpp index 2ec8a3bbd19f..4a6073372387 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/developer_menu.cpp @@ -44,7 +44,7 @@ void DeveloperMenu::onRedraw(draw_mode_t what) { constexpr bool has_flash = false; #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA constexpr bool has_media = true; #else constexpr bool has_media = false; @@ -98,7 +98,7 @@ bool DeveloperMenu::onTouchEnd(uint8_t tag) { break; case 4: GOTO_SCREEN(TouchRegistersScreen); break; case 5: sound.play(js_bach_joy, PLAY_ASYNCHRONOUS); break; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA case 6: if (!MediaPlayerScreen::playCardMedia()) AlertDialogBox::showError(F("Cannot open STARTUP.AVI")); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp index f7e57cf0b9a0..37f1ec5d4b71 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp @@ -41,7 +41,7 @@ void EndstopStatesScreen::onExit() { #define GRID_ROWS 7 #define PIN_BTN(X,Y,PIN,LABEL) button(BTN_POS(X,Y), BTN_SIZE(2,1), LABEL) -#define PIN_ENABLED(X,Y,LABEL,PIN,INV) cmd.enabled(1).colors(READ(PIN##_PIN) != INV ? action_btn : normal_btn).PIN_BTN(X,Y,PIN,LABEL); +#define PIN_ENABLED(X,Y,LABEL,PIN,ST) cmd.enabled(1).colors(READ(PIN##_PIN) == ST ? action_btn : normal_btn).PIN_BTN(X,Y,PIN,LABEL); #define PIN_DISABLED(X,Y,LABEL,PIN) cmd.enabled(0).PIN_BTN(X,Y,PIN,LABEL); void EndstopStatesScreen::onRedraw(draw_mode_t) { @@ -54,32 +54,32 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) { cmd.font(TERN(TOUCH_UI_PORTRAIT, font_large, font_medium)) .text(BTN_POS(1,1), BTN_SIZE(6,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) .font(font_tiny); - #if HAS_X_MAX + #if USE_X_MAX PIN_ENABLED (1, 2, PSTR(STR_X_MAX), X_MAX, X_MAX_ENDSTOP_INVERTING) #else PIN_DISABLED(1, 2, PSTR(STR_X_MAX), X_MAX) #endif - #if HAS_Y_MAX + #if USE_Y_MAX PIN_ENABLED (3, 2, PSTR(STR_Y_MAX), Y_MAX, Y_MAX_ENDSTOP_INVERTING) #else PIN_DISABLED(3, 2, PSTR(STR_Y_MAX), Y_MAX) #endif - #if HAS_Z_MAX + #if USE_Z_MAX PIN_ENABLED (5, 2, PSTR(STR_Z_MAX), Z_MAX, Z_MAX_ENDSTOP_INVERTING) #else PIN_DISABLED(5, 2, PSTR(STR_Z_MAX), Z_MAX) #endif - #if HAS_X_MIN + #if USE_X_MIN PIN_ENABLED (1, 3, PSTR(STR_X_MIN), X_MIN, X_MIN_ENDSTOP_INVERTING) #else PIN_DISABLED(1, 3, PSTR(STR_X_MIN), X_MIN) #endif - #if HAS_Y_MIN + #if USE_Y_MIN PIN_ENABLED (3, 3, PSTR(STR_Y_MIN), Y_MIN, Y_MIN_ENDSTOP_INVERTING) #else PIN_DISABLED(3, 3, PSTR(STR_Y_MIN), Y_MIN) #endif - #if HAS_Z_MIN + #if USE_Z_MIN PIN_ENABLED (5, 3, PSTR(STR_Z_MIN), Z_MIN, Z_MIN_ENDSTOP_INVERTING) #else PIN_DISABLED(5, 3, PSTR(STR_Z_MIN), Z_MIN) @@ -89,7 +89,7 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) { #else PIN_DISABLED(1, 4, GET_TEXT_F(MSG_RUNOUT_1), FIL_RUNOUT) #endif - #if BOTH(HAS_MULTI_EXTRUDER, FILAMENT_RUNOUT_SENSOR) && PIN_EXISTS(FIL_RUNOUT2) + #if ALL(HAS_MULTI_EXTRUDER, FILAMENT_RUNOUT_SENSOR) && PIN_EXISTS(FIL_RUNOUT2) PIN_ENABLED (3, 4, GET_TEXT_F(MSG_RUNOUT_2), FIL_RUNOUT2, FIL_RUNOUT2_STATE) #else PIN_DISABLED(3, 4, GET_TEXT_F(MSG_RUNOUT_2), FIL_RUNOUT2) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp index 68948b0c5e5d..0569b90032d1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/filament_runout_screen.cpp @@ -46,7 +46,9 @@ void FilamentRunoutScreen::onRedraw(draw_mode_t what) { bool FilamentRunoutScreen::onTouchHeld(uint8_t tag) { using namespace ExtUI; - const float increment = getIncrement(); + #if HAS_FILAMENT_RUNOUT_DISTANCE + const float increment = getIncrement(); + #endif switch (tag) { case 2: setFilamentRunoutEnabled(!getFilamentRunoutEnabled()); break; #if HAS_FILAMENT_RUNOUT_DISTANCE diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.cpp index 5d797f44df31..15252941d7de 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/language_menu.cpp @@ -53,6 +53,8 @@ void LanguageMenu::onRedraw(draw_mode_t) { #endif } +extern uint8_t ftdi_language; + bool LanguageMenu::onTouchEnd(uint8_t tag) { if (tag > 0 && tag <= NUM_LANGUAGES) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp index 2fb9d18498c0..64efb64cfc0a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp @@ -25,7 +25,7 @@ #ifdef FTDI_LEVELING_MENU -#if BOTH(HAS_BED_PROBE,BLTOUCH) +#if ALL(HAS_BED_PROBE, BLTOUCH) #include "../../../../feature/bltouch.h" #endif @@ -81,7 +81,7 @@ void LevelingMenu::onRedraw(draw_mode_t what) { .text(BLTOUCH_TITLE_POS, GET_TEXT_F(MSG_BLTOUCH)) #endif .font(font_medium).colors(normal_btn) - .enabled(EITHER(Z_STEPPER_AUTO_ALIGN,MECHANICAL_GANTRY_CALIBRATION)) + .enabled(ANY(Z_STEPPER_AUTO_ALIGN, MECHANICAL_GANTRY_CALIBRATION)) .tag(2).button(LEVEL_AXIS_POS, GET_TEXT_F(MSG_LEVEL_X_AXIS)) .enabled(ENABLED(HAS_BED_PROBE)) .tag(3).button(PROBE_BED_POS, GET_TEXT_F(MSG_PROBE_BED)) @@ -103,7 +103,7 @@ void LevelingMenu::onRedraw(draw_mode_t what) { bool LevelingMenu::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); break; - #if EITHER(Z_STEPPER_AUTO_ALIGN,MECHANICAL_GANTRY_CALIBRATION) + #if ANY(Z_STEPPER_AUTO_ALIGN, MECHANICAL_GANTRY_CALIBRATION) case 2: SpinnerDialogBox::enqueueAndWait(F("G34")); break; #endif #if HAS_BED_PROBE diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp index 001f97490b1d..137ddc59cff5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/main_menu.cpp @@ -43,7 +43,7 @@ void MainMenu::onRedraw(draw_mode_t what) { #define ADVANCED_SETTINGS_POS BTN_POS(1,2), BTN_SIZE(2,1) #if ENABLED(CUSTOM_MENU_MAIN) #define FILAMENTCHANGE_POS BTN_POS(1,3), BTN_SIZE(1,1) - #define CUSTOM_MENU_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define CUSTOM_MENU_POS BTN_POS(2,3), BTN_SIZE(1,1) #else #define FILAMENTCHANGE_POS BTN_POS(1,3), BTN_SIZE(2,1) #endif @@ -66,7 +66,7 @@ void MainMenu::onRedraw(draw_mode_t what) { #if ENABLED(CUSTOM_MENU_MAIN) #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(2,1) #define FILAMENTCHANGE_POS BTN_POS(3,4), BTN_SIZE(2,1) - #define CUSTOM_MENU_POS BTN_POS(5,4), BTN_SIZE(2,1) + #define CUSTOM_MENU_POS BTN_POS(5,4), BTN_SIZE(2,1) #else #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(3,1) #define FILAMENTCHANGE_POS BTN_POS(4,4), BTN_SIZE(3,1) @@ -92,7 +92,7 @@ void MainMenu::onRedraw(draw_mode_t what) { .tag( 9).button(LEVELING_POS, GET_TEXT_F(MSG_LEVELING)) .tag(10).button(ABOUT_PRINTER_POS, GET_TEXT_F(MSG_INFO_MENU)) #if ENABLED(CUSTOM_MENU_MAIN) - .tag(11).button(CUSTOM_MENU_POS, GET_TEXT_F(MSG_CUSTOM_COMMANDS)) + .tag(11).button(CUSTOM_MENU_POS, GET_TEXT_F(MSG_CUSTOM_COMMANDS)) #endif .colors(action_btn) .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BUTTON_DONE)); @@ -103,22 +103,30 @@ bool MainMenu::onTouchEnd(uint8_t tag) { using namespace ExtUI; switch (tag) { - case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; - case 2: SpinnerDialogBox::enqueueAndWait(F("G28")); break; + case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; + case 2: SpinnerDialogBox::enqueueAndWait(F("G28")); break; #if ENABLED(NOZZLE_CLEAN_FEATURE) - case 3: injectCommands(F("G12")); GOTO_SCREEN(StatusScreen); break; + case 3: + injectCommands(F("G12")); + GOTO_SCREEN(StatusScreen); break; #endif - case 4: GOTO_SCREEN(MoveAxisScreen); break; - case 5: injectCommands(F("M84")); break; - case 6: GOTO_SCREEN(TemperatureScreen); break; - case 7: GOTO_SCREEN(ChangeFilamentScreen); break; - case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; + case 4: GOTO_SCREEN(MoveAxisScreen); break; + case 5: + injectCommands(F("M84 E" + TERN_(DISABLE_IDLE_X, " X") + TERN_(DISABLE_IDLE_Y, " Y") + TERN_(DISABLE_IDLE_Z, " Z") + )); + break; + case 6: GOTO_SCREEN(TemperatureScreen); break; + case 7: GOTO_SCREEN(ChangeFilamentScreen); break; + case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; #if HAS_LEVELING - case 9: GOTO_SCREEN(LevelingMenu); break; + case 9: GOTO_SCREEN(LevelingMenu); break; #endif - case 10: GOTO_SCREEN(AboutScreen); break; + case 10: GOTO_SCREEN(AboutScreen); break; #if ENABLED(CUSTOM_MENU_MAIN) - case 11: GOTO_SCREEN(CustomUserMenus); break; + case 11: GOTO_SCREEN(CustomUserMenus); break; #endif default: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.cpp index 061c8555df54..fbfce19a7593 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/media_player_screen.cpp @@ -57,7 +57,7 @@ void MediaPlayerScreen::onRedraw(draw_mode_t) { } bool MediaPlayerScreen::playCardMedia() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA char fname[15]; strcpy_P(fname, PSTR("STARTUP.AVI")); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp index c3927c21a7dd..95fe023cdaf6 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp @@ -37,7 +37,7 @@ void BaseMoveAxisScreen::onEntry() { // ourselves. The relative distances are reset to zero whenever this // screen is entered. - LOOP_L_N(i, ExtUI::extruderCount) { + for (uint8_t i = 0; i < ExtUI::extruderCount; ++i) { mydata.e_rel[i] = 0; } BaseNumericAdjustmentScreen::onEntry(); @@ -72,13 +72,15 @@ void MoveAxisScreen::onRedraw(draw_mode_t what) { w.increments(); } -bool BaseMoveAxisScreen::onTouchHeld(uint8_t tag) { +bool BaseMoveAxisScreen::onTouchHeld(const uint8_t tag) { #define UI_INCREMENT_AXIS(axis) setManualFeedrate(axis, increment); UI_INCREMENT(AxisPosition_mm, axis); #define UI_DECREMENT_AXIS(axis) setManualFeedrate(axis, increment); UI_DECREMENT(AxisPosition_mm, axis); const float increment = getIncrement(); switch (tag) { - case 2: UI_DECREMENT_AXIS(X); break; - case 3: UI_INCREMENT_AXIS(X); break; + #if HAS_X_AXIS + case 2: UI_DECREMENT_AXIS(X); break; + case 3: UI_INCREMENT_AXIS(X); break; + #endif #if HAS_EXTRUDERS // For extruders, also update relative distances. case 8: UI_DECREMENT_AXIS(E0); mydata.e_rel[0] -= increment; break; @@ -120,20 +122,20 @@ void BaseMoveAxisScreen::raiseZtoTop() { setAxisPosition_mm(Z_MAX_POS - 5, Z, homing_feedrate.z); } -float BaseMoveAxisScreen::getManualFeedrate(uint8_t axis, float increment_mm) { +float BaseMoveAxisScreen::getManualFeedrate(const uint8_t axis, const_float_t increment_mm) { // Compute feedrate so that the tool lags the adjuster when it is // being held down, this allows enough margin for the planner to // connect segments and even out the motion. constexpr xyze_feedrate_t max_manual_feedrate = MANUAL_FEEDRATE; - return min(max_manual_feedrate[axis] / 60.0f, ABS(increment_mm * (TOUCH_REPEATS_PER_SECOND) * 0.80f)); + return min(MMM_TO_MMS(max_manual_feedrate[axis]), ABS(increment_mm * (TOUCH_REPEATS_PER_SECOND) * 0.80f)); } -void BaseMoveAxisScreen::setManualFeedrate(ExtUI::axis_t axis, float increment_mm) { +void BaseMoveAxisScreen::setManualFeedrate(const ExtUI::axis_t axis, const_float_t increment_mm) { ExtUI::setFeedrate_mm_s(getManualFeedrate(X_AXIS + (axis - ExtUI::X), increment_mm)); } #if HAS_EXTRUDERS - void BaseMoveAxisScreen::setManualFeedrate(ExtUI::extruder_t, float increment_mm) { + void BaseMoveAxisScreen::setManualFeedrate(const ExtUI::extruder_t, const_float_t increment_mm) { ExtUI::setFeedrate_mm_s(getManualFeedrate(E_AXIS, increment_mm)); } #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.h index 16723cfc13bc..b26254c4df62 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.h @@ -32,14 +32,14 @@ struct MoveAxisScreenData { class BaseMoveAxisScreen : public BaseNumericAdjustmentScreen { private: - static float getManualFeedrate(uint8_t axis, float increment_mm); + static float getManualFeedrate(const uint8_t axis, const_float_t increment_mm); public: static void raiseZtoTop(); - static void setManualFeedrate(ExtUI::axis_t, float increment_mm); - static void setManualFeedrate(ExtUI::extruder_t, float increment_mm); + static void setManualFeedrate(const ExtUI::axis_t, const_float_t increment_mm); + static void setManualFeedrate(const ExtUI::extruder_t, const_float_t increment_mm); static void onEntry(); - static bool onTouchHeld(uint8_t tag); + static bool onTouchHeld(const uint8_t tag); }; class MoveAxisScreen : public BaseMoveAxisScreen, public CachedScreen { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/screens.h index b88e51757690..c200931eec51 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/screens.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/screens.h @@ -74,7 +74,7 @@ enum { #if ENABLED(CASE_LIGHT_ENABLE) CASE_LIGHT_SCREEN_CACHE, #endif - #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) + #if ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) FILAMENT_MENU_CACHE, #endif #if ENABLED(LIN_ADVANCE) @@ -83,7 +83,7 @@ enum { #if ENABLED(FILAMENT_RUNOUT_SENSOR) FILAMENT_RUNOUT_SCREEN_CACHE, #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA FILES_SCREEN_CACHE, #endif #if ENABLED(CUSTOM_MENU_MAIN) @@ -192,7 +192,7 @@ enum { #include "case_light_screen.h" #endif -#if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) +#if ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) #include "filament_menu.h" #endif @@ -204,7 +204,7 @@ enum { #include "linear_advance_screen.h" #endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "files_screen.h" #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp index f1c65357e017..ea484344bd40 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp @@ -376,10 +376,10 @@ void StatusScreen::loadBitmaps() { // Load the bitmaps for the status screen using namespace Theme; constexpr uint32_t base = ftdi_memory_map::RAM_G; - CLCD::mem_write_pgm(base + TD_Icon_Info.RAMG_offset, TD_Icon, sizeof(TD_Icon)); - CLCD::mem_write_pgm(base + Extruder_Icon_Info.RAMG_offset, Extruder_Icon, sizeof(Extruder_Icon)); - CLCD::mem_write_pgm(base + Bed_Heat_Icon_Info.RAMG_offset, Bed_Heat_Icon, sizeof(Bed_Heat_Icon)); - CLCD::mem_write_pgm(base + Fan_Icon_Info.RAMG_offset, Fan_Icon, sizeof(Fan_Icon)); + CLCD::mem_write_xbm(base + TD_Icon_Info.RAMG_offset, TD_Icon, sizeof(TD_Icon)); + CLCD::mem_write_xbm(base + Extruder_Icon_Info.RAMG_offset, Extruder_Icon, sizeof(Extruder_Icon)); + CLCD::mem_write_xbm(base + Bed_Heat_Icon_Info.RAMG_offset, Bed_Heat_Icon, sizeof(Bed_Heat_Icon)); + CLCD::mem_write_xbm(base + Fan_Icon_Info.RAMG_offset, Fan_Icon, sizeof(Fan_Icon)); // Load fonts for internationalization #if ENABLED(TOUCH_UI_USE_UTF8) @@ -417,7 +417,7 @@ bool StatusScreen::onTouchEnd(uint8_t tag) { using namespace ExtUI; switch (tag) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA case 3: GOTO_SCREEN(FilesScreen); break; #endif case 4: 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 2dbf2d9f06a7..04eb2acec6bc 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 @@ -66,7 +66,7 @@ void TemperatureScreen::onRedraw(draw_mode_t what) { #if HAS_HEATED_CHAMBER w.adjuster( 22, GET_TEXT_F(MSG_CHAMBER), getTargetTemp_celsius(CHAMBER)); #endif - #if HAS_FAN + #if HAS_FAN0 w.color(fan_speed).units(GET_TEXT_F(MSG_UNITS_PERCENT)); w.adjuster( 10, GET_TEXT_F(MSG_FAN_SPEED), getTargetFan_percent(FAN0)); #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp index 0370c4417478..259f6d5b89ef 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp @@ -74,11 +74,11 @@ void TuneMenu::onRedraw(draw_mode_t what) { .tag(2).button(TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE)) .enabled(!sdOrHostPrinting || sdOrHostPaused) .tag(3).button(FIL_CHANGE_POS, GET_TEXT_F(MSG_FILAMENTCHANGE)) - .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) + .enabled(ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) .tag(9).button(FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) #if ENABLED(BABYSTEPPING) && HAS_MULTI_HOTEND .tag(4).button(NUDGE_NOZ_POS, GET_TEXT_F(MSG_NUDGE_NOZZLE)) - #elif BOTH(HAS_LEVELING, HAS_BED_PROBE) + #elif ALL(HAS_LEVELING, HAS_BED_PROBE) .tag(4).button(NUDGE_NOZ_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) #endif .tag(5).button(SPEED_POS, GET_TEXT_F(MSG_PRINT_SPEED)) @@ -105,7 +105,7 @@ bool TuneMenu::onTouchEnd(uint8_t tag) { case 4: #if ENABLED(BABYSTEPPING) && HAS_MULTI_HOTEND GOTO_SCREEN(NudgeNozzleScreen); - #elif BOTH(HAS_LEVELING, HAS_BED_PROBE) + #elif ALL(HAS_LEVELING, HAS_BED_PROBE) GOTO_SCREEN(ZOffsetScreen); #endif break; @@ -117,7 +117,7 @@ bool TuneMenu::onTouchEnd(uint8_t tag) { current_screen.forget(); PUSH_SCREEN(StatusScreen); break; - #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) + #if ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) case 9: GOTO_SCREEN(FilamentMenu); break; #endif #if ENABLED(CASE_LIGHT_ENABLE) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp index 9ff738e45c19..c087bf41b58c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp @@ -19,7 +19,6 @@ * location: . * ****************************************************************************/ - #include "../../../../MarlinCore.h" #if ENABLED(TOUCH_UI_FTDI_EVE) #include "language.h" 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 05e625842ad9..6deb5b47587e 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 @@ -91,7 +91,6 @@ namespace Language_en { LSTR MSG_IDLE = u8"idle"; LSTR MSG_SET_MAXIMUM = u8"Set Maximum"; LSTR MSG_PRINT_SPEED = u8"Print Speed"; - LSTR MSG_LINEAR_ADVANCE = u8"Linear Advance"; LSTR MSG_LINEAR_ADVANCE_K = u8"K"; LSTR MSG_LINEAR_ADVANCE_K1 = u8"K E1"; LSTR MSG_LINEAR_ADVANCE_K2 = u8"K E2"; @@ -148,6 +147,8 @@ namespace Language_en { LSTR MSG_MOVE_Z_TO_TOP = u8"Raise Z to Top"; LSTR MSG_MAX_SPEED_NO_UNITS = u8"Max Speed"; + //LSTR MSG_FTDI_HEATER_TIMEOUT = u8"Idle timeout, temperature decreased. Press Okay to reheat and again to resume."; + #if ENABLED(TOUCH_UI_LULZBOT_BIO) LSTR MSG_MOVE_TO_HOME = u8"Move to Home"; LSTR MSG_RAISE_PLUNGER = u8"Raise Plunger"; @@ -170,8 +171,6 @@ namespace Language_en { LSTR MSG_PREHEAT_CHOCOLATE = u8"Preheat Chocolate"; LSTR MSG_PREHEAT_FINISHED = u8"Preheat finished"; LSTR MSG_PREHEAT = u8"Preheat"; - LSTR MSG_BUTTON_PAUSE = u8"Pause"; - LSTR MSG_BUTTON_RESUME = u8"Resume"; LSTR MSG_ELAPSED_PRINT = u8"Elapsed Print"; LSTR MSG_XYZ_MOVE = u8"XYZ Move"; LSTR MSG_E_MOVE = u8"Extrusion Move"; 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 34026f4a26e6..396349384159 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 @@ -42,13 +42,13 @@ #elif ENABLED(CR10_TFT_PINMAP) // FYSETC S6 - STM32F4 - with TOUCH_UI_ULTIPANEL #define CLCD_USE_SOFT_SPI - #define CLCD_SOFT_SPI_SCLK LCD_PINS_D4 // PORTA1 Pin 6 - #define CLCD_SOFT_SPI_MOSI LCD_PINS_ENABLE // PORTC1 Pin 8 - #define CLCD_SPI_CS LCD_PINS_RS // PORTA3 Pin 7 - #define CLCD_SOFT_SPI_MISO 16 // PORTC0 BTN_ENC Pin 2 - #define CLCD_MOD_RESET 11 // PORTD3 BTN_EN1 Pin 3 - #define CLCD_AUX_0 10 // PORTD2 BTN_EN2 Pin 5 - #define CLCD_AUX_1 BEEPER_PIN // PORTA4 Pin 1 + #define CLCD_SOFT_SPI_SCLK LCD_PINS_D4 // PORTA1 Pin 6 + #define CLCD_SOFT_SPI_MOSI LCD_PINS_EN // PORTC1 Pin 8 + #define CLCD_SPI_CS LCD_PINS_RS // PORTA3 Pin 7 + #define CLCD_SOFT_SPI_MISO 16 // PORTC0 BTN_ENC Pin 2 + #define CLCD_MOD_RESET 11 // PORTD3 BTN_EN1 Pin 3 + #define CLCD_AUX_0 10 // PORTD2 BTN_EN2 Pin 5 + #define CLCD_AUX_1 BEEPER_PIN // PORTA4 Pin 1 #elif ENABLED(AO_EXP1_DEPRECATED_PINMAP) @@ -60,7 +60,7 @@ #define CLCD_MOD_RESET LCD_PINS_D4 #define CLCD_SPI_CS LCD_PINS_D5 - #define CLCD_AUX_0 LCD_PINS_ENABLE + #define CLCD_AUX_0 LCD_PINS_EN #define CLCD_AUX_1 BTN_ENC #define CLCD_AUX_2 BEEPER_PIN @@ -93,7 +93,7 @@ * functionality over software SPI. */ - #define CLCD_MOD_RESET LCD_PINS_ENABLE + #define CLCD_MOD_RESET LCD_PINS_EN #define CLCD_SPI_CS LCD_PINS_D4 #define CLCD_USE_SOFT_SPI @@ -137,7 +137,7 @@ #define CLCD_SPI_CS BTN_EN1 #define CLCD_MOD_RESET BTN_EN2 - #if MB(EINSY_RAMBO, EINSY_RETRO) && DISABLED(SDSUPPORT) + #if MB(EINSY_RAMBO, EINSY_RETRO) && !HAS_MEDIA #define CLCD_SPI_EXTRA_CS SDSS #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screen_data.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screen_data.h index 48a0c1a96440..7b0a0d25e9aa 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screen_data.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screen_data.h @@ -62,9 +62,11 @@ union screen_data_t { DECL_DATA_IF_INCLUDED(FTDI_Z_OFFSET_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_BASE_NUMERIC_ADJ_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_ALERT_DIALOG_BOX) + DECL_DATA_IF_INCLUDED(COCOA_STATUS_SCREEN) DECL_DATA_IF_INCLUDED(COCOA_PREHEAT_SCREEN) DECL_DATA_IF_INCLUDED(COCOA_LOAD_CHOCOLATE_SCREEN) DECL_DATA_IF_INCLUDED(COCOA_FILES_SCREEN) + DECL_DATA_IF_INCLUDED(COCOA_Z_OFFSET_WIZARD) }; extern screen_data_t screen_data; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp index ed210369c4f2..b17ac9c7cbaa 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp @@ -26,7 +26,6 @@ #include "screens.h" tiny_timer_t refresh_timer; - /** * DECL_SCREEN_IF_INCLUDED allows for a concise * definition of SCREEN_TABLE: @@ -118,6 +117,10 @@ SCREEN_TABLE { DECL_SCREEN_IF_INCLUDED(COCOA_MOVE_E_SCREEN) DECL_SCREEN_IF_INCLUDED(COCOA_CONFIRM_START_PRINT) DECL_SCREEN_IF_INCLUDED(COCOA_FILES_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_Z_OFFSET_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_Z_OFFSET_WIZARD) + DECL_SCREEN_IF_INCLUDED(COCOA_ABOUT_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_STATISTICS_SCREEN) }; SCREEN_TABLE_POST diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h index c194225d99ae..a2729979c6bf 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bitmaps.h @@ -37,25 +37,25 @@ namespace Theme { }; constexpr PROGMEM unsigned char Extruder_Icon[69] = { - 0x3F, 0xFF, 0xFC, - 0x7F, 0xFF, 0xFE, - 0xC0, 0x00, 0x03, - 0xC0, 0x00, 0x03, - 0xC0, 0x00, 0x03, - 0xC0, 0x00, 0x03, - 0x7F, 0xFF, 0xFE, - 0x3F, 0xFF, 0xFC, - 0x3F, 0xFF, 0xFC, - 0x7F, 0xFF, 0xFE, - 0xC0, 0x00, 0x03, - 0xC0, 0x00, 0x03, - 0xC0, 0x00, 0x03, - 0xC0, 0x00, 0x03, - 0x7F, 0xFF, 0xFE, - 0x7F, 0xFF, 0xFE, - 0x07, 0xFF, 0xE0, - 0x03, 0xFF, 0xC0, - 0x01, 0x81, 0x80, + 0xFC, 0xFF, 0x3F, + 0xFE, 0xFF, 0x7F, + 0x03, 0x00, 0xC0, + 0x03, 0x00, 0xC0, + 0x03, 0x00, 0xC0, + 0x03, 0x00, 0xC0, + 0xFE, 0xFF, 0x7F, + 0xFC, 0xFF, 0x3F, + 0xFC, 0xFF, 0x3F, + 0xFE, 0xFF, 0x7F, + 0x03, 0x00, 0xC0, + 0x03, 0x00, 0xC0, + 0x03, 0x00, 0xC0, + 0x03, 0x00, 0xC0, + 0xFE, 0xFF, 0x7F, + 0xFE, 0xFF, 0x7F, + 0xE0, 0xFF, 0x07, + 0xC0, 0xFF, 0x03, + 0x80, 0x81, 0x01, 0x00, 0xC3, 0x00, 0x00, 0x66, 0x00, 0x00, 0x3C, 0x00, @@ -74,28 +74,28 @@ namespace Theme { }; constexpr PROGMEM unsigned char Bed_Heat_Icon[92] = { - 0x01, 0x81, 0x81, 0x80, - 0x01, 0x81, 0x81, 0x80, - 0x00, 0xC0, 0xC0, 0xC0, - 0x00, 0xC0, 0xC0, 0xC0, - 0x00, 0x60, 0x60, 0x60, - 0x00, 0x60, 0x60, 0x60, - 0x00, 0xC0, 0xC0, 0xC0, - 0x00, 0xC0, 0xC0, 0xC0, - 0x01, 0x81, 0x81, 0x80, - 0x01, 0x81, 0x81, 0x80, - 0x03, 0x03, 0x03, 0x00, - 0x03, 0x03, 0x03, 0x00, - 0x06, 0x06, 0x06, 0x00, - 0x06, 0x06, 0x06, 0x00, - 0x03, 0x03, 0x03, 0x00, - 0x03, 0x03, 0x03, 0x00, - 0x01, 0x81, 0x81, 0x80, - 0x01, 0x81, 0x81, 0x80, + 0x80, 0x81, 0x81, 0x01, + 0x80, 0x81, 0x81, 0x01, + 0x00, 0x03, 0x03, 0x03, + 0x00, 0x03, 0x03, 0x03, + 0x00, 0x06, 0x06, 0x06, + 0x00, 0x06, 0x06, 0x06, + 0x00, 0x03, 0x03, 0x03, + 0x00, 0x03, 0x03, 0x03, + 0x80, 0x81, 0x81, 0x01, + 0x80, 0x81, 0x81, 0x01, + 0xC0, 0xC0, 0xC0, 0x00, + 0xC0, 0xC0, 0xC0, 0x00, + 0x60, 0x60, 0x60, 0x00, + 0x60, 0x60, 0x60, 0x00, + 0xC0, 0xC0, 0xC0, 0x00, + 0xC0, 0xC0, 0xC0, 0x00, + 0x80, 0x81, 0x81, 0x01, + 0x80, 0x81, 0x81, 0x01, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, - 0xC0, 0x00, 0x00, 0x03, + 0x03, 0x00, 0x00, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF }; @@ -113,34 +113,34 @@ namespace Theme { constexpr PROGMEM unsigned char Fan_Icon[128] = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, - 0xF8, 0x00, 0x00, 0x1F, - 0xF0, 0x03, 0xF8, 0x0F, - 0xE0, 0x07, 0xF0, 0x07, - 0xC0, 0x0F, 0xE0, 0x03, - 0xC0, 0x1F, 0xE0, 0x03, - 0xC0, 0x1F, 0xE0, 0x03, - 0xC0, 0x0F, 0xE0, 0x03, - 0xC0, 0x07, 0xE0, 0x03, - 0xC0, 0x03, 0xC0, 0x03, - 0xD0, 0x00, 0x00, 0xC3, - 0xD8, 0x03, 0xC1, 0xE3, - 0xDF, 0xC7, 0xE3, 0xF3, - 0xDF, 0xEF, 0xF7, 0xFB, - 0xDF, 0xEF, 0xF7, 0xFB, - 0xDF, 0xEF, 0xF7, 0xFB, - 0xDF, 0xEF, 0xF7, 0xFB, - 0xCF, 0xC7, 0xE3, 0xFB, - 0xC7, 0x83, 0xC0, 0x1B, - 0xC3, 0x00, 0x00, 0x0B, - 0xC0, 0x03, 0xC0, 0x03, - 0xC0, 0x07, 0xE0, 0x03, - 0xC0, 0x07, 0xF0, 0x03, - 0xC0, 0x07, 0xF8, 0x03, - 0xC0, 0x07, 0xF8, 0x03, - 0xC0, 0x07, 0xF0, 0x03, - 0xE0, 0x0F, 0xE0, 0x07, - 0xF0, 0x1F, 0xC0, 0x0F, - 0xF8, 0x00, 0x00, 0x1F, + 0x1F, 0x00, 0x00, 0xF8, + 0x0F, 0xC0, 0x1F, 0xF0, + 0x07, 0xE0, 0x0F, 0xE0, + 0x03, 0xF0, 0x07, 0xC0, + 0x03, 0xF8, 0x07, 0xC0, + 0x03, 0xF8, 0x07, 0xC0, + 0x03, 0xF0, 0x07, 0xC0, + 0x03, 0xE0, 0x07, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, + 0x0B, 0x00, 0x00, 0xC3, + 0x1B, 0xC0, 0x83, 0xC7, + 0xFB, 0xE3, 0xC7, 0xCF, + 0xFB, 0xF7, 0xEF, 0xDF, + 0xFB, 0xF7, 0xEF, 0xDF, + 0xFB, 0xF7, 0xEF, 0xDF, + 0xFB, 0xF7, 0xEF, 0xDF, + 0xF3, 0xE3, 0xC7, 0xDF, + 0xE3, 0xC1, 0x03, 0xD8, + 0xC3, 0x00, 0x00, 0xD0, + 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xE0, 0x07, 0xC0, + 0x03, 0xE0, 0x0F, 0xC0, + 0x03, 0xE0, 0x1F, 0xC0, + 0x03, 0xE0, 0x1F, 0xC0, + 0x03, 0xE0, 0x0F, 0xC0, + 0x07, 0xF0, 0x07, 0xE0, + 0x0F, 0xF8, 0x03, 0xF0, + 0x1F, 0x00, 0x00, 0xF8, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF }; @@ -157,26 +157,26 @@ namespace Theme { }; constexpr PROGMEM unsigned char TD_Icon[140] = { - 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, // Thumb Drive Widget - 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, - 0x00, 0x60, 0x00, 0x00, 0x00, 0x03, 0x80, - 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0xC0, 0x60, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0xC0, 0x60, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0xC0, 0x60, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0xC0, 0x60, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0xC0, 0x60, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0xC0, 0x60, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0xC0, 0x60, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0xC0, 0x60, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0xC0, - 0x00, 0x60, 0x00, 0x00, 0x00, 0x03, 0x80, - 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, - 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFC, 0x00 + 0x00, 0xFE, 0xFF, 0xFF, 0xFF, 0x3F, 0x00, // Thumb Drive Widget + 0x00, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, + 0x00, 0x06, 0x00, 0x00, 0x00, 0xC0, 0x01, + 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x03, + 0xFF, 0x07, 0x00, 0x00, 0x00, 0x00, 0x03, + 0xFF, 0x07, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x03, 0x06, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x03, 0x06, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x03, 0x06, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x03, 0x06, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x03, 0x06, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x03, 0x06, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x03, 0x06, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x03, 0x06, 0x00, 0x00, 0x00, 0x00, 0x03, + 0xFF, 0x07, 0x00, 0x00, 0x00, 0x00, 0x03, + 0xFF, 0x07, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x06, 0x00, 0x00, 0x00, 0xC0, 0x01, + 0x00, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, + 0x00, 0xFE, 0xFF, 0xFF, 0xFF, 0x3F, 0x00 }; constexpr PROGMEM bitmap_info_t File_Icon_Info = { @@ -191,17 +191,17 @@ namespace Theme { }; const unsigned char File_Icon[128] PROGMEM = { - 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x40, 0x03, 0x00, 0x00, - 0x40, 0x02, 0x80, 0x00, 0x40, 0x02, 0x40, 0x00, 0x40, 0x02, 0x20, 0x00, - 0x40, 0x02, 0x10, 0x00, 0x40, 0x02, 0x08, 0x00, 0x40, 0x02, 0x04, 0x00, - 0x40, 0x02, 0x02, 0x00, 0x40, 0x03, 0xFF, 0x00, 0x40, 0x00, 0x01, 0x00, - 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, - 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, - 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, - 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, - 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, - 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, 0x40, 0x00, 0x01, 0x00, - 0x7F, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00 + 0x00, 0x00, 0x00, 0x00, 0xFE, 0x7F, 0x00, 0x00, 0x02, 0xC0, 0x00, 0x00, + 0x02, 0x40, 0x01, 0x00, 0x02, 0x40, 0x02, 0x00, 0x02, 0x40, 0x04, 0x00, + 0x02, 0x40, 0x08, 0x00, 0x02, 0x40, 0x10, 0x00, 0x02, 0x40, 0x20, 0x00, + 0x02, 0x40, 0x40, 0x00, 0x02, 0xC0, 0xFF, 0x00, 0x02, 0x00, 0x80, 0x00, + 0x02, 0x00, 0x80, 0x00, 0x02, 0x00, 0x80, 0x00, 0x02, 0x00, 0x80, 0x00, + 0x02, 0x00, 0x80, 0x00, 0x02, 0x00, 0x80, 0x00, 0x02, 0x00, 0x80, 0x00, + 0x02, 0x00, 0x80, 0x00, 0x02, 0x00, 0x80, 0x00, 0x02, 0x00, 0x80, 0x00, + 0x02, 0x00, 0x80, 0x00, 0x02, 0x00, 0x80, 0x00, 0x02, 0x00, 0x80, 0x00, + 0x02, 0x00, 0x80, 0x00, 0x02, 0x00, 0x80, 0x00, 0x02, 0x00, 0x80, 0x00, + 0x02, 0x00, 0x80, 0x00, 0x02, 0x00, 0x80, 0x00, 0x02, 0x00, 0x80, 0x00, + 0xFE, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00 }; constexpr PROGMEM bitmap_info_t Clock_Icon_Info = { @@ -216,17 +216,17 @@ namespace Theme { }; const unsigned char Clock_Icon[128] PROGMEM = { - 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x7E, 0x7E, 0x00, - 0x00, 0xE0, 0x07, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x07, 0x01, 0x00, 0xE0, - 0x0C, 0x01, 0x80, 0x70, 0x0C, 0x01, 0x80, 0x30, 0x18, 0x01, 0x80, 0x18, - 0x30, 0x01, 0x80, 0x08, 0x30, 0x01, 0x80, 0x0C, 0x20, 0x01, 0x80, 0x0C, - 0x60, 0x01, 0x80, 0x04, 0x60, 0x01, 0x80, 0x06, 0x60, 0x01, 0x80, 0x06, - 0x60, 0x01, 0xFF, 0x06, 0x60, 0x01, 0xFF, 0x06, 0x60, 0x00, 0x00, 0x06, - 0x60, 0x00, 0x00, 0x06, 0x60, 0x00, 0x00, 0x04, 0x20, 0x00, 0x00, 0x0C, - 0x30, 0x00, 0x00, 0x0C, 0x30, 0x00, 0x00, 0x08, 0x18, 0x00, 0x00, 0x18, - 0x0C, 0x00, 0x00, 0x30, 0x0E, 0x00, 0x00, 0x70, 0x07, 0x00, 0x00, 0xE0, - 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x07, 0x00, 0x00, 0x7F, 0xFE, 0x00, - 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00 + 0x00, 0x00, 0x00, 0x00, 0x00, 0xF0, 0x0F, 0x00, 0x00, 0x7E, 0x7E, 0x00, + 0x00, 0x07, 0xE0, 0x00, 0xC0, 0x01, 0x80, 0x03, 0xE0, 0x80, 0x00, 0x07, + 0x30, 0x80, 0x01, 0x0E, 0x30, 0x80, 0x01, 0x0C, 0x18, 0x80, 0x01, 0x18, + 0x0C, 0x80, 0x01, 0x10, 0x0C, 0x80, 0x01, 0x30, 0x04, 0x80, 0x01, 0x30, + 0x06, 0x80, 0x01, 0x20, 0x06, 0x80, 0x01, 0x60, 0x06, 0x80, 0x01, 0x60, + 0x06, 0x80, 0xFF, 0x60, 0x06, 0x80, 0xFF, 0x60, 0x06, 0x00, 0x00, 0x60, + 0x06, 0x00, 0x00, 0x60, 0x06, 0x00, 0x00, 0x20, 0x04, 0x00, 0x00, 0x30, + 0x0C, 0x00, 0x00, 0x30, 0x0C, 0x00, 0x00, 0x10, 0x18, 0x00, 0x00, 0x18, + 0x30, 0x00, 0x00, 0x0C, 0x70, 0x00, 0x00, 0x0E, 0xE0, 0x00, 0x00, 0x07, + 0xC0, 0x01, 0x80, 0x03, 0x00, 0x07, 0xE0, 0x00, 0x00, 0xFE, 0x7F, 0x00, + 0x00, 0xF0, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00 }; constexpr PROGMEM bitmap_info_t Light_Bulb_Info = { @@ -241,17 +241,42 @@ namespace Theme { }; const unsigned char Light_Bulb[128] PROGMEM = { - 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, - 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x04, 0x00, 0x00, 0x40, - 0x02, 0x00, 0x00, 0x80, 0x01, 0x00, 0x01, 0x00, 0x00, 0x80, 0x02, 0x00, - 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x18, 0x30, 0x00, 0x00, 0x36, 0x18, 0x00, - 0x00, 0x2C, 0x08, 0x00, 0x00, 0x58, 0x04, 0x00, 0x00, 0x50, 0x04, 0x00, - 0x7C, 0x50, 0x04, 0x7C, 0x00, 0x40, 0x04, 0x00, 0x00, 0x40, 0x04, 0x00, - 0x00, 0x60, 0x0C, 0x00, 0x00, 0x20, 0x08, 0x00, 0x00, 0x10, 0x10, 0x00, - 0x00, 0x10, 0x10, 0x00, 0x00, 0x88, 0x22, 0x00, 0x01, 0x08, 0x21, 0x00, - 0x02, 0x08, 0x20, 0x80, 0x04, 0x0F, 0xE0, 0x40, 0x00, 0x07, 0xC0, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x03, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, + 0x00, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x20, 0x00, 0x00, 0x02, + 0x40, 0x00, 0x00, 0x01, 0x80, 0x00, 0x80, 0x00, 0x00, 0x01, 0x40, 0x00, + 0x00, 0xF0, 0x07, 0x00, 0x00, 0x18, 0x0C, 0x00, 0x00, 0x6C, 0x18, 0x00, + 0x00, 0x34, 0x10, 0x00, 0x00, 0x1A, 0x20, 0x00, 0x00, 0x0A, 0x20, 0x00, + 0x3E, 0x0A, 0x20, 0x3E, 0x00, 0x02, 0x20, 0x00, 0x00, 0x02, 0x20, 0x00, + 0x00, 0x06, 0x30, 0x00, 0x00, 0x04, 0x10, 0x00, 0x00, 0x08, 0x08, 0x00, + 0x00, 0x08, 0x08, 0x00, 0x00, 0x11, 0x44, 0x00, 0x80, 0x10, 0x84, 0x00, + 0x40, 0x10, 0x04, 0x01, 0x20, 0xF0, 0x07, 0x02, 0x00, 0xE0, 0x03, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0xE0, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0xC0, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00 + }; + + constexpr PROGMEM bitmap_info_t Chamber_Icon_Info = { + .format = L1, + .linestride = 4, + .filter = BILINEAR, + .wrapx = BORDER, + .wrapy = BORDER, + .RAMG_offset = 8813, + .width = 32, + .height = 32, + }; + + const unsigned char Chamber_Icon[128] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x1F, 0x00, 0x00, 0xF8, + 0x0F, 0x00, 0x00, 0xF0, 0x07, 0x00, 0x00, 0xE0, 0x03, 0x00, 0x00, 0xC0, + 0x03, 0x00, 0x00, 0xC0, 0x83, 0x81, 0x81, 0xC1, 0x83, 0x81, 0x81, 0xC1, + 0x03, 0x03, 0x03, 0xC3, 0x03, 0x03, 0x03, 0xC3, 0x03, 0x06, 0x06, 0xC6, + 0x03, 0x06, 0x06, 0xC6, 0x03, 0x03, 0x03, 0xC3, 0x03, 0x03, 0x03, 0xC3, + 0x83, 0x81, 0x81, 0xC1, 0x83, 0x81, 0x81, 0xC1, 0xC3, 0xC0, 0xC0, 0xC0, + 0xC3, 0xC0, 0xC0, 0xC0, 0x63, 0x60, 0x60, 0xC0, 0x63, 0x60, 0x60, 0xC0, + 0xC3, 0xC0, 0xC0, 0xC0, 0xC3, 0xC0, 0xC0, 0xC0, 0x83, 0x81, 0x81, 0xC1, + 0x83, 0x81, 0x81, 0xC1, 0x03, 0x00, 0x00, 0xC0, 0x03, 0x00, 0x00, 0xC0, + 0x07, 0x00, 0x00, 0xE0, 0x0F, 0x00, 0x00, 0xF0, 0x1F, 0x00, 0x00, 0xF8, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF }; constexpr PROGMEM uint32_t UTF8_FONT_OFFSET = 10000; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h deleted file mode 100644 index 169a306afcaa..000000000000 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h +++ /dev/null @@ -1,41 +0,0 @@ -/**************************************************************************** - * This program is free software: you can redistribute it and/or modify * - * it under the terms of the GNU General Public License as published by * - * the Free Software Foundation, either version 3 of the License, or * - * (at your option) any later version. * - * * - * This program is distributed in the hope that it will be useful, * - * but WITHOUT ANY WARRANTY; without even the implied warranty of * - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * - * GNU General Public License for more details. * - * * - * To view a copy of the GNU General Public License, go to the following * - * location: . * - ****************************************************************************/ - -/** - * This file was auto-generated using "svg2cpp.pl" - * - * The encoding consists of x,y pairs with the min and max scaled to - * 0x0000 and 0xFFFE. A single 0xFFFF in the data stream indicates the - * start of a new closed path. - */ -#pragma once - -constexpr float x_min = 0.000000, x_max = 272.000000, - y_min = 0.000000, y_max = 480.000000; - -const PROGMEM uint16_t logo_green[] = {0x8048, 0x46D9, 0x27BC, 0x9DBA, 0xD8D3, 0x9DBA}; -const PROGMEM uint16_t logo_mark[] = {0xDB9F, 0xAC0C, 0xDA6F, 0xAC2D, 0xD970, 0xAC91, 0xD8C0, 0xAD23, 0xD885, 0xADCF, 0xD8C0, 0xAE7A, 0xD970, 0xAF0C, 0xDA6F, 0xAF6F, 0xDB9F, 0xAF8F, 0xDCCE, 0xAF6F, 0xDDD0, 0xAF0C, 0xDE7D, 0xAE7B, 0xDEB9, 0xADCF, 0xDE7D, 0xAD22, 0xDDD0, 0xAC91, 0xDCCE, 0xAC2D, 0xFFFF, 0xDB9F, 0xABC3, 0xDCFE, 0xABEA, 0xDE28, 0xAC5E, 0xDEF1, 0xAD06, 0xDF36, 0xADCF, 0xDEF1, 0xAE95, 0xDE28, 0xAF3E, 0xDCFE, 0xAFB1, 0xDB9F, 0xAFD8, 0xDA3F, 0xAFB1, 0xD916, 0xAF3E, 0xD849, 0xAE95, 0xD808, 0xADCF, 0xD849, 0xAD06, 0xD916, 0xAC5E, 0xDA3F, 0xABEA, 0xFFFF, 0xDB7D, 0xACE6, 0xDAE4, 0xACE6, 0xDAE4, 0xADA9, 0xDB7D, 0xADA9, 0xDC3B, 0xAD94, 0xDC71, 0xAD48, 0xDC3B, 0xACFD, 0xFFFF, 0xDB85, 0xAC9E, 0xDCCB, 0xACC8, 0xDD37, 0xAD47, 0xDCF6, 0xADAC, 0xDC3E, 0xADDE, 0xDC85, 0xADFF, 0xDCE8, 0xAE4E, 0xDD92, 0xAEEA, 0xDCBD, 0xAEEA, 0xDC1E, 0xAE58, 0xDBA7, 0xAE03, 0xDB36, 0xADEF, 0xDAE4, 0xADEF, 0xDAE4, 0xAEEA, 0xDA26, 0xAEEA, 0xDA26, 0xAC9E}; -const PROGMEM uint16_t logo_type[] = {0xD8D5, 0xA520, 0xD8A5, 0xA563, 0xD82E, 0xA57F, 0xD348, 0xA57F, 0xD2D1, 0xA598, 0xD2A0, 0xA5D9, 0xD2A0, 0xAF7A, 0xD274, 0xAFBE, 0xD202, 0xAFDA, 0xCD37, 0xAFDA, 0xCCBF, 0xAFBE, 0xCC8F, 0xAF7A, 0xCC8F, 0xA5D9, 0xCC63, 0xA598, 0xCBF1, 0xA57F, 0xC70B, 0xA57F, 0xC694, 0xA563, 0xC664, 0xA520, 0xC664, 0xA28C, 0xC70B, 0xA22C, 0xD82E, 0xA22C, 0xD8A5, 0xA248, 0xD8D5, 0xA28C, 0xFFFF, 0xB138, 0xAC8C, 0xB952, 0xAC8C, 0xB952, 0xA57F, 0xB138, 0xA57F, 0xFFFF, 0xBF27, 0xA421, 0xBF57, 0xA476, 0xBF6D, 0xA4D0, 0xBF6D, 0xAD36, 0xBF57, 0xAD90, 0xBF27, 0xADE6, 0xBBFA, 0xAFB2, 0xBB60, 0xAFCF, 0xBABD, 0xAFDA, 0xAFCE, 0xAFDA, 0xAF30, 0xAFCF, 0xAE9A, 0xAFB2, 0xAB6E, 0xADE6, 0xAB39, 0xAD90, 0xAB28, 0xAD36, 0xAB28, 0xA4D0, 0xAB39, 0xA476, 0xAB6E, 0xA421, 0xAE9A, 0xA255, 0xAF30, 0xA239, 0xAFCE, 0xA22C, 0xBABD, 0xA22C, 0xBB60, 0xA239, 0xBBFA, 0xA255, 0xFFFF, 0x93A4, 0xACDC, 0x9CEA, 0xACDC, 0x9CEA, 0xAA34, 0x93A4, 0xAA34, 0x93A4, 0xACDC, 0xFFFF, 0x93A4, 0xA796, 0x9CEA, 0xA796, 0x9CEA, 0xA525, 0x93A4, 0xA525, 0xFFFF, 0xA227, 0xA421, 0xA258, 0xA478, 0xA26E, 0xA4D5, 0xA26E, 0xA700, 0xA24F, 0xA757, 0xA204, 0xA7A5, 0xA089, 0xA8B8, 0xA061, 0xA903, 0xA092, 0xA949, 0xA1FC, 0xAA43, 0xA24B, 0xAA91, 0xA26E, 0xAAE8, 0xA26E, 0xAD36, 0xA258, 0xAD90, 0xA227, 0xADE6, 0x9EFC, 0xAFB2, 0x9E61, 0xAFCF, 0x9DBE, 0xAFDA, 0x8ED0, 0xAFDA, 0x8E28, 0xAF7A, 0x8E28, 0xA28C, 0x8E59, 0xA248, 0x8ED0, 0xA22C, 0x9DBE, 0xA22C, 0x9E61, 0xA239, 0x9EFC, 0xA255, 0xFFFF, 0x853C, 0xA502, 0x8517, 0xA557, 0x84C9, 0xA5A2, 0x7994, 0xACC8, 0x8494, 0xACC8, 0x850A, 0xACE4, 0x853C, 0xAD27, 0x853C, 0xAF7A, 0x850A, 0xAFBE, 0x8494, 0xAFDA, 0x7371, 0xAFDA, 0x72C9, 0xAF7A, 0x72C9, 0xAD09, 0x72E8, 0xACB2, 0x7333, 0xAC64, 0x7EA5, 0xA53E, 0x73A6, 0xA53E, 0x732F, 0xA522, 0x72FE, 0xA4DF, 0x72FE, 0xA28C, 0x732F, 0xA248, 0x73A6, 0xA22C, 0x8494, 0xA22C, 0x850A, 0xA248, 0x853C, 0xA28C, 0xFFFF, 0x6B68, 0xAC87, 0x6BDB, 0xACA3, 0x6C07, 0xACE6, 0x6C07, 0xAF7A, 0x6BDB, 0xAFBE, 0x6B68, 0xAFDA, 0x5C84, 0xAFDA, 0x5BDC, 0xAF7A, 0x5BDC, 0xA28C, 0x5C84, 0xA22C, 0x6146, 0xA22C, 0x61EE, 0xA28C, 0x61EE, 0xAC2D, 0x621E, 0xAC6E, 0x6295, 0xAC87, 0xFFFF, 0x52C6, 0xA248, 0x52F7, 0xA28C, 0x52F7, 0xAD45, 0x52EE, 0xAD45, 0x52DC, 0xAD9B, 0x52B1, 0xADE6, 0x4F85, 0xAFB2, 0x4EEA, 0xAFCF, 0x4E47, 0xAFDA, 0x4359, 0xAFDA, 0x42BA, 0xAFCF, 0x4224, 0xAFB2, 0x3EF8, 0xADE6, 0x3EC3, 0xAD90, 0x3EB2, 0xAD36, 0x3EB2, 0xA28C, 0x3EE2, 0xA248, 0x3F5A, 0xA22C, 0x441B, 0xA22C, 0x4493, 0xA248, 0x44C3, 0xA28C, 0x44C3, 0xAC2D, 0x44F4, 0xAC71, 0x456B, 0xAC8C, 0x4C3E, 0xAC8C, 0x4CB1, 0xAC71, 0x4CDD, 0xAC2D, 0x4CDD, 0xA28C, 0x4D0D, 0xA248, 0x4D85, 0xA22C, 0x524F, 0xA22C, 0xFFFF, 0x3748, 0xAC87, 0x37BB, 0xACA3, 0x37E7, 0xACE6, 0x37E7, 0xAF7A, 0x37BB, 0xAFBE, 0x3748, 0xAFDA, 0x2864, 0xAFDA, 0x27BC, 0xAF7A, 0x27BC, 0xA28C, 0x2864, 0xA22C, 0x2D26, 0xA22C, 0x2DCD, 0xA28C, 0x2DCD, 0xAC2D, 0x2DFE, 0xAC6E, 0x2E75, 0xAC87}; -const PROGMEM uint16_t logo_black[] = {0x8048, 0x527A, 0x8ADE, 0x5CDE, 0x75B2, 0x5CDE, 0xFFFF, 0x8048, 0x4FF6, 0x71D9, 0x5E20, 0x8EB8, 0x5E20, 0x8048, 0x4FF6, 0xFFFF, 0x4436, 0x8D8E, 0x4ECC, 0x97F2, 0x39A0, 0x97F2, 0xFFFF, 0x4436, 0x8B0A, 0x35C8, 0x9934, 0x52A5, 0x9934, 0xFFFF, 0xBC3D, 0x8D8E, 0xC6D4, 0x97F2, 0xB1A7, 0x97F2, 0xFFFF, 0xBC3D, 0x8B0A, 0xADCE, 0x9934, 0xCAAC, 0x9934, 0xFFFF, 0x8045, 0x6778, 0x7F6D, 0x67A7, 0x7E9D, 0x689F, 0x7D49, 0x69EA, 0x7B41, 0x6A81, 0x7908, 0x6A3A, 0x7726, 0x692C, 0x75EA, 0x685A, 0x7505, 0x684C, 0x744A, 0x6899, 0x73F5, 0x69A8, 0x7345, 0x6B1A, 0x7193, 0x6BF8, 0x6F4D, 0x6C08, 0x6CFA, 0x6B45, 0x6B61, 0x6AA3, 0x6A7D, 0x6AB7, 0x69EB, 0x6B1D, 0x6A1D, 0x6C34, 0x6A22, 0x6DB8, 0x68E5, 0x6ECD, 0x66B9, 0x6F33, 0x6417, 0x6EC5, 0x6239, 0x6E5C, 0x6165, 0x6E91, 0x6108, 0x6F09, 0x61C1, 0x7018, 0x6282, 0x7196, 0x61CF, 0x72D1, 0x5FE5, 0x7384, 0x5D38, 0x7380, 0x5B4B, 0x7365, 0x5A97, 0x73B7, 0x5A74, 0x7438, 0x5B90, 0x7520, 0x5CE8, 0x7671, 0x5CCB, 0x77BB, 0x5B43, 0x78B0, 0x58B6, 0x7914, 0x56D7, 0x7944, 0x564F, 0x79AD, 0x5667, 0x7A2F, 0x57DA, 0x7AE3, 0x59B7, 0x7BF3, 0x5A31, 0x7D37, 0x5927, 0x7E5D, 0x56E0, 0x7F1E, 0x5529, 0x7F93, 0x54D7, 0x800D, 0x5529, 0x8087, 0x56E0, 0x80FD, 0x5926, 0x81BE, 0x5A30, 0x82E5, 0x59B5, 0x8428, 0x57D8, 0x8538, 0x5664, 0x85EB, 0x564C, 0x866D, 0x56D4, 0x86D7, 0x58B2, 0x8708, 0x5B3F, 0x876B, 0x5CC6, 0x8860, 0x5CE3, 0x89AA, 0x5B8B, 0x8AFC, 0x5A6D, 0x8BE3, 0x5A91, 0x8C65, 0x5B44, 0x8CB7, 0x5D32, 0x8C9C, 0x5FDE, 0x8C98, 0x61C7, 0x8D4B, 0x627A, 0x8E87, 0x61B9, 0x9005, 0x60FF, 0x9114, 0x615C, 0x918B, 0x622F, 0x91C0, 0x640E, 0x9158, 0x66B0, 0x90EA, 0x68DC, 0x9150, 0x6A18, 0x9266, 0x6A12, 0x93E9, 0x69E0, 0x9501, 0x6A72, 0x9567, 0x6B56, 0x957B, 0x6CEE, 0x94D9, 0x6F43, 0x9417, 0x7188, 0x9428, 0x7339, 0x9506, 0x73E9, 0x9678, 0x743E, 0x9787, 0x74F8, 0x97D4, 0x75DD, 0x97C6, 0x771A, 0x96F4, 0x78FB, 0x95E6, 0x7B35, 0x95A1, 0x7D3D, 0x9637, 0x7E91, 0x9782, 0x7F60, 0x987A, 0x8038, 0x98AA, 0x810F, 0x987B, 0x81DF, 0x9782, 0x8333, 0x9638, 0x853B, 0x95A1, 0x8775, 0x95E7, 0x8956, 0x96F5, 0x8A92, 0x97C8, 0x8B78, 0x97D6, 0x8C32, 0x9789, 0x8C88, 0x967A, 0x8D37, 0x9508, 0x8EE9, 0x942A, 0x912F, 0x941A, 0x9383, 0x94DD, 0x951B, 0x957F, 0x95FF, 0x956B, 0x9690, 0x9505, 0x9660, 0x93ED, 0x9659, 0x926A, 0x9797, 0x9154, 0x99C3, 0x90EF, 0x9C65, 0x915D, 0x9E43, 0x91C6, 0x9F17, 0x9191, 0x9F74, 0x9119, 0x9EBB, 0x900A, 0x9DFA, 0x8E8C, 0x9EAE, 0x8D51, 0xA098, 0x8C9E, 0xA345, 0x8CA2, 0xA531, 0x8CBE, 0xA5E5, 0x8C6B, 0xA609, 0x8BEA, 0xA4EC, 0x8B02, 0xA394, 0x89B1, 0xA3B2, 0x8867, 0xA53A, 0x8772, 0xA7C6, 0x870E, 0xA9A5, 0x86DE, 0xAA2D, 0x8675, 0xAA14, 0x85F2, 0xA8A2, 0x853F, 0xA6C5, 0x842E, 0xA64B, 0x82EB, 0xA755, 0x81C5, 0xA99C, 0x8104, 0xAB52, 0x808F, 0xABA6, 0x8015, 0xAB52, 0x7F9B, 0xA99C, 0x7F25, 0xA755, 0x7E64, 0xA64C, 0x7D3E, 0xA6C7, 0x7BFA, 0xA8A5, 0x7AEA, 0xAA18, 0x7A37, 0xAA31, 0x79B5, 0xA9A9, 0x794B, 0xA7CA, 0x791B, 0xA53C, 0x78B7, 0xA3B6, 0x77C1, 0xA39A, 0x7677, 0xA4F1, 0x7526, 0xA60E, 0x743F, 0xA5EB, 0x73BD, 0xA538, 0x736B, 0xA34B, 0x7387, 0xA09E, 0x738A, 0x9EB4, 0x72D6, 0x9E02, 0x719B, 0x9EC4, 0x701D, 0x9F7E, 0x6F0E, 0x9F20, 0x6E96, 0x9E4E, 0x6E61, 0x9C6E, 0x6ECA, 0x99CB, 0x6F37, 0x97A0, 0x6ED2, 0x9664, 0x6DBC, 0x966B, 0x6C38, 0x969B, 0x6B21, 0x960B, 0x6ABB, 0x9526, 0x6AA6, 0x938E, 0x6B48, 0x913B, 0x6C0B, 0x8EF4, 0x6BFA, 0x8D43, 0x6B1D, 0x8C94, 0x69AA, 0x8C3F, 0x689B, 0x8B85, 0x684D, 0x8A9E, 0x685C, 0x8962, 0x692E, 0x8781, 0x6A3C, 0x8546, 0x6A82, 0x833F, 0x69EA, 0x81EC, 0x68A0, 0x811C, 0x67A8, 0x8045, 0x6778, 0x8045, 0x6778, 0xFFFF, 0x8047, 0x6AA0, 0x81C8, 0x6AFA, 0x8268, 0x6BD5, 0x81C8, 0x6CAF, 0x8047, 0x6D09, 0x7EC6, 0x6CAF, 0x7E27, 0x6BD5, 0x7EC6, 0x6AFA, 0x8047, 0x6AA0, 0x8047, 0x6AA0, 0xFFFF, 0x803E, 0x6E19, 0x867C, 0x6E71, 0x8C65, 0x6F75, 0x91D7, 0x711B, 0x96AD, 0x735B, 0x9ABC, 0x762C, 0x9DA2, 0x794C, 0x9F5F, 0x7CA2, 0x9FF3, 0x8011, 0x9F5E, 0x8380, 0x9DA1, 0x86D5, 0x9ABA, 0x89F6, 0x96AB, 0x8CC7, 0x91D6, 0x8F08, 0x8C65, 0x90AD, 0x867C, 0x91B1, 0x803D, 0x9209, 0x7A00, 0x91B1, 0x7416, 0x90AD, 0x6EA6, 0x8F08, 0x69D0, 0x8CC7, 0x65D6, 0x8A0A, 0x62EE, 0x86F4, 0x6125, 0x839B, 0x6089, 0x8011, 0x6124, 0x7C88, 0x62ED, 0x792E, 0x65D6, 0x7619, 0x69CF, 0x735B, 0x6EA5, 0x711B, 0x7416, 0x6F75, 0x7A00, 0x6E71, 0x803E, 0x6E19, 0x803E, 0x6E19, 0xFFFF, 0x803E, 0x6EB2, 0x7A5A, 0x6F04, 0x74B2, 0x6FF8, 0x6F4B, 0x7194, 0x6A8F, 0x73C7, 0x66A2, 0x7681, 0x63D5, 0x7986, 0x6226, 0x7CBF, 0x6197, 0x8011, 0x6226, 0x8363, 0x63D5, 0x869C, 0x66A2, 0x89A2, 0x6A8F, 0x8C5B, 0x6F4B, 0x8E8E, 0x74B2, 0x902B, 0x7A5A, 0x911E, 0x803D, 0x9170, 0x803E, 0x9170, 0x8621, 0x911E, 0x8BCA, 0x902B, 0x9130, 0x8E8E, 0x95ED, 0x8C5B, 0x99CF, 0x89AB, 0x9CA7, 0x869C, 0x9E55, 0x8367, 0x9EE5, 0x8011, 0x9E55, 0x7CBB, 0x9CA7, 0x7986, 0x99CF, 0x7677, 0x95ED, 0x73C7, 0x9130, 0x7194, 0x8BCA, 0x6FF8, 0x8621, 0x6F04, 0x803E, 0x6EB2, 0x803E, 0x6EB2, 0xFFFF, 0x80BC, 0x6FD7, 0x80AF, 0x71D8, 0x7FC8, 0x71D9, 0x7FB7, 0x6FD8, 0x80BC, 0x6FD7, 0x80BC, 0x6FD7, 0xFFFF, 0x83CB, 0x6FF6, 0x84CD, 0x700B, 0x843E, 0x7206, 0x835B, 0x71F4, 0xFFFF, 0x7CA9, 0x6FF8, 0x7D1A, 0x71F5, 0x7C37, 0x7207, 0x7BA7, 0x700D, 0x7CA9, 0x6FF8, 0x7CA9, 0x6FF8, 0xFFFF, 0x87CD, 0x7068, 0x88C7, 0x7092, 0x87BA, 0x727C, 0x86DF, 0x7258, 0xFFFF, 0x78A8, 0x706B, 0x7997, 0x725A, 0x78BA, 0x727E, 0x77AD, 0x7095, 0x78A8, 0x706B, 0x78A8, 0x706B, 0xFFFF, 0x6700, 0x708A, 0x6880, 0x70E5, 0x6920, 0x71BF, 0x6880, 0x7299, 0x66FF, 0x72F4, 0x657F, 0x7299, 0x64E0, 0x71BF, 0x657F, 0x70E4, 0x6700, 0x708A, 0x6700, 0x708A, 0xFFFF, 0x998D, 0x708C, 0x9B0E, 0x70E6, 0x9BAE, 0x71C0, 0x9B0E, 0x729B, 0x998D, 0x72F6, 0x980D, 0x729B, 0x976E, 0x71C1, 0x980D, 0x70E7, 0x998D, 0x708C, 0x998D, 0x708C, 0xFFFF, 0x8BA7, 0x712C, 0x8C95, 0x716A, 0x8B10, 0x7339, 0x8A3F, 0x7303, 0x8BA7, 0x712C, 0xFFFF, 0x74CE, 0x712F, 0x7635, 0x7307, 0x7564, 0x733C, 0x73DE, 0x716D, 0x74CE, 0x712F, 0x74CE, 0x712F, 0xFFFF, 0x8F47, 0x723F, 0x9023, 0x728E, 0x8E2D, 0x743A, 0x8D6B, 0x73F4, 0x8F47, 0x723F, 0xFFFF, 0x712D, 0x7242, 0x7308, 0x73F7, 0x7248, 0x743D, 0x7050, 0x7292, 0x712D, 0x7242, 0x712D, 0x7242, 0xFFFF, 0x803E, 0x72F6, 0x891B, 0x73F4, 0x909A, 0x76CC, 0x959F, 0x7B0B, 0x975E, 0x8011, 0x959F, 0x8517, 0x909A, 0x8957, 0x891B, 0x8C2E, 0x803E, 0x8D2B, 0x7761, 0x8C2E, 0x6FE2, 0x8957, 0x6ADD, 0x8517, 0x691E, 0x8011, 0x6ADD, 0x7B0B, 0x6FE2, 0x76CC, 0x7761, 0x73F4, 0x803E, 0x72F6, 0x803E, 0x72F6, 0xFFFF, 0x803E, 0x738F, 0x77C8, 0x7481, 0x70A0, 0x7738, 0x6BD7, 0x7B46, 0x6A2C, 0x8011, 0x6BD7, 0x84DC, 0x70A1, 0x88EA, 0x77C9, 0x8BA1, 0x803E, 0x8C93, 0x88B4, 0x8BA1, 0x8FDB, 0x88EA, 0x94A5, 0x84DD, 0x9650, 0x8011, 0x94A5, 0x7B46, 0x8FDB, 0x7738, 0x88B4, 0x7481, 0x803E, 0x738F, 0x803E, 0x738F, 0xFFFF, 0x929B, 0x739A, 0x935C, 0x73FA, 0x9100, 0x7578, 0x905A, 0x7527, 0x9175, 0x745E, 0xFFFF, 0x6DDC, 0x739D, 0x7022, 0x7527, 0x6F74, 0x757C, 0x6D16, 0x73FF, 0x6DDC, 0x739D, 0x6DDC, 0x739D, 0xFFFF, 0x9589, 0x7533, 0x9634, 0x75A4, 0x937E, 0x76ED, 0x92E8, 0x768B, 0xFFFF, 0x6AEB, 0x7539, 0x6D8D, 0x7690, 0x6CFB, 0x76F0, 0x6CEC, 0x76FA, 0x6BED, 0x7674, 0x6A40, 0x75A9, 0x6A45, 0x75A7, 0x6AEB, 0x7539, 0x6AEB, 0x7539, 0xFFFF, 0x980B, 0x7707, 0x989A, 0x7784, 0x9597, 0x7892, 0x951A, 0x7825, 0xFFFF, 0x686A, 0x770C, 0x6B5B, 0x782A, 0x6ADF, 0x7897, 0x67DD, 0x7788, 0x686A, 0x770C, 0x686A, 0x770C, 0xFFFF, 0x9A12, 0x790A, 0x9A7E, 0x7991, 0x9740, 0x7A5E, 0x96E1, 0x79E8, 0x9A12, 0x790A, 0xFFFF, 0x6664, 0x790F, 0x6996, 0x79ED, 0x6937, 0x7A63, 0x65F9, 0x7996, 0x6664, 0x790F, 0x6664, 0x790F, 0xFFFF, 0x9B91, 0x7B32, 0x9BDB, 0x7BC1, 0x9870, 0x7C48, 0x9831, 0x7BCB, 0xFFFF, 0x64E6, 0x7B37, 0x6847, 0x7BD0, 0x6807, 0x7C4C, 0x649D, 0x7BC5, 0x64E6, 0x7B37, 0x64E6, 0x7B37, 0xFFFF, 0x9C82, 0x7D72, 0x9CA7, 0x7E06, 0x9925, 0x7E46, 0x9903, 0x7DC5, 0xFFFF, 0x63F7, 0x7D78, 0x6776, 0x7DC9, 0x6756, 0x7E49, 0x63D3, 0x7E0A, 0x63F7, 0x7D78, 0x63F7, 0x7D78, 0xFFFF, 0x5C87, 0x7EDB, 0x5E08, 0x7F35, 0x5EA8, 0x800F, 0x5E08, 0x80E9, 0x5C87, 0x8144, 0x5C85, 0x8144, 0x5B06, 0x80E9, 0x5A67, 0x800F, 0x5B06, 0x7F35, 0x5C87, 0x7EDB, 0x5C87, 0x7EDB, 0xFFFF, 0xA402, 0x7EDE, 0xA583, 0x7F38, 0xA623, 0x8011, 0xA623, 0x8013, 0xA583, 0x80EC, 0xA402, 0x8147, 0xA281, 0x80ED, 0xA1E2, 0x8013, 0xA281, 0x7F38, 0xA402, 0x7EDE, 0xA402, 0x7EDE, 0xFFFF, 0x9CE0, 0x7FC0, 0x9CE0, 0x8055, 0x9957, 0x804D, 0x9957, 0x7FCB, 0xFFFF, 0x639D, 0x7FC5, 0x6726, 0x7FCE, 0x6726, 0x8051, 0x639D, 0x805A, 0x639D, 0x7FC5, 0x639D, 0x7FC5, 0xFFFF, 0x9927, 0x81D1, 0x9CAA, 0x8210, 0x9C87, 0x82A2, 0x9907, 0x8252, 0x9927, 0x81D1, 0x9927, 0x81D1, 0xFFFF, 0x6757, 0x81D5, 0x6777, 0x8255, 0x63F9, 0x82A7, 0x63D4, 0x8214, 0xFFFF, 0x9877, 0x83CF, 0x9BE2, 0x8455, 0x9B99, 0x84E3, 0x9838, 0x844C, 0x9877, 0x83CF, 0x9877, 0x83CF, 0xFFFF, 0x6808, 0x83D3, 0x6848, 0x8450, 0x64E7, 0x84E8, 0x649E, 0x845A, 0xFFFF, 0x9749, 0x85B9, 0x9A88, 0x8684, 0x9A1D, 0x870C, 0x96EB, 0x862E, 0x9749, 0x85B9, 0x9749, 0x85B9, 0xFFFF, 0x6938, 0x85BD, 0x6997, 0x8634, 0x6665, 0x8710, 0x65F9, 0x8689, 0xFFFF, 0x95A2, 0x8785, 0x98A5, 0x8892, 0x9818, 0x890F, 0x9527, 0x87F2, 0x95A2, 0x8785, 0x95A2, 0x8785, 0xFFFF, 0x6ADF, 0x878A, 0x6B5B, 0x87F8, 0x686A, 0x8914, 0x67DC, 0x8897, 0x6ADF, 0x878A, 0xFFFF, 0x6CF7, 0x892F, 0x6D8D, 0x8991, 0x6AEB, 0x8AE9, 0x6A40, 0x8A79, 0xFFFF, 0x9380, 0x8932, 0x9645, 0x8A72, 0x963E, 0x8A77, 0x9599, 0x8AE3, 0x92F5, 0x898D, 0x9380, 0x8932, 0x9380, 0x8932, 0xFFFF, 0x9110, 0x8AA1, 0x936F, 0x8C1F, 0x92AA, 0x8C80, 0x9064, 0x8AF7, 0x9110, 0x8AA1, 0x9110, 0x8AA1, 0xFFFF, 0x6F73, 0x8AA5, 0x7021, 0x8AFB, 0x7035, 0x8B04, 0x6DED, 0x8C8B, 0x6DE1, 0x8C87, 0x6D17, 0x8C23, 0xFFFF, 0x8E3E, 0x8BE1, 0x9037, 0x8D8B, 0x8F59, 0x8DDC, 0x8D7C, 0x8C27, 0x8E3E, 0x8BE1, 0x8E3E, 0x8BE1, 0xFFFF, 0x7259, 0x8BEB, 0x731B, 0x8C31, 0x7140, 0x8DE7, 0x7064, 0x8D97, 0xFFFF, 0x8B21, 0x8CE3, 0x8CA9, 0x8EB2, 0x8BBA, 0x8EEF, 0x8A51, 0x8D18, 0x8B21, 0x8CE3, 0x8B21, 0x8CE3, 0xFFFF, 0x7576, 0x8CEB, 0x7648, 0x8D20, 0x74E0, 0x8EF8, 0x73F2, 0x8EBB, 0xFFFF, 0x66F3, 0x8D2F, 0x6874, 0x8D8A, 0x687D, 0x8D8F, 0x6886, 0x8D94, 0x6926, 0x8E6E, 0x6887, 0x8F48, 0x6705, 0x8FA2, 0x6584, 0x8F49, 0x657F, 0x8F45, 0x6570, 0x8F3E, 0x6573, 0x8F3E, 0x64D3, 0x8E63, 0x6573, 0x8D89, 0x66F3, 0x8D2F, 0x66F3, 0x8D2F, 0xFFFF, 0x9993, 0x8D31, 0x9B13, 0x8D8C, 0x9BB4, 0x8E66, 0x9B16, 0x8F40, 0x9993, 0x8F9A, 0x9814, 0x8F40, 0x9774, 0x8E66, 0x9812, 0x8D8C, 0x9993, 0x8D31, 0x9993, 0x8D31, 0xFFFF, 0x87CD, 0x8DA1, 0x88DC, 0x8F8B, 0x87E0, 0x8FB5, 0x86F0, 0x8DC6, 0x87CD, 0x8DA1, 0x87CD, 0x8DA1, 0xFFFF, 0x78CD, 0x8DA8, 0x79A8, 0x8DCB, 0x78BC, 0x8FBB, 0x77C1, 0x8F92, 0xFFFF, 0x8450, 0x8E19, 0x84E2, 0x9014, 0x83E0, 0x9029, 0x836C, 0x8E2C, 0x8450, 0x8E19, 0x8450, 0x8E19, 0xFFFF, 0x7C48, 0x8E1C, 0x7D2B, 0x8E2E, 0x7CBD, 0x902C, 0x7BBB, 0x9017, 0x7C48, 0x8E1C, 0xFFFF, 0x80BF, 0x8E49, 0x80D2, 0x904A, 0x7FCC, 0x904A, 0x7FD9, 0x8E49, 0x80BF, 0x8E49, 0x80BF, 0x8E49, 0xFFFF, 0x804F, 0x9321, 0x81D0, 0x937A, 0x8271, 0x9455, 0x81D1, 0x952F, 0x8051, 0x958A, 0x7ECF, 0x9530, 0x7E2F, 0x9456, 0x7ECE, 0x937B, 0x804F, 0x9321, 0x804F, 0x9321, 0xFFFF, 0x8048, 0x46D9, 0x27BC, 0x9DBA, 0xD8D3, 0x9DBA, 0xFFFF, 0x8048, 0x4BC9, 0x952E, 0x604A, 0x6B62, 0x604A, 0xFFFF, 0x68D2, 0x62CE, 0x97BF, 0x62CE, 0xB9BA, 0x8427, 0xA239, 0x9B36, 0x5E16, 0x9B36, 0x46B6, 0x8446, 0x68D2, 0x62CE, 0xFFFF, 0xBC3E, 0x869F, 0xD13B, 0x9B36, 0xA742, 0x9B36, 0xFFFF, 0x4431, 0x86BE, 0x590E, 0x9B36, 0x2F54, 0x9B36, 0x4431, 0x86BE}; -const PROGMEM uint16_t logo_white[] = {0x80BC, 0x6FD7, 0x80AF, 0x71D8, 0x7FC8, 0x71D9, 0x7FB7, 0x6FD8, 0x80BC, 0x6FD7, 0xFFFF, 0x83CB, 0x6FF6, 0x84CD, 0x700B, 0x843E, 0x7206, 0x835B, 0x71F4, 0xFFFF, 0x7CA9, 0x6FF8, 0x7D1A, 0x71F5, 0x7C37, 0x7207, 0x7BA7, 0x700D, 0x7CA9, 0x6FF8, 0x7CA9, 0x6FF8, 0xFFFF, 0x87CD, 0x7068, 0x88C7, 0x7092, 0x87BA, 0x727C, 0x86DF, 0x7258, 0xFFFF, 0x78A8, 0x706B, 0x7997, 0x725A, 0x78BA, 0x727E, 0x77AD, 0x7095, 0x78A8, 0x706B, 0x78A8, 0x706B, 0xFFFF, 0x8BA7, 0x712C, 0x8C95, 0x716A, 0x8B10, 0x7339, 0x8A3F, 0x7303, 0xFFFF, 0x74CE, 0x712F, 0x7635, 0x7307, 0x7564, 0x733C, 0x73DE, 0x716D, 0x74CE, 0x712F, 0x74CE, 0x712F, 0xFFFF, 0x8F47, 0x723F, 0x9023, 0x728E, 0x8E2D, 0x743A, 0x8D6B, 0x73F4, 0xFFFF, 0x712D, 0x7242, 0x7309, 0x73F7, 0x7248, 0x743D, 0x7050, 0x7292, 0x712D, 0x7242, 0x712D, 0x7242, 0xFFFF, 0x929B, 0x739A, 0x935C, 0x73FA, 0x9100, 0x7578, 0x905A, 0x7527, 0xFFFF, 0x6DDC, 0x739D, 0x7022, 0x7527, 0x6F74, 0x757C, 0x6D16, 0x73FF, 0x6DDC, 0x739D, 0x6DDC, 0x739D, 0xFFFF, 0x9589, 0x7533, 0x9634, 0x75A4, 0x937E, 0x76ED, 0x92E8, 0x768B, 0xFFFF, 0x6AEB, 0x7539, 0x6D8D, 0x7690, 0x6CFB, 0x76F0, 0x6A40, 0x75A9, 0x6AEB, 0x7539, 0xFFFF, 0x980B, 0x7707, 0x989A, 0x7784, 0x9597, 0x7892, 0x951A, 0x7825, 0xFFFF, 0x686A, 0x770C, 0x6B5B, 0x782A, 0x6ADF, 0x7897, 0x67DD, 0x7788, 0x686A, 0x770C, 0x686A, 0x770C, 0xFFFF, 0x9A12, 0x790A, 0x9A7E, 0x7991, 0x9740, 0x7A5E, 0x96E1, 0x79E8, 0xFFFF, 0x6664, 0x790F, 0x6996, 0x79ED, 0x6937, 0x7A63, 0x65F9, 0x7996, 0x6664, 0x790F, 0x6664, 0x790F, 0xFFFF, 0x9B91, 0x7B32, 0x9BDB, 0x7BC1, 0x9870, 0x7C48, 0x9831, 0x7BCC, 0xFFFF, 0x64E6, 0x7B37, 0x6847, 0x7BD0, 0x6807, 0x7C4C, 0x649D, 0x7BC5, 0x64E6, 0x7B37, 0x64E6, 0x7B37, 0xFFFF, 0x9C82, 0x7D72, 0x9CA7, 0x7E06, 0x9925, 0x7E46, 0x9903, 0x7DC5, 0xFFFF, 0x63F7, 0x7D78, 0x6776, 0x7DC9, 0x6756, 0x7E49, 0x63D3, 0x7E0A, 0x63F7, 0x7D78, 0x63F7, 0x7D78, 0xFFFF, 0x9CE0, 0x7FC0, 0x9CE0, 0x8055, 0x9957, 0x804D, 0x9957, 0x7FCB, 0xFFFF, 0x639D, 0x7FC5, 0x6726, 0x7FCE, 0x6726, 0x8051, 0x639D, 0x805A, 0x639D, 0x7FC5, 0xFFFF, 0x9927, 0x81D1, 0x9CAA, 0x8210, 0x9C87, 0x82A2, 0x9907, 0x8252, 0x9927, 0x81D1, 0x9927, 0x81D1, 0xFFFF, 0x6757, 0x81D5, 0x6777, 0x8256, 0x63F9, 0x82A7, 0x63D4, 0x8214, 0xFFFF, 0x9877, 0x83CF, 0x9BE2, 0x8455, 0x9B99, 0x84E3, 0x9838, 0x844C, 0x9877, 0x83CF, 0xFFFF, 0x6808, 0x83D3, 0x6848, 0x8450, 0x64E7, 0x84E8, 0x649E, 0x845A, 0xFFFF, 0x9749, 0x85B9, 0x9A88, 0x8684, 0x9A1D, 0x870C, 0x96EB, 0x862E, 0x9749, 0x85B9, 0x9749, 0x85B9, 0xFFFF, 0x6938, 0x85BD, 0x6997, 0x8634, 0x6665, 0x8710, 0x65F9, 0x8689, 0xFFFF, 0x95A2, 0x8785, 0x98A5, 0x8892, 0x9818, 0x890F, 0x9527, 0x87F2, 0x95A2, 0x8785, 0x95A2, 0x8785, 0xFFFF, 0x6ADF, 0x878A, 0x6B5B, 0x87F8, 0x686A, 0x8915, 0x67DC, 0x8897, 0xFFFF, 0x6CF7, 0x8930, 0x6D8D, 0x8991, 0x6AEB, 0x8AE9, 0x6A40, 0x8A79, 0xFFFF, 0x9380, 0x8932, 0x9645, 0x8A72, 0x9599, 0x8AE3, 0x92F5, 0x898D, 0x9380, 0x8932, 0xFFFF, 0x9110, 0x8AA1, 0x936F, 0x8C1F, 0x92AA, 0x8C80, 0x9064, 0x8AF7, 0x9110, 0x8AA1, 0x9110, 0x8AA1, 0xFFFF, 0x6F73, 0x8AA5, 0x7021, 0x8AFB, 0x6DED, 0x8C8C, 0x6D17, 0x8C23, 0xFFFF, 0x8E3E, 0x8BE1, 0x9037, 0x8D8B, 0x8F59, 0x8DDC, 0x8D7C, 0x8C27, 0x8E3E, 0x8BE1, 0x8E3E, 0x8BE1, 0xFFFF, 0x7259, 0x8BEB, 0x731B, 0x8C31, 0x7140, 0x8DE7, 0x7064, 0x8D97, 0xFFFF, 0x8B21, 0x8CE3, 0x8CA9, 0x8EB2, 0x8BBA, 0x8EEF, 0x8A51, 0x8D18, 0x8B21, 0x8CE3, 0x8B21, 0x8CE3, 0xFFFF, 0x7576, 0x8CEB, 0x7648, 0x8D20, 0x74E0, 0x8EF8, 0x73F2, 0x8EBB, 0xFFFF, 0x87CD, 0x8DA1, 0x88DC, 0x8F8B, 0x87E0, 0x8FB5, 0x86F0, 0x8DC6, 0x87CD, 0x8DA1, 0x87CD, 0x8DA1, 0xFFFF, 0x78CC, 0x8DA8, 0x79A8, 0x8DCB, 0x78BC, 0x8FBB, 0x77C0, 0x8F92, 0xFFFF, 0x8450, 0x8E19, 0x84E2, 0x9014, 0x83E0, 0x9029, 0x836C, 0x8E2C, 0x8450, 0x8E19, 0x8450, 0x8E19, 0xFFFF, 0x7C48, 0x8E1C, 0x7D2B, 0x8E2E, 0x7CBD, 0x902C, 0x7BBB, 0x9017, 0xFFFF, 0x80BE, 0x8E49, 0x80D1, 0x904A, 0x7FCC, 0x904A, 0x7FD9, 0x8E49, 0x80BE, 0x8E49, 0xFFFF, 0x8276, 0x75D6, 0x83AF, 0x75FE, 0x8436, 0x7628, 0x84AE, 0x7661, 0x8542, 0x7706, 0x8512, 0x77BA, 0x8457, 0x7845, 0x8335, 0x788B, 0x8318, 0x7882, 0x82D8, 0x7860, 0x831E, 0x7830, 0x8353, 0x7823, 0x83E6, 0x77F9, 0x8464, 0x7790, 0x847A, 0x771A, 0x8415, 0x76B7, 0x83B6, 0x7691, 0x8351, 0x7676, 0x827F, 0x7662, 0x81BB, 0x7687, 0x8161, 0x76AF, 0x8123, 0x76DA, 0x80E5, 0x771A, 0x80C5, 0x774D, 0x80B8, 0x77C1, 0x80D1, 0x77EE, 0x8107, 0x7814, 0x81CC, 0x786B, 0x837F, 0x7918, 0x8464, 0x7983, 0x84C0, 0x79B2, 0x852D, 0x79FD, 0x859D, 0x7ABC, 0x858E, 0x7B79, 0x8545, 0x7C25, 0x84D9, 0x7CC5, 0x8469, 0x7D4D, 0x843B, 0x7DCD, 0x8555, 0x7DA8, 0x85D3, 0x7D67, 0x870D, 0x7CA0, 0x87E0, 0x7BC0, 0x880D, 0x7B5B, 0x886D, 0x7A46, 0x88B3, 0x799B, 0x88CC, 0x7970, 0x893A, 0x78EA, 0x8995, 0x78A8, 0x8A01, 0x786F, 0x8AF8, 0x781F, 0x8BA6, 0x77FD, 0x8C0C, 0x77EF, 0x8C96, 0x77FB, 0x8D1D, 0x7815, 0x8D59, 0x7826, 0x8E40, 0x7889, 0x8EDB, 0x7925, 0x8EFC, 0x797B, 0x8EFF, 0x79D4, 0x8E71, 0x7A7B, 0x8D58, 0x7AD2, 0x8C23, 0x7ADE, 0x8AFF, 0x7A97, 0x8AF5, 0x7A81, 0x8AEF, 0x7A4E, 0x8B68, 0x7A52, 0x8B96, 0x7A5F, 0x8C39, 0x7A87, 0x8D33, 0x7A7F, 0x8E07, 0x7A3F, 0x8E66, 0x79CB, 0x8E63, 0x7985, 0x8E43, 0x793F, 0x8DC6, 0x78C6, 0x8CFA, 0x7876, 0x8C7E, 0x785F, 0x8C18, 0x7857, 0x8B84, 0x7874, 0x8B22, 0x788F, 0x8A7D, 0x78CA, 0x8A2E, 0x78F9, 0x89F0, 0x7930, 0x89A3, 0x79A5, 0x8979, 0x7AC0, 0x897C, 0x7B9C, 0x8972, 0x7BF2, 0x88CC, 0x7D32, 0x87B7, 0x7E4C, 0x8665, 0x7F52, 0x8660, 0x7F5A, 0x878F, 0x7F01, 0x88AE, 0x7EC2, 0x89FD, 0x7E9E, 0x8B8D, 0x7EC6, 0x8C40, 0x7F0E, 0x8CB6, 0x7F68, 0x8D1D, 0x7FD7, 0x8DFA, 0x80BD, 0x8EA8, 0x816E, 0x8F34, 0x81D4, 0x8F8A, 0x81F9, 0x8FDA, 0x820A, 0x90AB, 0x820F, 0x9120, 0x81FF, 0x91A5, 0x81DC, 0x91F4, 0x81B8, 0x922C, 0x8198, 0x9288, 0x812B, 0x927D, 0x80AB, 0x9252, 0x8068, 0x921C, 0x8033, 0x9174, 0x7FEB, 0x9099, 0x7FEB, 0x8FCF, 0x8029, 0x8F5D, 0x808D, 0x8F47, 0x80A4, 0x8ED4, 0x80A4, 0x8EC5, 0x8070, 0x8F65, 0x7FE6, 0x906D, 0x7F92, 0x91A4, 0x7F90, 0x92A8, 0x7FF7, 0x92FC, 0x8043, 0x9331, 0x8090, 0x9349, 0x813D, 0x92D1, 0x81E3, 0x9264, 0x8227, 0x91E5, 0x825B, 0x915D, 0x8280, 0x90D3, 0x8296, 0x8FA0, 0x829A, 0x8F2C, 0x8286, 0x8EE7, 0x8273, 0x8E78, 0x824A, 0x8DA9, 0x81D4, 0x8CB9, 0x8127, 0x8B68, 0x802C, 0x8B22, 0x8001, 0x8AC3, 0x7FE7, 0x8A50, 0x7FF4, 0x88FD, 0x8068, 0x87A4, 0x811D, 0x879E, 0x812D, 0x8904, 0x81F1, 0x89D4, 0x8285, 0x8A7C, 0x8343, 0x8A94, 0x8431, 0x8A4E, 0x84A1, 0x89E8, 0x850E, 0x892F, 0x85E5, 0x88B0, 0x86E5, 0x88C0, 0x8757, 0x88F2, 0x878D, 0x8927, 0x87AD, 0x8ABF, 0x8821, 0x8B0E, 0x881E, 0x8B70, 0x8811, 0x8C1B, 0x87D6, 0x8C9B, 0x8776, 0x8CC4, 0x873D, 0x8CD3, 0x8705, 0x8CA2, 0x86A3, 0x8C06, 0x8662, 0x8B39, 0x864F, 0x8A77, 0x8662, 0x89F9, 0x864D, 0x8A10, 0x8606, 0x8A66, 0x85F7, 0x8B35, 0x85DC, 0x8C50, 0x85FD, 0x8D3C, 0x8663, 0x8D94, 0x870A, 0x8D7D, 0x875F, 0x8D3A, 0x87B8, 0x8CB1, 0x882D, 0x8BC1, 0x888C, 0x8B30, 0x88A7, 0x8A8D, 0x88AE, 0x89EE, 0x8898, 0x896E, 0x887E, 0x8869, 0x882D, 0x87EE, 0x87EA, 0x87A4, 0x87A8, 0x878E, 0x8785, 0x874D, 0x86E3, 0x875D, 0x8637, 0x87FD, 0x8466, 0x8705, 0x835A, 0x86B8, 0x8359, 0x84A4, 0x8358, 0x7F20, 0x851B, 0x7F13, 0x864D, 0x8016, 0x86F9, 0x818E, 0x87D8, 0x823B, 0x8869, 0x8272, 0x88C9, 0x8276, 0x8915, 0x8266, 0x893D, 0x81FB, 0x89D8, 0x8197, 0x8A21, 0x8119, 0x8A62, 0x80A7, 0x8A8A, 0x8016, 0x8AAA, 0x7EDC, 0x8AAE, 0x7DC5, 0x8A63, 0x7D55, 0x8A29, 0x7CFA, 0x89E5, 0x7CAD, 0x8939, 0x7D1B, 0x8895, 0x7E00, 0x8825, 0x7F27, 0x8800, 0x7F66, 0x880F, 0x7F69, 0x8850, 0x7E49, 0x8873, 0x7D9A, 0x88C9, 0x7D4F, 0x893E, 0x7D8B, 0x89B2, 0x7DD8, 0x89E6, 0x7E36, 0x8A10, 0x7F02, 0x8A40, 0x7FDB, 0x8A34, 0x8046, 0x8A16, 0x8091, 0x89F5, 0x80A5, 0x89EB, 0x80FE, 0x89AB, 0x8126, 0x8981, 0x8159, 0x8918, 0x814F, 0x88E6, 0x8128, 0x88B8, 0x8094, 0x8856, 0x7EFC, 0x8796, 0x7D74, 0x86E7, 0x7D3D, 0x86C5, 0x7CD8, 0x8674, 0x7C98, 0x8605, 0x7CA0, 0x8536, 0x7D7C, 0x83E6, 0x7E07, 0x8357, 0x7DED, 0x835B, 0x79CC, 0x843E, 0x7962, 0x8448, 0x77CB, 0x8450, 0x76F3, 0x8438, 0x763E, 0x841E, 0x7502, 0x83FE, 0x746C, 0x83FD, 0x73E4, 0x840A, 0x72CE, 0x8444, 0x729B, 0x8457, 0x71E6, 0x84B7, 0x71B5, 0x84EB, 0x719B, 0x853B, 0x719B, 0x8558, 0x71D4, 0x85E0, 0x72B0, 0x8642, 0x73D4, 0x8661, 0x74B3, 0x8616, 0x74AD, 0x84D7, 0x74B2, 0x84B3, 0x74B5, 0x849B, 0x751E, 0x8496, 0x753B, 0x84B8, 0x75C5, 0x856E, 0x756D, 0x865A, 0x74D0, 0x86B8, 0x73FA, 0x86EA, 0x7250, 0x86CF, 0x70E7, 0x863F, 0x707E, 0x85C8, 0x705F, 0x8549, 0x7075, 0x84CC, 0x70AC, 0x8475, 0x70CD, 0x8452, 0x71FF, 0x839C, 0x7287, 0x8376, 0x736A, 0x833A, 0x7443, 0x8319, 0x751E, 0x8311, 0x76AC, 0x8327, 0x77C4, 0x8341, 0x7810, 0x8340, 0x799F, 0x8313, 0x7A2A, 0x82EA, 0x7B24, 0x8281, 0x7BE4, 0x820C, 0x7BEC, 0x81B1, 0x7A5E, 0x81C8, 0x7809, 0x81ED, 0x7751, 0x81F8, 0x7664, 0x81EF, 0x7571, 0x81B4, 0x74BB, 0x8141, 0x7483, 0x80F9, 0x7408, 0x802F, 0x73D9, 0x7FEB, 0x7359, 0x7F50, 0x72A0, 0x7EC4, 0x719E, 0x7E89, 0x7074, 0x7EA8, 0x7015, 0x7ECC, 0x6FD0, 0x7EF8, 0x6FA3, 0x7F19, 0x6F6B, 0x7FBB, 0x6F93, 0x8017, 0x6FA7, 0x8032, 0x6FD7, 0x805A, 0x70DF, 0x8092, 0x7205, 0x805A, 0x729E, 0x7FCB, 0x72B3, 0x7FBC, 0x7309, 0x7FA6, 0x733B, 0x7FDE, 0x72F9, 0x804B, 0x726D, 0x80A7, 0x70E6, 0x80FB, 0x700D, 0x80EC, 0x6F48, 0x80A8, 0x6EFC, 0x8073, 0x6EC1, 0x8026, 0x6E93, 0x7FCC, 0x6ED4, 0x7ED8, 0x6F54, 0x7E72, 0x6FCB, 0x7E3A, 0x700B, 0x7E25, 0x71AB, 0x7DED, 0x7356, 0x7E3E, 0x7472, 0x7EF4, 0x7536, 0x7FBD, 0x75DA, 0x8075, 0x7628, 0x80B6, 0x767B, 0x80D8, 0x76D9, 0x80EF, 0x7755, 0x80FC, 0x7881, 0x80D5, 0x7931, 0x8093, 0x7A00, 0x801E, 0x799B, 0x7D9B, 0x789A, 0x7CD8, 0x77C0, 0x7BE5, 0x7783, 0x7B55, 0x7787, 0x7AB9, 0x77AE, 0x7A67, 0x77E6, 0x7A1D, 0x781E, 0x79CD, 0x785E, 0x7909, 0x7853, 0x78C0, 0x7823, 0x788B, 0x7808, 0x7875, 0x7649, 0x77E8, 0x74B6, 0x7869, 0x7488, 0x78B3, 0x7472, 0x7901, 0x74D2, 0x796F, 0x75D8, 0x799A, 0x76EE, 0x7971, 0x774A, 0x797A, 0x7751, 0x79B4, 0x76A0, 0x79F0, 0x75E4, 0x7A0A, 0x7454, 0x79E1, 0x73AF, 0x7986, 0x7369, 0x7909, 0x7374, 0x7891, 0x739D, 0x783C, 0x73B6, 0x781E, 0x74B7, 0x7768, 0x765D, 0x772C, 0x77ED, 0x7769, 0x7932, 0x77FC, 0x7979, 0x7836, 0x79B8, 0x787B, 0x79DF, 0x7912, 0x7998, 0x7A14, 0x7967, 0x7AB4, 0x796A, 0x7AD8, 0x79C5, 0x7B60, 0x7A9D, 0x7BE9, 0x7B72, 0x7C47, 0x7EBA, 0x7BD6, 0x8206, 0x7CA8, 0x82FA, 0x7C2E, 0x8391, 0x7BB4, 0x83F6, 0x7B40, 0x8413, 0x7AD0, 0x83DD, 0x7A71, 0x838A, 0x7A39, 0x8296, 0x79B7, 0x80F3, 0x78FA, 0x8016, 0x788A, 0x7FB4, 0x7833, 0x7F8D, 0x77DF, 0x7F92, 0x77A9, 0x7FB3, 0x7718, 0x7FF6, 0x76C2, 0x8036, 0x768A, 0x8097, 0x764A, 0x80DF, 0x762A, 0x813C, 0x7605, 0x8275, 0x75D5}; - -#define LOGO_BACKGROUND 0xDEEA5C - -#define LOGO_PAINT_PATHS \ - LOGO_PAINT_PATH(0xC1D82F, logo_green) \ - LOGO_PAINT_PATH(0x000000, logo_black) \ - LOGO_PAINT_PATH(0x000000, logo_type) \ - LOGO_PAINT_PATH(0x000000, logo_mark) \ - LOGO_PAINT_PATH(0xFFFFFF, logo_white) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h index 70c2be4ec23f..0e145e39f208 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h @@ -37,7 +37,7 @@ namespace Theme { #else // Use linear accent colors - #if EITHER(TOUCH_UI_ROYAL_THEME, TOUCH_UI_FROZEN_THEME) + #if ANY(TOUCH_UI_ROYAL_THEME, TOUCH_UI_FROZEN_THEME) // Dark blue accent colors constexpr int accent_hue = 216; constexpr float accent_sat = 0.7; @@ -88,7 +88,7 @@ namespace Theme { constexpr uint32_t bed_mesh_lines_rgb = 0xFFFFFF; constexpr uint32_t bed_mesh_shadow_rgb = 0x444444; - #elif EITHER(TOUCH_UI_COCOA_THEME, TOUCH_UI_FROZEN_THEME) + #elif ANY(TOUCH_UI_COCOA_THEME, TOUCH_UI_FROZEN_THEME) constexpr uint32_t theme_darkest = accent_color_1; constexpr uint32_t theme_dark = accent_color_4; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp index efeed1920114..49967be086e9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp @@ -165,7 +165,6 @@ namespace Theme { {ORGAN, NOTE_A4, 4}, {SILENCE, REST, 36}, - {ORGAN, NOTE_C5S, 4}, {ORGAN, NOTE_D5, 2}, {ORGAN, NOTE_E5, 2}, @@ -300,6 +299,44 @@ namespace Theme { {SILENCE, END_SONG, 0} }; + const PROGMEM SoundPlayer::sound_t flagpole[] = { + {TRIANGLE_WAVE, NOTE_G3, 2}, + {TRIANGLE_WAVE, NOTE_C4, 2}, + {TRIANGLE_WAVE, NOTE_E4, 2}, + {TRIANGLE_WAVE, NOTE_G4, 2}, + {TRIANGLE_WAVE, NOTE_C5, 2}, + {TRIANGLE_WAVE, NOTE_E5, 2}, + {TRIANGLE_WAVE, NOTE_G5, 5}, + {TRIANGLE_WAVE, NOTE_E5, 2}, + + {TRIANGLE_WAVE, NOTE_G3S, 2}, + {TRIANGLE_WAVE, NOTE_C4, 2}, + {TRIANGLE_WAVE, NOTE_D4S, 2}, + {TRIANGLE_WAVE, NOTE_G4S, 2}, + {TRIANGLE_WAVE, NOTE_C5, 2}, + {TRIANGLE_WAVE, NOTE_D5S, 2}, + {TRIANGLE_WAVE, NOTE_G5S, 5}, + {TRIANGLE_WAVE, NOTE_D5S, 5}, + + {TRIANGLE_WAVE, NOTE_A3S, 2}, + {TRIANGLE_WAVE, NOTE_D4, 2}, + {TRIANGLE_WAVE, NOTE_F4, 2}, + {TRIANGLE_WAVE, NOTE_A4S, 2}, + {TRIANGLE_WAVE, NOTE_D5, 2}, + {TRIANGLE_WAVE, NOTE_F5, 2}, + {TRIANGLE_WAVE, NOTE_A5S, 5}, + + {SILENCE, REST, 1}, + {TRIANGLE_WAVE, NOTE_A5S, 1}, + {SILENCE, REST, 1}, + {TRIANGLE_WAVE, NOTE_A5S, 1}, + {SILENCE, REST, 1}, + {TRIANGLE_WAVE, NOTE_A5S, 1}, + {SILENCE, REST, 1}, + {TRIANGLE_WAVE, NOTE_A5S, 8}, + {SILENCE, END_SONG, 0} + }; + const PROGMEM SoundPlayer::sound_t big_band[] = { {XYLOPHONE, NOTE_F4, 3}, {XYLOPHONE, NOTE_G4, 3}, @@ -402,7 +439,8 @@ const SoundList::list_t SoundList::list[] = { {"Carousel", Theme::carousel}, {"Beats", Theme::beats}, {"Bach Joy", Theme::js_bach_joy}, - {"Bach Toccata", Theme::js_bach_toccata} + {"Bach Toccata", Theme::js_bach_toccata}, + {"Flagpole", Theme::flagpole} }; const uint8_t SoundList::n = N_ELEMENTS(SoundList::list); diff --git a/Marlin/src/lcd/extui/malyan/malyan.cpp b/Marlin/src/lcd/extui/malyan/malyan.cpp index 06c9886f0131..306f3198561b 100644 --- a/Marlin/src/lcd/extui/malyan/malyan.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan.cpp @@ -79,7 +79,7 @@ void write_to_lcd(FSTR_P const fmsg) { char encoded_message[MAX_CURLY_COMMAND]; uint8_t message_length = _MIN(strlen_P(pmsg), sizeof(encoded_message)); - LOOP_L_N(i, message_length) + for (uint8_t i = 0; i < message_length; ++i) encoded_message[i] = pgm_read_byte(&pmsg[i]) | 0x80; LCD_SERIAL.Print::write(encoded_message, message_length); @@ -89,7 +89,7 @@ void write_to_lcd(const char * const cmsg) { char encoded_message[MAX_CURLY_COMMAND]; const uint8_t message_length = _MIN(strlen(cmsg), sizeof(encoded_message)); - LOOP_L_N(i, message_length) + for (uint8_t i = 0; i < message_length; ++i) encoded_message[i] = cmsg[i] | 0x80; LCD_SERIAL.Print::write(encoded_message, message_length); @@ -106,7 +106,6 @@ void set_lcd_error(FSTR_P const error, FSTR_P const component/*=nullptr*/) { write_to_lcd(F("}")); } - /** * Process an LCD 'C' command. * These are currently all temperature commands @@ -167,7 +166,7 @@ void process_lcd_eb_command(const char *command) { char message_buffer[MAX_CURLY_COMMAND]; uint8_t done_pct = print_job_timer.isRunning() ? (iteration * 10) : 100; iteration = (iteration + 1) % 10; // Provide progress animation - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (ExtUI::isPrintingFromMedia() || ExtUI::isPrintingFromMediaPaused()) done_pct = card.percentDone(); #endif @@ -180,7 +179,7 @@ void process_lcd_eb_command(const char *command) { #else 0, 0, #endif - TERN(SDSUPPORT, done_pct, 0), + TERN(HAS_MEDIA, done_pct, 0), elapsed_buffer ); write_to_lcd(message_buffer); @@ -257,7 +256,7 @@ void process_lcd_p_command(const char *command) { break; case 'H': queue.enqueue_now_P(G28_STR); break; // Home all axes default: { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA // Print file 000 - a three digit number indicating which // file to print in the SD card. If it's a directory, // then switch to the directory. @@ -316,7 +315,7 @@ void process_lcd_s_command(const char *command) { } break; case 'L': { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (!card.isMounted()) card.mount(); // A more efficient way to do this would be to @@ -326,8 +325,8 @@ void process_lcd_s_command(const char *command) { // select a file for printing during a print, there's // little reason not to do it this way. char message_buffer[MAX_CURLY_COMMAND]; - uint16_t file_count = card.get_num_Files(); - for (uint16_t i = 0; i < file_count; i++) { + int16_t file_count = card.get_num_items(); + for (int16_t i = 0; i < file_count; i++) { card.selectFileByIndex(i); sprintf_P(message_buffer, card.flag.filenameIsDir ? PSTR("{DIR:%s}") : PSTR("{FILE:%s}"), card.longest_filename()); write_to_lcd(message_buffer); diff --git a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp index 945ff472e1a1..6ba5e2bc3c1d 100644 --- a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp @@ -78,7 +78,7 @@ namespace ExtUI { while (LCD_SERIAL.available()) parse_lcd_byte((byte)LCD_SERIAL.read()); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA // The way last printing status works is simple: // The UI needs to see at least one TQ which is not 100% // and then when the print is complete, one which is. @@ -137,7 +137,7 @@ namespace ExtUI { void onMediaInserted() {} void onMediaError() {} void onMediaRemoved() {} - void onPlayTone(const uint16_t, const uint16_t) {} + void onPlayTone(const uint16_t, const uint16_t/*=0*/) {} void onFilamentRunout(const extruder_t extruder) {} void onUserConfirmRequired(const char * const) {} void onHomingStart() {} @@ -147,18 +147,29 @@ namespace ExtUI { void onStoreSettings(char*) {} void onLoadSettings(const char*) {} void onPostprocessSettings() {} - void onSettingsStored(bool) {} - void onSettingsLoaded(bool) {} + void onSettingsStored(const bool) {} + void onSettingsLoaded(const bool) {} - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) {} - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) {} + #endif + + #if HAS_MESH + void onMeshUpdate(const int8_t, const int8_t, const_float_t) {} + void onMeshUpdate(const int8_t, const int8_t, const ExtUI::probe_state_t) {} #endif #if ENABLED(POWER_LOSS_RECOVERY) - void onPowerLossResume() {} + void onSetPowerLoss(const bool onoff) { + // Called when power-loss is enabled/disabled + } + void onPowerLoss() { + // Called when power-loss state is detected + } + void onPowerLossResume() { + // Called on resume from power-loss + } #endif void onSteppersDisabled() {} diff --git a/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp index 43149dc60c58..0554c34a19ac 100644 --- a/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp +++ b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp @@ -59,7 +59,7 @@ uint32_t SPIFlashStorage::m_startAddress; while (index < inputLength && index - count < max && input[index] == pixel) index++; if (index - count == 1) { - /* + /** * Failed to "replicate" the current pixel. See how many to copy. * Avoid a replicate run of only 2-pixels after a literal run. There * is no gain in this, and there is a risK of loss if the run after @@ -68,7 +68,7 @@ uint32_t SPIFlashStorage::m_startAddress; */ while (index < inputLength && index - count < max && (input[index] != input[index - 1] || (index > 1 && input[index] != input[index - 2]))) index++; - /* + /** * Check why this run stopped. If it found two identical pixels, reset * the index so we can add a run. Do this twice: the previous run * tried to detect a replicate run of at least 3 pixels. So we may be @@ -158,7 +158,6 @@ void SPIFlashStorage::beginWrite(const uint32_t startAddress) { #endif } - void SPIFlashStorage::endWrite() { // Flush remaining data #if HAS_SPI_FLASH_COMPRESSION diff --git a/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp index 42abd4bf6453..5f10d76e2f79 100644 --- a/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp +++ b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp @@ -37,11 +37,11 @@ TFT SPI_TFT; // use SPI1 for the spi tft. -void TFT::spi_init(uint8_t spiRate) { +void TFT::spiInit(uint8_t spiRate) { tftio.Init(); } -void TFT::SetPoint(uint16_t x, uint16_t y, uint16_t point) { +void TFT::setPoint(uint16_t x, uint16_t y, uint16_t point) { if ((x > 480) || (y > 320)) return; setWindow(x, y, 1, 1); @@ -52,32 +52,30 @@ void TFT::setWindow(uint16_t x, uint16_t y, uint16_t with, uint16_t height) { tftio.set_window(x, y, (x + with - 1), (y + height - 1)); } -void TFT::LCD_init() { +void TFT::lcdInit() { tftio.InitTFT(); #if PIN_EXISTS(TFT_BACKLIGHT) OUT_WRITE(TFT_BACKLIGHT_PIN, LOW); #endif delay(100); - LCD_clear(0x0000); - LCD_Draw_Logo(); + lcdClear(0x0000); + lcdDrawLogo(); #if PIN_EXISTS(TFT_BACKLIGHT) OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif - #if HAS_LOGO_IN_FLASH - delay(2000); - #endif + TERN_(HAS_LOGO_IN_FLASH, delay(2000)); } -void TFT::LCD_clear(uint16_t color) { +void TFT::lcdClear(uint16_t color) { setWindow(0, 0, TFT_WIDTH, TFT_HEIGHT); tftio.WriteMultiple(color, uint32_t(TFT_WIDTH) * uint32_t(TFT_HEIGHT)); } -void TFT::LCD_Draw_Logo() { +void TFT::lcdDrawLogo() { #if HAS_LOGO_IN_FLASH setWindow(0, 0, TFT_WIDTH, TFT_HEIGHT); for (uint16_t i = 0; i < (TFT_HEIGHT); i++) { - Pic_Logo_Read((uint8_t *)"", (uint8_t *)bmp_public_buf, (TFT_WIDTH) * 2); + picLogoRead((uint8_t *)"", (uint8_t *)bmp_public_buf, (TFT_WIDTH) * 2); tftio.WriteSequence((uint16_t *)bmp_public_buf, TFT_WIDTH); } #endif diff --git a/Marlin/src/lcd/extui/mks_ui/SPI_TFT.h b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.h index 62a084fb1196..56576c8c16a5 100644 --- a/Marlin/src/lcd/extui/mks_ui/SPI_TFT.h +++ b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.h @@ -27,12 +27,12 @@ class TFT { public: TFT_IO tftio; - void spi_init(uint8_t spiRate); - void SetPoint(uint16_t x, uint16_t y, uint16_t point); + void spiInit(uint8_t spiRate); + void setPoint(uint16_t x, uint16_t y, uint16_t point); void setWindow(uint16_t x, uint16_t y, uint16_t with, uint16_t height); - void LCD_init(); - void LCD_clear(uint16_t color); - void LCD_Draw_Logo(); + void lcdInit(); + void lcdClear(uint16_t color); + void lcdDrawLogo(); }; extern TFT SPI_TFT; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp index ac7d6d3dfb37..48455e7e36c5 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_acceleration_settings.cpp @@ -124,8 +124,10 @@ void lv_draw_acceleration_settings() { lv_screen_menu_item_1_edit(scr, machine_menu.TravelAcceleration, PARA_UI_POS_X, y, event_handler, ID_ACCE_TRAVEL, 2, public_buf_l); y += PARA_UI_POS_Y; - itoa(planner.settings.max_acceleration_mm_per_s2[X_AXIS], public_buf_l, 10); - lv_screen_menu_item_1_edit(scr, machine_menu.X_Acceleration, PARA_UI_POS_X, y, event_handler, ID_ACCE_X, 3, public_buf_l); + #if HAS_X_AXIS + itoa(planner.settings.max_acceleration_mm_per_s2[X_AXIS], public_buf_l, 10); + lv_screen_menu_item_1_edit(scr, machine_menu.X_Acceleration, PARA_UI_POS_X, y, event_handler, ID_ACCE_X, 3, public_buf_l); + #endif lv_big_button_create(scr, "F:/bmp_back70x40.bin", machine_menu.next, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y, event_handler, ID_ACCE_DOWN, true); } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp index fd14585e7028..5a5d457b080b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, HAS_BED_PROBE) +#if ALL(HAS_TFT_LVGL_UI, HAS_BED_PROBE) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp index 1dae0ebe2251..0798db1cc9f4 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) +#if ALL(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "lv_conf.h" #include "draw_ui.h" diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp index a214e7d1e0e7..061949289690 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp @@ -85,7 +85,7 @@ static void btn_ok_event_cb(lv_obj_t *btn, lv_event_t event) { lv_clear_dialog(); lv_draw_printing(); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (!gcode_preview_over) { char *cur_name; cur_name = strrchr(list_file.file_name[sel_id], '/'); @@ -121,7 +121,7 @@ static void btn_ok_event_cb(lv_obj_t *btn, lv_event_t event) { lv_clear_dialog(); lv_draw_ready_print(); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA uiCfg.print_state = IDLE; card.abortFilePrintSoon(); #endif @@ -380,6 +380,7 @@ void lv_draw_dialog(uint8_t type) { lv_label_set_text(labelDialog, DIALOG_UPDATE_NO_DEVICE_EN); lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); } + #if ENABLED(MKS_WIFI_MODULE) else if (DIALOG_IS(TYPE_UPLOAD_FILE)) { if (upload_result == 1) { @@ -422,6 +423,7 @@ void lv_draw_dialog(uint8_t type) { lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); } #endif // MKS_WIFI_MODULE + else if (DIALOG_IS(TYPE_FILAMENT_LOAD_HEAT)) { lv_label_set_text(labelDialog, filament_menu.filament_dialog_load_heat); lv_obj_align(labelDialog, nullptr, LV_ALIGN_CENTER, 0, -20); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp index bc151001531f..2c9928f3879f 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_error_message.cpp @@ -35,7 +35,7 @@ static lv_obj_t *scr; void lv_draw_error_message(FSTR_P const fmsg) { FSTR_P fhalted = F("PRINTER HALTED"), fplease = F("Please Reset"); - SPI_TFT.LCD_clear(0x0000); + SPI_TFT.lcdClear(0x0000); if (fmsg) disp_string((TFT_WIDTH - strlen_P(FTOP(fmsg)) * 16) / 2, 100, fmsg, 0xFFFF, 0x0000); disp_string((TFT_WIDTH - strlen_P(FTOP(fhalted)) * 16) / 2, 140, fhalted, 0xFFFF, 0x0000); disp_string((TFT_WIDTH - strlen_P(FTOP(fplease)) * 16) / 2, 180, fplease, 0xFFFF, 0x0000); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp index a070cae15f4e..5b22103e8f2d 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, HAS_CLASSIC_JERK) +#if ALL(HAS_TFT_LVGL_UI, HAS_CLASSIC_JERK) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp index 90b181d6b548..af61d716b859 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp @@ -155,7 +155,7 @@ static void lv_kb_event_cb(lv_obj_t *kb, lv_event_t event) { #endif // MKS_WIFI_MODULE case autoLevelGcodeCommand: uint8_t buf[100]; - strncpy((char *)buf, ret_ta_txt, sizeof(buf)); + strncpy((char *)buf, ret_ta_txt, sizeof(buf) - 1); update_gcode_command(AUTO_LEVELING_COMMAND_ADDR, buf); goto_previous_ui(); break; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp index 81c82dc02dfa..085a008acde9 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp @@ -21,7 +21,7 @@ */ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MULTI_VOLUME) +#if ALL(HAS_TFT_LVGL_UI, MULTI_VOLUME) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp b/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp index 850a409a1857..7e0624c15988 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp @@ -56,15 +56,9 @@ static bool point_flag = true; enum { ID_NUM_KEY1 = 1, - ID_NUM_KEY2, - ID_NUM_KEY3, - ID_NUM_KEY4, - ID_NUM_KEY5, - ID_NUM_KEY6, - ID_NUM_KEY7, - ID_NUM_KEY8, - ID_NUM_KEY9, - ID_NUM_KEY0, + ID_NUM_KEY2, ID_NUM_KEY3, ID_NUM_KEY4, + ID_NUM_KEY5, ID_NUM_KEY6, ID_NUM_KEY7, + ID_NUM_KEY8, ID_NUM_KEY9, ID_NUM_KEY0, ID_NUM_BACK, ID_NUM_RESET, ID_NUM_CONFIRM, diff --git a/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp b/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp index ffe714fca964..bf39a52fe965 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_operation.cpp @@ -70,7 +70,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { uiCfg.extruderIndexBak = active_extruder; #endif if (uiCfg.print_state == WORKING) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA card.pauseSDPrint(); stop_print_time(); uiCfg.print_state = PAUSING; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp index e5f6a5963a6b..b753a578012b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, ADVANCED_PAUSE_FEATURE) +#if ALL(HAS_TFT_LVGL_UI, ADVANCED_PAUSE_FEATURE) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp index 0199bc1f555d..6521bd6af41a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp @@ -55,7 +55,7 @@ extern char public_buf_m[100]; uint8_t sel_id = 0; -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA static uint8_t search_file() { int valid_name_cnt = 0; @@ -72,11 +72,11 @@ uint8_t sel_id = 0; else card.cdroot(); - const uint16_t fileCnt = card.get_num_Files(); + const int16_t fileCnt = card.get_num_items(); - for (uint16_t i = 0; i < fileCnt; i++) { + for (int16_t i = 0; i < fileCnt; i++) { if (list_file.Sd_file_cnt == list_file.Sd_file_offset) { - card.getfilename_sorted(SD_ORDER(i, fileCnt)); + card.selectFileByIndexSorted(i); list_file.IsFolder[valid_name_cnt] = card.flag.filenameIsDir; strcpy(list_file.file_name[valid_name_cnt], list_file.curDirPath); @@ -100,10 +100,10 @@ uint8_t sel_id = 0; return valid_name_cnt; } -#endif // SDSUPPORT +#endif // HAS_MEDIA bool have_pre_pic(char *path) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA char *ps1, *ps2, *cur_name = strrchr(path, '/'); card.openFileRead(cur_name); card.read(public_buf, 512); @@ -120,8 +120,6 @@ bool have_pre_pic(char *path) { static void event_handler(lv_obj_t *obj, lv_event_t event) { if (event != LV_EVENT_RELEASED) return; uint8_t i, file_count = 0; - //switch (obj->mks_obj_id) - //{ if (obj->mks_obj_id == ID_P_UP) { if (dir_offset[curDirLever].curPage > 0) { // 2015.05.19 @@ -130,9 +128,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { if (dir_offset[curDirLever].cur_page_first_offset >= FILE_NUM) list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_first_offset - FILE_NUM; - #if ENABLED(SDSUPPORT) - file_count = search_file(); - #endif + TERN_(HAS_MEDIA, file_count = search_file()); if (file_count != 0) { dir_offset[curDirLever].curPage--; lv_clear_print_file(); @@ -144,9 +140,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { if (dir_offset[curDirLever].cur_page_last_offset > 0) { list_file.Sd_file_cnt = 0; list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_last_offset + 1; - #if ENABLED(SDSUPPORT) - file_count = search_file(); - #endif + TERN_(HAS_MEDIA, file_count = search_file()); if (file_count != 0) { dir_offset[curDirLever].curPage++; lv_clear_print_file(); @@ -161,17 +155,13 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { int8_t *ch = (int8_t *)strrchr(list_file.curDirPath, '/'); if (ch) { *ch = 0; - #if ENABLED(SDSUPPORT) - card.cdup(); - #endif + TERN_(HAS_MEDIA, card.cdup()); dir_offset[curDirLever].curPage = 0; dir_offset[curDirLever].cur_page_first_offset = 0; dir_offset[curDirLever].cur_page_last_offset = 0; curDirLever--; list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_first_offset; - #if ENABLED(SDSUPPORT) - file_count = search_file(); - #endif + TERN_(HAS_MEDIA, file_count = search_file()); lv_clear_print_file(); disp_gcode_icon(file_count); } @@ -189,9 +179,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { strcpy(list_file.curDirPath, list_file.file_name[i]); curDirLever++; list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_first_offset; - #if ENABLED(SDSUPPORT) - file_count = search_file(); - #endif + TERN_(HAS_MEDIA, file_count = search_file()); lv_clear_print_file(); disp_gcode_icon(file_count); } @@ -222,7 +210,7 @@ void lv_draw_print_file() { ZERO(list_file.curDirPath); list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_first_offset; - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA card.mount(); file_count = search_file(); #endif @@ -359,7 +347,7 @@ void disp_gcode_icon(uint8_t file_num) { } uint32_t lv_open_gcode_file(char *path) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA uint32_t *ps4; uintptr_t pre_sread_cnt = UINTPTR_MAX; char *cur_name; @@ -375,7 +363,7 @@ uint32_t lv_open_gcode_file(char *path) { card.setIndex(pre_sread_cnt); } return pre_sread_cnt; - #endif // SDSUPPORT + #endif // HAS_MEDIA } int ascii2dec_test(char *ascii) { @@ -395,9 +383,8 @@ int ascii2dec_test(char *ascii) { } void lv_gcode_file_read(uint8_t *data_buf) { - #if ENABLED(SDSUPPORT) - uint16_t i = 0, j = 0, k = 0; - uint16_t row_1 = 0; + #if HAS_MEDIA + uint16_t i = 0, j = 0, k = 0, row_1 = 0; bool ignore_start = true; char temp_test[200]; volatile uint16_t *p_index; @@ -435,29 +422,18 @@ void lv_gcode_file_read(uint8_t *data_buf) { break; } } - #if HAS_TFT_LVGL_UI_SPI - for (i = 0; i < 200;) { - p_index = (uint16_t *)(&public_buf[i]); - - //Color = (*p_index >> 8); - //*p_index = Color | ((*p_index & 0xFF) << 8); - i += 2; - if (*p_index == 0x0000) *p_index = LV_COLOR_BACKGROUND.full; - } - #else // !HAS_TFT_LVGL_UI_SPI - for (i = 0; i < 200;) { - p_index = (uint16_t *)(&public_buf[i]); - //Color = (*p_index >> 8); - //*p_index = Color | ((*p_index & 0xFF) << 8); - i += 2; - if (*p_index == 0x0000) *p_index = LV_COLOR_BACKGROUND.full; // 0x18C3; - } - #endif // !HAS_TFT_LVGL_UI_SPI + for (i = 0; i < 200;) { + p_index = (uint16_t *)(&public_buf[i]); + //Color = (*p_index >> 8); + //*p_index = Color | ((*p_index & 0xFF) << 8); + i += 2; + if (*p_index == 0x0000) *p_index = LV_COLOR_BACKGROUND.full; + } memcpy(data_buf, public_buf, 200); - #endif // SDSUPPORT + #endif // HAS_MEDIA } -void lv_close_gcode_file() {TERN_(SDSUPPORT, card.closefile());} +void lv_close_gcode_file() {TERN_(HAS_MEDIA, card.closefile());} void lv_gcode_file_seek(uint32_t pos) { card.setIndex(pos); @@ -509,17 +485,17 @@ void cutFileName(char *path, int len, int bytePerLine, char *outStr) { wcsncpy(outStr, (const WCHAR *)beginIndex, len - 3); wcscat(outStr, (const WCHAR *)gFileTail); #else - //strncpy(outStr, beginIndex, len - 3); strncpy(outStr, beginIndex, len - 4); strcat_P(outStr, PSTR("~.g")); #endif } else { + const size_t strsize = strIndex2 - beginIndex + 1; #if _LFN_UNICODE - wcsncpy(outStr, (const WCHAR *)beginIndex, strIndex2 - beginIndex + 1); + wcsncpy(outStr, (const WCHAR *)beginIndex, strsize); wcscat(outStr, (const WCHAR *)&gFileTail[3]); #else - strncpy(outStr, beginIndex, strIndex2 - beginIndex + 1); + strncpy(outStr, beginIndex, strsize); strcat_P(outStr, PSTR("g")); #endif } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp index 5dc3861f6525..345c5dd732c0 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp @@ -80,7 +80,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { switch (obj->mks_obj_id) { case ID_PAUSE: if (uiCfg.print_state == WORKING) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA card.pauseSDPrint(); stop_print_time(); uiCfg.print_state = PAUSING; @@ -274,13 +274,13 @@ void setProBarRate() { volatile long long rate_tmp_r; if (!gCfgItems.from_flash_pic) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA rate_tmp_r = (long long)card.getIndex() * 100; #endif rate = rate_tmp_r / gCfgItems.curFilesize; } else { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA rate_tmp_r = (long long)card.getIndex(); #endif rate = (rate_tmp_r - (PREVIEW_SIZE + To_pre_view)) * 100 / (gCfgItems.curFilesize - (PREVIEW_SIZE + To_pre_view)); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp index 9ec8f1501a0b..b243c88705a3 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, HAS_TRINAMIC_CONFIG) +#if ALL(HAS_TFT_LVGL_UI, HAS_TRINAMIC_CONFIG) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp index 990cdda7e63b..d09c823b5979 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, HAS_STEALTHCHOP) +#if ALL(HAS_TFT_LVGL_UI, HAS_STEALTHCHOP) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp index a9a25db11822..74902a30ddc8 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, TOUCH_SCREEN_CALIBRATION) +#if ALL(HAS_TFT_LVGL_UI, TOUCH_SCREEN_CALIBRATION) #include "draw_ui.h" #include "draw_touch_calibration.h" diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index b510e3c0c6f3..708ad77fca8c 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -563,7 +563,7 @@ char *creat_title_text() { uintptr_t gPicturePreviewStart = 0; void preview_gcode_prehandle(char *path) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA uintptr_t pre_read_cnt = 0; uint32_t *p1; char *cur_name; @@ -593,7 +593,7 @@ char *creat_title_text() { } void gcode_preview(char *path, int xpos_pixel, int ypos_pixel) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA volatile uint32_t i, j; volatile uint16_t *p_index; char *cur_name; @@ -672,7 +672,7 @@ char *creat_title_text() { } return; } - #endif // SDSUPPORT + #endif // HAS_MEDIA } void draw_default_preview(int xpos_pixel, int ypos_pixel, uint8_t sel) { @@ -1345,7 +1345,7 @@ void lv_screen_menu_item_onoff_update(lv_obj_t *btn, const bool curValue) { lv_label_set_text((lv_obj_t*)btn->child_ll.head, curValue ? machine_menu.enable : machine_menu.disable); } -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA void sd_detection() { static bool last_sd_status; @@ -1377,7 +1377,7 @@ void LV_TASK_HANDLER() { if (TERN1(USE_SPI_DMA_TC, !get_lcd_dma_lock())) lv_task_handler(); - #if BOTH(MKS_TEST, SDSUPPORT) + #if ALL(MKS_TEST, HAS_MEDIA) if (mks_test_flag == 0x1E) mks_hardware_test(); #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.h b/Marlin/src/lcd/extui/mks_ui/draw_ui.h index 9bc583d3ad32..10b8dcee2875 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.h @@ -133,16 +133,16 @@ #define FILE_PRE_PIC_Y_OFFSET 0 #define PREVIEW_LITTLE_PIC_SIZE 40910 // 400*100+9*101+1 - #define PREVIEW_SIZE 202720 // (PREVIEW_LITTLE_PIC_SIZE+800*200+201*9+1) + #define PREVIEW_SIZE 202720 // (PREVIEW_LITTLE_PIC_SIZE+800*200+201*9+1) // machine parameter ui - #define PARA_UI_POS_X 10 - #define PARA_UI_POS_Y 50 + #define PARA_UI_POS_X 10 + #define PARA_UI_POS_Y 50 #define PARA_UI_SIZE_X 450 - #define PARA_UI_SIZE_Y 40 + #define PARA_UI_SIZE_Y 40 - #define PARA_UI_ARROW_V 12 + #define PARA_UI_ARROW_V 12 #define PARA_UI_BACK_POS_X 400 #define PARA_UI_BACK_POS_Y 270 @@ -152,31 +152,31 @@ #define PARA_UI_VALUE_SIZE_X 370 #define PARA_UI_VALUE_POS_X 400 - #define PARA_UI_VALUE_V 5 + #define PARA_UI_VALUE_V 5 #define PARA_UI_STATE_POS_X 380 - #define PARA_UI_STATE_V 2 + #define PARA_UI_STATE_V 2 #define PARA_UI_VALUE_SIZE_X_2 200 #define PARA_UI_VALUE_POS_X_2 320 - #define PARA_UI_VALUE_V_2 5 + #define PARA_UI_VALUE_V_2 5 - #define PARA_UI_VALUE_BTN_X_SIZE 70 - #define PARA_UI_VALUE_BTN_Y_SIZE 28 + #define PARA_UI_VALUE_BTN_X_SIZE 70 + #define PARA_UI_VALUE_BTN_Y_SIZE 28 - #define PARA_UI_BACK_BTN_X_SIZE 70 - #define PARA_UI_BACK_BTN_Y_SIZE 40 + #define PARA_UI_BACK_BTN_X_SIZE 70 + #define PARA_UI_BACK_BTN_Y_SIZE 40 - #define QRCODE_X 20 - #define QRCODE_Y 40 + #define QRCODE_X 20 + #define QRCODE_Y 40 #define QRCODE_WIDTH 160 -#else // ifdef TFT35 +#else // !TFT35 #define TFT_WIDTH 320 #define TFT_HEIGHT 240 -#endif // ifdef TFT35 +#endif #ifdef __cplusplus extern "C" { @@ -294,9 +294,7 @@ typedef enum { LEVELING_UI, MESHLEVELING_UI, BIND_UI, - #if HAS_BED_PROBE - NOZZLE_PROBE_OFFSET_UI, - #endif + OPTITEM(HAS_BED_PROBE, NOZZLE_PROBE_OFFSET_UI) TOOL_UI, HARDWARE_TEST_UI, WIFI_LIST_UI, @@ -402,11 +400,11 @@ typedef enum { level_pos_y4, level_pos_x5, level_pos_y5, + #if HAS_BED_PROBE - x_offset, - y_offset, - z_offset, + x_offset, y_offset, z_offset, #endif + load_length, load_speed, unload_length, diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi.h index a89bbd67d8c2..18cfd0755c1f 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi.h @@ -25,7 +25,6 @@ extern "C" { #endif - void lv_draw_wifi(); void lv_clear_wifi(); void disp_wifi_state(); 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 ad1523893243..6f1499a06833 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h @@ -25,7 +25,6 @@ extern "C" { #endif - void lv_draw_wifi_tips(); void lv_clear_wifi_tips(); @@ -38,7 +37,7 @@ extern TIPS_TYPE wifi_tips_type; typedef struct { unsigned char timer; - unsigned int timer_count; + uint16_t timer_count; } TIPS_DISP; extern TIPS_DISP tips_disp; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp b/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp index d143234fd53e..a7fb3b029342 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, PROBE_OFFSET_WIZARD) +#if ALL(HAS_TFT_LVGL_UI, PROBE_OFFSET_WIZARD) #include "draw_ui.h" #include @@ -36,7 +36,7 @@ #if HAS_LEVELING #include "../../../feature/bedlevel/bedlevel.h" - bool leveling_was_active; + bool mks_leveling_was_active; #endif extern lv_group_t *g; @@ -110,7 +110,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { case ID_M_RETURN: probe.offset.z = z_offset_backup; SET_SOFT_ENDSTOP_LOOSE(false); - TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); + TERN_(HAS_LEVELING, set_bed_leveling_enabled(mks_leveling_was_active)); #if HOMING_Z_WITH_PROBE && defined(PROBE_OFFSET_WIZARD_START_Z) set_axis_never_homed(Z_AXIS); // On cancel the Z position needs correction queue.inject_P(PSTR("G28Z")); @@ -149,8 +149,8 @@ void lv_draw_z_offset_wizard() { // Store Bed-Leveling-State and disable #if HAS_LEVELING - leveling_was_active = planner.leveling_active; - set_bed_leveling_enabled(leveling_was_active); + mks_leveling_was_active = planner.leveling_active; + set_bed_leveling_enabled(mks_leveling_was_active); #endif queue.inject_P(PSTR("G28")); diff --git a/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp b/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp index aca1db0039ba..b2615ac24b24 100644 --- a/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp +++ b/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp @@ -23,7 +23,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) +#if ALL(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "tft_lvgl_configuration.h" diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp index 0c6315d43870..63b6d487b723 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp @@ -50,7 +50,7 @@ #else constexpr static bool endstopx1_sta = true; #endif - #if HAS_X2_MIN || HAS_X2_MAX + #if USE_X2_MIN || USE_X2_MAX bool endstopx2_sta; #else constexpr static bool endstopx2_sta = true; @@ -60,7 +60,7 @@ #else constexpr static bool endstopy1_sta = true; #endif - #if HAS_Y2_MIN || HAS_Y2_MAX + #if USE_Y2_MIN || USE_Y2_MAX bool endstopy2_sta; #else constexpr static bool endstopy2_sta = true; @@ -70,7 +70,7 @@ #else constexpr static bool endstopz1_sta = true; #endif - #if HAS_Z2_MIN || HAS_Z2_MAX + #if USE_Z2_MIN || USE_Z2_MAX bool endstopz2_sta; #else constexpr static bool endstopz2_sta = true; @@ -87,34 +87,34 @@ #if PIN_EXISTS(MT_DET_2) mt_det2_sta = (READ(MT_DET_2_PIN) == LOW); #endif - #if HAS_X_MIN + #if USE_X_MIN endstopx1_sta = ESTATE(X_MIN); - #elif HAS_X_MAX + #elif USE_X_MAX endstopx1_sta = ESTATE(X_MAX); #endif - #if HAS_X2_MIN + #if USE_X2_MIN endstopx2_sta = ESTATE(X2_MIN); - #elif HAS_X2_MAX + #elif USE_X2_MAX endstopx2_sta = ESTATE(X2_MAX); #endif - #if HAS_Y_MIN + #if USE_Y_MIN endstopy1_sta = ESTATE(Y_MIN); - #elif HAS_Y_MAX + #elif USE_Y_MAX endstopy1_sta = ESTATE(Y_MAX); #endif - #if HAS_Y2_MIN + #if USE_Y2_MIN endstopy2_sta = ESTATE(Y2_MIN); - #elif HAS_Y2_MAX + #elif USE_Y2_MAX endstopy2_sta = ESTATE(Y2_MAX); #endif - #if HAS_Z_MIN + #if USE_Z_MIN endstopz1_sta = ESTATE(Z_MIN); - #elif HAS_Z_MAX + #elif USE_Z_MAX endstopz1_sta = ESTATE(Z_MAX); #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN endstopz2_sta = ESTATE(Z2_MIN); - #elif HAS_Z2_MAX + #elif USE_Z2_MAX endstopz2_sta = ESTATE(Z2_MAX); #endif } @@ -128,34 +128,34 @@ #if PIN_EXISTS(MT_DET_2) mt_det2_sta = (READ(MT_DET_2_PIN) == HIGH); #endif - #if HAS_X_MIN + #if USE_X_MIN endstopx1_sta = !ESTATE(X_MIN); - #elif HAS_X_MAX + #elif USE_X_MAX endstopx1_sta = !ESTATE(X_MAX); #endif - #if HAS_X2_MIN + #if USE_X2_MIN endstopx2_sta = !ESTATE(X2_MIN); - #elif HAS_X2_MAX + #elif USE_X2_MAX endstopx2_sta = !ESTATE(X2_MAX); #endif - #if HAS_Y_MIN + #if USE_Y_MIN endstopy1_sta = !ESTATE(Y_MIN); - #elif HAS_Y_MAX + #elif USE_Y_MAX endstopy1_sta = !ESTATE(Y_MAX); #endif - #if HAS_Y2_MIN + #if USE_Y2_MIN endstopy2_sta = !ESTATE(Y2_MIN); - #elif HAS_Y2_MAX + #elif USE_Y2_MAX endstopy2_sta = !ESTATE(Y2_MAX); #endif - #if HAS_Z_MIN + #if USE_Z_MIN endstopz1_sta = !ESTATE(Z_MIN); - #elif HAS_Z_MAX + #elif USE_Z_MAX endstopz1_sta = !ESTATE(Z_MAX); #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN endstopz2_sta = !ESTATE(Z2_MIN); - #elif HAS_Z2_MAX + #elif USE_Z2_MAX endstopz2_sta = !ESTATE(Z2_MAX); #endif } @@ -178,7 +178,9 @@ SET_INPUT_PULLUP(MKS_TEST_PS_ON_PIN); SET_INPUT_PULLUP(SERVO0_PIN); - OUT_WRITE(X_ENABLE_PIN, LOW); + #if HAS_X_AXIS + OUT_WRITE(X_ENABLE_PIN, LOW); + #endif #if HAS_Y_AXIS OUT_WRITE(Y_ENABLE_PIN, LOW); #endif @@ -205,7 +207,7 @@ void mks_test_beeper() { buzzer.click(100); } - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA void mks_gpio_test() { init_test_gpio(); @@ -240,7 +242,9 @@ void mks_hardware_test() { if (millis() % 2000 < 1000) { thermalManager.fan_speed[0] = 255; - WRITE(X_DIR_PIN, LOW); + #if HAS_X_AXIS + WRITE(X_DIR_PIN, LOW); + #endif #if HAS_Y_AXIS WRITE(Y_DIR_PIN, LOW); #endif @@ -265,11 +269,13 @@ } else { thermalManager.fan_speed[0] = 0; - WRITE(X_DIR_PIN, HIGH); + #if HAS_X_AXIS + WRITE(X_DIR_PIN, HIGH); + #endif #if HAS_Y_AXIS WRITE(Y_DIR_PIN, HIGH); #endif - #if HAS_Y_AXIS + #if HAS_Z_AXIS WRITE(Z_DIR_PIN, HIGH); #endif #if HAS_EXTRUDERS @@ -690,7 +696,7 @@ void disp_char_1624(uint16_t x, uint16_t y, uint8_t c, uint16_t charColor, uint1 for (uint16_t i = 0; i < 24; i++) { const uint16_t tmp_char = pgm_read_word(&ASCII_Table_16x24[((c - 0x20) * 24) + i]); for (uint16_t j = 0; j < 16; j++) - SPI_TFT.SetPoint(x + j, y + i, ((tmp_char >> j) & 0x01) ? charColor : bkColor); + SPI_TFT.setPoint(x + j, y + i, ((tmp_char >> j) & 0x01) ? charColor : bkColor); } } @@ -706,7 +712,7 @@ void disp_string(uint16_t x, uint16_t y, FSTR_P const fstr, uint16_t charColor, } void disp_assets_update() { - SPI_TFT.LCD_clear(0x0000); + SPI_TFT.lcdClear(0x0000); disp_string(100, 140, F("Assets Updating..."), 0xFFFF, 0x0000); } @@ -716,14 +722,13 @@ void disp_assets_update_progress(FSTR_P const fmsg) { char buf[buflen]; memset(buf, ' ', buflen); strncpy_P(buf, FTOP(fmsg), buflen - 1); - buf[buflen - 1] = '\0'; disp_string(100, 165, buf, 0xFFFF, 0x0000); #else disp_string(100, 165, FTOP(fmsg), 0xFFFF, 0x0000); #endif } -#if BOTH(MKS_TEST, SDSUPPORT) +#if ALL(MKS_TEST, HAS_MEDIA) uint8_t mks_test_flag = 0; const char *MKSTestPath = "MKS_TEST"; void mks_test_get() { diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.h b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h index c0cdacd963f4..f73f4e645910 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.h +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h @@ -26,7 +26,7 @@ #include // Functions for MKS_TEST -#if BOTH(MKS_TEST, SDSUPPORT) +#if ALL(MKS_TEST, HAS_MEDIA) void mks_hardware_test(); void mks_test_get(); void mks_gpio_test(); diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index d642d81f6baa..aaa7a919f672 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -24,7 +24,6 @@ #if HAS_TFT_LVGL_UI -#include "string.h" #include "draw_ui.h" #include "pic_manager.h" #include "draw_ready_print.h" @@ -34,9 +33,11 @@ #include "../../../sd/cardreader.h" #include "../../../MarlinCore.h" +#include + extern uint16_t DeviceCode; -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA extern char *createFilename(char * const buffer, const dir_t &p); #endif @@ -290,7 +291,7 @@ void spiFlashErase_PIC() { uint32_t LogoWrite_Addroffset = 0; -uint8_t Pic_Logo_Write(uint8_t *LogoName, uint8_t *Logo_Wbuff, uint32_t LogoWriteSize) { +uint8_t picLogoWrite(uint8_t *LogoName, uint8_t *Logo_Wbuff, uint32_t LogoWriteSize) { if (LogoWriteSize <= 0) return 0; W25QXX.SPI_FLASH_BufferWrite(Logo_Wbuff, PIC_LOGO_ADDR + LogoWrite_Addroffset, LogoWriteSize); @@ -307,7 +308,7 @@ uint8_t Pic_Logo_Write(uint8_t *LogoName, uint8_t *Logo_Wbuff, uint32_t LogoWrit } uint32_t TitleLogoWrite_Addroffset = 0; -uint8_t Pic_TitleLogo_Write(uint8_t *TitleLogoName, uint8_t *TitleLogo_Wbuff, uint32_t TitleLogoWriteSize) { +uint8_t picTitleLogoWrite(uint8_t *TitleLogoName, uint8_t *TitleLogo_Wbuff, uint32_t TitleLogoWriteSize) { if (TitleLogoWriteSize <= 0) return 0; if ((DeviceCode == 0x9488) || (DeviceCode == 0x5761)) @@ -328,15 +329,15 @@ void default_view_Write(uint8_t *default_view__Rbuff, uint32_t default_view_Writ default_view_addroffset_r = 0; } -uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { +uint32_t picInfoWrite(uint8_t *P_name, uint32_t P_size) { uint8_t pic_counter = 0; - uint32_t Pic_SaveAddr; + uint32_t picSaveAddr; uint32_t Pic_SizeSaveAddr; - uint32_t Pic_NameSaveAddr; - uint8_t Pname_temp; + uint32_t picNameSaveAddr; + uint8_t pNameTemp; uint32_t i, j; uint32_t name_len = 0; - uint32_t SaveName_len = 0; + uint32_t saveNameLen = 0; union union32 size_tmp; W25QXX.SPI_FLASH_BufferRead(&pic_counter, PIC_COUNTER_ADDR, 1); @@ -345,15 +346,15 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { pic_counter = 0; if ((DeviceCode == 0x9488) || (DeviceCode == 0x5761)) - Pic_SaveAddr = PIC_DATA_ADDR_TFT35 + pic_counter * PER_PIC_MAX_SPACE_TFT35; + picSaveAddr = PIC_DATA_ADDR_TFT35 + pic_counter * PER_PIC_MAX_SPACE_TFT35; else - Pic_SaveAddr = PIC_DATA_ADDR_TFT32 + pic_counter * PER_PIC_MAX_SPACE_TFT32; + picSaveAddr = PIC_DATA_ADDR_TFT32 + pic_counter * PER_PIC_MAX_SPACE_TFT32; for (j = 0; j < pic_counter; j++) { do { - W25QXX.SPI_FLASH_BufferRead(&Pname_temp, PIC_NAME_ADDR + SaveName_len, 1); - SaveName_len++; - } while (Pname_temp != '\0'); + W25QXX.SPI_FLASH_BufferRead(&pNameTemp, PIC_NAME_ADDR + saveNameLen, 1); + saveNameLen++; + } while (pNameTemp != '\0'); } i = 0; while ((*(P_name + i) != '\0')) { @@ -361,8 +362,8 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { name_len++; } - Pic_NameSaveAddr = PIC_NAME_ADDR + SaveName_len; - W25QXX.SPI_FLASH_BufferWrite(P_name, Pic_NameSaveAddr, name_len + 1); + picNameSaveAddr = PIC_NAME_ADDR + saveNameLen; + W25QXX.SPI_FLASH_BufferWrite(P_name, picNameSaveAddr, name_len + 1); Pic_SizeSaveAddr = PIC_SIZE_ADDR + 4 * pic_counter; size_tmp.dwords = P_size; W25QXX.SPI_FLASH_BufferWrite(size_tmp.bytes, Pic_SizeSaveAddr, 4); @@ -371,14 +372,14 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { W25QXX.SPI_FLASH_SectorErase(PIC_COUNTER_ADDR); W25QXX.SPI_FLASH_BufferWrite(&pic_counter, PIC_COUNTER_ADDR, 1); - return Pic_SaveAddr; + return picSaveAddr; } -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA static void dosName2LongName(const char dosName[11], char *longName) { uint8_t j = 0; - LOOP_L_N(i, 11) { + for (uint8_t i = 0; i < 11; ++i) { if (i == 8) longName[j++] = '.'; if (dosName[i] == '\0' || dosName[i] == ' ') continue; longName[j++] = dosName[i]; @@ -387,7 +388,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { } static int8_t arrayFindStr(FSTR_P const arr[], uint8_t arraySize, const char *str) { - for (uint8_t a = 0; a < arraySize; a++) { + for (uint8_t a = 0; a < arraySize; ++a) { if (strcasecmp(FTOP(arr[a]), str) == 0) return a; } @@ -429,14 +430,14 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { do { hal.watchdog_refresh(); pbr = file.read(public_buf, BMP_WRITE_BUF_LEN); - Pic_Logo_Write((uint8_t*)fn, public_buf, pbr); + picLogoWrite((uint8_t*)fn, public_buf, pbr); } while (pbr >= BMP_WRITE_BUF_LEN); } else if (assetType == ASSET_TYPE_TITLE_LOGO) { do { hal.watchdog_refresh(); pbr = file.read(public_buf, BMP_WRITE_BUF_LEN); - Pic_TitleLogo_Write((uint8_t*)fn, public_buf, pbr); + picTitleLogoWrite((uint8_t*)fn, public_buf, pbr); } while (pbr >= BMP_WRITE_BUF_LEN); } else if (assetType == ASSET_TYPE_G_PREVIEW) { @@ -447,7 +448,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { } while (pbr >= BMP_WRITE_BUF_LEN); } else if (assetType == ASSET_TYPE_ICON) { - Pic_Write_Addr = Pic_Info_Write((uint8_t*)fn, pfileSize); + Pic_Write_Addr = picInfoWrite((uint8_t*)fn, pfileSize); SPIFlash.beginWrite(Pic_Write_Addr); #if HAS_SPI_FLASH_COMPRESSION do { @@ -547,9 +548,9 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { void spi_flash_read_test() { W25QXX.SPI_FLASH_BufferRead(public_buf, UNIGBK_FLASH_ADDR, BMP_WRITE_BUF_LEN); } #endif -#endif // SDSUPPORT +#endif // HAS_MEDIA -void Pic_Read(uint8_t *Pname, uint8_t *P_Rbuff) { +void picRead(uint8_t *Pname, uint8_t *P_Rbuff) { uint8_t i, j; uint8_t Pic_cnt; uint32_t tmp_cnt = 0; @@ -595,7 +596,7 @@ void lv_pic_test(uint8_t *P_Rbuff, uint32_t addr, uint32_t size) { #endif uint32_t logo_addroffset = 0; -void Pic_Logo_Read(uint8_t *LogoName, uint8_t *Logo_Rbuff, uint32_t LogoReadsize) { +void picLogoRead(uint8_t *LogoName, uint8_t *Logo_Rbuff, uint32_t LogoReadsize) { W25QXX.init(SPI_QUARTER_SPEED); W25QXX.SPI_FLASH_BufferRead(Logo_Rbuff, PIC_LOGO_ADDR + logo_addroffset, LogoReadsize); logo_addroffset += LogoReadsize; diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.h b/Marlin/src/lcd/extui/mks_ui/pic_manager.h index cdcc5b76b8a9..1483b96461e4 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.h +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.h @@ -154,8 +154,8 @@ typedef struct pic_msg PIC_MSG; #define PIC_SIZE_xM 6 #define FONT_SIZE_xM 2 -void Pic_Read(uint8_t *Pname, uint8_t *P_Rbuff); -void Pic_Logo_Read(uint8_t *LogoName, uint8_t *Logo_Rbuff, uint32_t LogoReadsize); +void picRead(uint8_t *Pname, uint8_t *P_Rbuff); +void picLogoRead(uint8_t *LogoName, uint8_t *Logo_Rbuff, uint32_t LogoReadsize); void lv_pic_test(uint8_t *P_Rbuff, uint32_t addr, uint32_t size); uint32_t lv_get_pic_addr(uint8_t *Pname); void get_spi_flash_data(const char *rec_buf, int offset, int size); diff --git a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp index 8f5b89cf347c..26979af2703f 100644 --- a/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp +++ b/Marlin/src/lcd/extui/mks_ui/printer_operation.cpp @@ -45,7 +45,7 @@ extern bool flash_preview_begin, default_preview_flg, gcode_preview_over; void printer_state_polling() { char str_1[16]; if (uiCfg.print_state == PAUSING) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (!planner.has_blocks_queued() && card.getIndex() > MIN_FILE_PRINTED) uiCfg.waitEndMoves++; diff --git a/Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h index f0b19d4e0275..35c753ad1ac3 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h @@ -154,7 +154,6 @@ #define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_FR "Chargement terminé,\n pour revenir!" #define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_FR "Déchargement terminé,\n pour revenir!" - #define PRE_HEAT_EXT_TEXT_FR "E" #define PRE_HEAT_BED_TEXT_FR "Bed" diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index 9a8996330365..081b8c03ed57 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -36,10 +36,11 @@ #include #include "../../../MarlinCore.h" +#include "../../marlinui.h" + #include "../../../inc/MarlinConfig.h" #include HAL_PATH(../../.., tft/xpt2046.h) -#include "../../marlinui.h" XPT2046 touch; #if ENABLED(POWER_LOSS_RECOVERY) @@ -50,7 +51,7 @@ XPT2046 touch; #include "../../../module/servo.h" #endif -#if EITHER(PROBE_TARE, HAS_Z_SERVO_PROBE) +#if ANY(PROBE_TARE, HAS_Z_SERVO_PROBE) #include "../../../module/probe.h" #endif @@ -78,7 +79,7 @@ XPT2046 touch; static lv_disp_buf_t disp_buf; lv_group_t* g; -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA void UpdateAssets(); #endif uint16_t DeviceCode = 0x9488; @@ -128,15 +129,14 @@ void tft_lvgl_init() { hal.watchdog_refresh(); // LVGL init takes time // Init TFT first! - SPI_TFT.spi_init(SPI_FULL_SPEED); - SPI_TFT.LCD_init(); + SPI_TFT.spiInit(SPI_FULL_SPEED); + SPI_TFT.lcdInit(); hal.watchdog_refresh(); // LVGL init takes time #if ENABLED(USB_FLASH_DRIVE_SUPPORT) uint16_t usb_flash_loop = 1000; #if ENABLED(MULTI_VOLUME) && !HAS_SD_HOST_DRIVE - SET_INPUT_PULLUP(SD_DETECT_PIN); if (IS_SD_INSERTED()) card.changeMedia(&card.media_driver_sdcard); else @@ -156,7 +156,7 @@ void tft_lvgl_init() { hal.watchdog_refresh(); // LVGL init takes time - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA UpdateAssets(); hal.watchdog_refresh(); // LVGL init takes time TERN_(MKS_TEST, mks_test_get()); @@ -237,11 +237,11 @@ void tft_lvgl_init() { uiCfg.print_state = REPRINTING; #if ENABLED(LONG_FILENAME_HOST_SUPPORT) - strncpy(public_buf_m, recovery.info.sd_filename, sizeof(public_buf_m)); + strncpy(public_buf_m, recovery.info.sd_filename, sizeof(public_buf_m) - 1); card.printLongPath(public_buf_m); - strncpy(list_file.long_name[sel_id], card.longFilename, sizeof(list_file.long_name[0])); + strncpy(list_file.long_name[sel_id], card.longFilename, sizeof(list_file.long_name[0]) - 1); #else - strncpy(list_file.long_name[sel_id], recovery.info.sd_filename, sizeof(list_file.long_name[0])); + strncpy(list_file.long_name[sel_id], recovery.info.sd_filename, sizeof(list_file.long_name[0]) - 1); #endif lv_draw_printing(); } @@ -249,7 +249,7 @@ void tft_lvgl_init() { if (ready) lv_draw_ready_print(); - #if BOTH(MKS_TEST, SDSUPPORT) + #if ALL(MKS_TEST, HAS_MEDIA) if (mks_test_flag == 0x1E) mks_gpio_test(); #endif } @@ -301,18 +301,16 @@ void lv_fill_rect(lv_coord_t x1, lv_coord_t y1, lv_coord_t x2, lv_coord_t y2, lv W25QXX.init(SPI_QUARTER_SPEED); } -#define TICK_CYCLE 1 - -unsigned int getTickDiff(unsigned int curTick, unsigned int lastTick) { - return TICK_CYCLE * (lastTick <= curTick ? (curTick - lastTick) : (0xFFFFFFFF - lastTick + curTick)); +uint16_t getTickDiff(const uint16_t curTick, const uint16_t lastTick) { + return (TICK_CYCLE) * (lastTick <= curTick ? (curTick - lastTick) : (0xFFFFFFFF - lastTick + curTick)); } -static bool get_point(int16_t *x, int16_t *y) { +static bool get_point(int16_t * const x, int16_t * const y) { if (!touch.getRawPoint(x, y)) return false; #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)) lv_update_touch_calibration_screen(); return false; } @@ -327,27 +325,10 @@ static bool get_point(int16_t *x, int16_t *y) { } bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data) { - static int16_t last_x = 0, last_y = 0; - if (get_point(&last_x, &last_y)) { - #if TFT_ROTATION == TFT_ROTATE_180 - data->point.x = TFT_WIDTH - last_x; - data->point.y = TFT_HEIGHT - last_y; - #else - data->point.x = last_x; - data->point.y = last_y; - #endif - data->state = LV_INDEV_STATE_PR; - } - else { - #if TFT_ROTATION == TFT_ROTATE_180 - data->point.x = TFT_WIDTH - last_x; - data->point.y = TFT_HEIGHT - last_y; - #else - data->point.x = last_x; - data->point.y = last_y; - #endif - data->state = LV_INDEV_STATE_REL; - } + static xy_int_t last { 0, 0 }; + data->state = get_point(&last.x, &last.y) ? LV_INDEV_STATE_PR : LV_INDEV_STATE_REL; + data->point.x = (TFT_ROTATION == TFT_ROTATE_180) ? TFT_WIDTH - last.x : last.x; + data->point.y = (TFT_ROTATION == TFT_ROTATE_180) ? TFT_HEIGHT - last.y : last.y; return false; // Return `false` since no data is buffering or left to read } @@ -563,7 +544,7 @@ void lv_encoder_pin_init() { #endif // HAS_ENCODER_ACTION -#if __PLAT_NATIVE_SIM__ +#ifdef __PLAT_NATIVE_SIM__ #include typedef void (*lv_log_print_g_cb_t)(lv_log_level_t level, const char *, uint32_t, const char *); extern "C" void lv_log_register_print_cb(lv_log_print_g_cb_t print_cb) {} 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 0368140b2858..d847cfb1933b 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h @@ -32,8 +32,6 @@ #include -//#define TFT_ROTATION TFT_ROTATE_180 - extern uint8_t bmp_public_buf[14 * 1024]; extern uint8_t public_buf[513]; @@ -42,11 +40,7 @@ void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * co bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data); bool my_mousewheel_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data); -void LCD_Clear(uint16_t Color); -void tft_set_point(uint16_t x, uint16_t y, uint16_t point); -void LCD_setWindowArea(uint16_t StartX, uint16_t StartY, uint16_t width, uint16_t height); -void LCD_WriteRAM_Prepare(); -void lcd_draw_logo(); +void lcdClear(uint16_t color); void lv_encoder_pin_init(); void lv_update_encoder(); diff --git a/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp index 6e9c37b0169e..aaddbcb892d2 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.cpp @@ -167,7 +167,7 @@ void machine_setting_disp() { machine_menu.Extrude_Min_Temper = EXTRUD_MIN_TEMPER_CN; machine_menu.HotbedConfTitle = HOTBED_CONF_TITLE_CN; - machine_menu.HotbedAjustType = HOTBED_ADJUST_CN; + machine_menu.HotbedAdjustType = HOTBED_ADJUST_CN; machine_menu.HotbedMinTemperature = HOTBED_MIN_TEMPERATURE_CN; machine_menu.HotbedMaxTemperature = HOTBED_MAX_TEMPERATURE_CN; @@ -395,7 +395,7 @@ void machine_setting_disp() { machine_menu.Extrude_Min_Temper = EXTRUD_MIN_TEMPER_T_CN; machine_menu.HotbedConfTitle = HOTBED_CONF_TITLE_T_CN; - machine_menu.HotbedAjustType = HOTBED_ADJUST_T_CN; + machine_menu.HotbedAdjustType = HOTBED_ADJUST_T_CN; machine_menu.HotbedMinTemperature = HOTBED_MIN_TEMPERATURE_T_CN; machine_menu.HotbedMaxTemperature = HOTBED_MAX_TEMPERATURE_T_CN; @@ -627,7 +627,7 @@ void machine_setting_disp() { machine_menu.HotbedEnable = HOTBED_ENABLE_EN; machine_menu.HotbedConfTitle = HOTBED_CONF_TITLE_EN; - machine_menu.HotbedAjustType = HOTBED_ADJUST_EN; + machine_menu.HotbedAdjustType = HOTBED_ADJUST_EN; machine_menu.HotbedMinTemperature = HOTBED_MIN_TEMPERATURE_EN; machine_menu.HotbedMaxTemperature = HOTBED_MAX_TEMPERATURE_EN; diff --git a/Marlin/src/lcd/extui/mks_ui/tft_multi_language.h b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.h index 2a5135dded4f..9a6109cbe7c3 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_multi_language.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_multi_language.h @@ -150,7 +150,7 @@ typedef struct machine_common_disp { const char *HotbedEnable; const char *HotbedConfTitle; - const char *HotbedAjustType; + const char *HotbedAdjustType; const char *HotbedMinTemperature; const char *HotbedMaxTemperature; diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp index 0e55b3448ba1..cb5b7f0b68c8 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp @@ -25,7 +25,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) +#if ALL(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "tft_lvgl_configuration.h" @@ -230,7 +230,7 @@ void WifiSerial::_rx_complete_irq(serial_t *obj) { WRITE(WIFI_IO1_PIN, HIGH); - rx_buffer_index_t i = (unsigned int)(obj->rx_head + 1) % WIFI_RX_BUF_SIZE; + rx_buffer_index_t i = uint16_t(obj->rx_head + 1) % WIFI_RX_BUF_SIZE; // if we should be storing the received character into the location // just before the tail (meaning that the head would advance to the @@ -292,7 +292,7 @@ void WifiSerial::begin(unsigned long baud, byte config) { case 0: Error_Handler(); break; } - uart_init(&_serial, (uint32_t)baud, databits, parity, stopbits); + uart_init(&_serial, uint32_t(baud), databits, parity, stopbits); enableHalfDuplexRx(); if (baud == WIFI_BAUDRATE) uart_attach_rx_callback(&_serial, _rx_complete_irq); @@ -311,7 +311,7 @@ void WifiSerial::end() { } int WifiSerial::available() { - return ((unsigned int)(WIFI_RX_BUF_SIZE + _serial.rx_head - _serial.rx_tail)) % WIFI_RX_BUF_SIZE; + return uint16_t(WIFI_RX_BUF_SIZE + _serial.rx_head - _serial.rx_tail) % WIFI_RX_BUF_SIZE; } // @@ -322,7 +322,7 @@ int WifiSerial::read() { // if the head isn't ahead of the tail, we don't have any characters if (_serial.rx_head == _serial.rx_tail) return -1; - unsigned char c = _serial.rx_buff[_serial.rx_tail]; + uint8_t c = _serial.rx_buff[_serial.rx_tail]; _serial.rx_tail = (rx_buffer_index_t)(_serial.rx_tail + 1) % WIFI_RX_BUF_SIZE; return c; } diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp index 654fca6cb334..92fd139dfa5d 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp @@ -23,7 +23,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) +#if ALL(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "tft_lvgl_configuration.h" diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index a8d30b442a9b..122712e9e114 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) +#if ALL(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "draw_ui.h" #include "wifi_module.h" @@ -55,11 +55,11 @@ #define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); #define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); -extern uint8_t Explore_Disk(char *path, uint8_t recu_level); +uint8_t exploreDisk(const char * const path, const uint8_t recu_level, const bool with_longnames); extern uint8_t commands_in_queue; extern uint8_t sel_id; -extern unsigned int getTickDiff(unsigned int curTick, unsigned int lastTick); +uint16_t getTickDiff(const uint16_t curTick, const uint16_t lastTick); volatile SZ_USART_FIFO WifiRxFifo; @@ -114,33 +114,34 @@ extern CLOUD_PARA cloud_para; extern bool once_flag, flash_preview_begin, default_preview_flg, gcode_preview_over; extern bool flash_dma_mode; -uint32_t getWifiTick() { return millis(); } +millis_t getWifiTick() { return millis(); } -uint32_t getWifiTickDiff(int32_t lastTick, int32_t curTick) { - return (lastTick <= curTick ? curTick - lastTick : 0xFFFFFFFF - lastTick + curTick) * TICK_CYCLE; +millis_t getWifiTickDiff(const millis_t lastTick, const millis_t curTick) { + return (TICK_CYCLE) * (lastTick <= curTick ? curTick - lastTick : 0xFFFFFFFFUL - lastTick + curTick); } -void wifi_delay(int n) { - const uint32_t start = getWifiTick(); - while (getWifiTickDiff(start, getWifiTick()) < (uint32_t)n) +void wifi_delay(const uint16_t n) { + const millis_t start = getWifiTick(); + while (getWifiTickDiff(start, getWifiTick()) < millis_t(n)) hal.watchdog_refresh(); } void wifi_reset() { - uint32_t start = getWifiTick(); + const millis_t start = getWifiTick(); WIFI_RESET(); while (getWifiTickDiff(start, getWifiTick()) < 500) { /* nada */ } WIFI_SET(); } -void mount_file_sys(uint8_t disk_type) { - if (disk_type == FILE_SYS_SD) { - TERN_(SDSUPPORT, card.mount()); - } - else if (disk_type == FILE_SYS_USB) { +void mount_file_sys(const uint8_t disk_type) { + switch (disk_type) { + case FILE_SYS_SD: TERN_(HAS_MEDIA, card.mount()); break; + case FILE_SYS_USB: break; } } +#define ILLEGAL_CHAR_REPLACE 0x5F // '_' + static bool longName2DosName(const char *longName, char *dosName) { uint8_t i = FILENAME_LENGTH; while (i) dosName[--i] = '\0'; @@ -152,18 +153,24 @@ static bool longName2DosName(const char *longName, char *dosName) { strcat_P(dosName, PSTR(".GCO")); return dosName[0] != '\0'; } + + // Fail for illegal characters + if (c < 0x21 || c == 0x7F) // Check size, non-printable characters + c = ILLEGAL_CHAR_REPLACE; // replace non-printable chars with underscore '_' else { - // Fail for illegal characters PGM_P p = PSTR("|<>^+=?/[];,*\"\\"); - while (uint8_t b = pgm_read_byte(p++)) if (b == c) return false; - if (c < 0x21 || c == 0x7F) return false; // Check size, non-printable characters - dosName[i++] = (c < 'a' || c > 'z') ? (c) : (c + ('A' - 'a')); // Uppercase required for 8.3 name + while (const uint8_t b = pgm_read_byte(p++)) + if (b == c) c = ILLEGAL_CHAR_REPLACE; // replace illegal chars with underscore '_' } + + dosName[i++] = (c < 'a' || c > 'z') ? (c) : (c + ('A' - 'a')); // Uppercase required for 8.3 name + if (i >= 5) { strcat_P(dosName, PSTR("~1.GCO")); return dosName[0] != '\0'; } } + return dosName[0] != '\0'; // Return true if any name was set } @@ -562,8 +569,8 @@ static bool longName2DosName(const char *longName, char *dosName) { #if ENABLED(MKS_WIFI_MODULE) - int raw_send_to_wifi(uint8_t *buf, int len) { - if (buf == 0 || len <= 0) return 0; + int raw_send_to_wifi(uint8_t * const buf, const int len) { + if (buf == nullptr || len <= 0) return 0; for (int i = 0; i < len; i++) WIFISERIAL.write(*(buf + i)); return len; } @@ -701,22 +708,22 @@ int package_to_wifi(WIFI_RET_TYPE type, uint8_t *buf, int len) { return 1; } +int send_to_wifi(uint8_t * const buf, const int len) { return package_to_wifi(WIFI_TRANS_INF, buf, len); } -#define SEND_OK_TO_WIFI send_to_wifi((uint8_t *)"ok\r\n", strlen("ok\r\n")) -int send_to_wifi(uint8_t *buf, int len) { return package_to_wifi(WIFI_TRANS_INF, buf, len); } +inline void send_ok_to_wifi() { send_to_wifi((uint8_t *)"ok\r\n", strlen("ok\r\n")); } void set_cur_file_sys(int fileType) { gCfgItems.fileSysType = fileType; } -void get_file_list(char *path) { +void get_file_list(const char * const path, const bool with_longnames) { if (!path) return; if (gCfgItems.fileSysType == FILE_SYS_SD) { - TERN_(SDSUPPORT, card.mount()); + TERN_(HAS_MEDIA, card.mount()); } else if (gCfgItems.fileSysType == FILE_SYS_USB) { // udisk } - Explore_Disk(path, 0); + exploreDisk(path, 0, with_longnames); } char wait_ip_back_flag = 0; @@ -795,7 +802,7 @@ typedef struct { uint8_t tail; } ESP_PROTOC_FRAME; -static int cut_msg_head(uint8_t *msg, uint16_t msgLen, uint16_t cutLen) { +static int cut_msg_head(uint8_t * const msg, const uint16_t msgLen, uint16_t cutLen) { if (msgLen < cutLen) return 0; else if (msgLen == cutLen) { @@ -811,25 +818,31 @@ static int cut_msg_head(uint8_t *msg, uint16_t msgLen, uint16_t cutLen) { return msgLen - cutLen; } -uint8_t Explore_Disk(char *path , uint8_t recu_level) { - char tmp[200]; +uint8_t exploreDisk(const char * const path, const uint8_t recu_level, const bool with_longnames) { char Fstream[200]; if (!path) return 0; - const uint8_t fileCnt = card.get_num_Files(); + const int16_t fileCnt = card.get_num_items(); - for (uint8_t i = 0; i < fileCnt; i++) { - card.getfilename_sorted(SD_ORDER(i, fileCnt)); - ZERO(tmp); - strcpy(tmp, card.filename); + MediaFile file; + MediaFile *diveDir; + for (int16_t i = 0; i < fileCnt; i++) { + card.selectFileByIndexSorted(i); ZERO(Fstream); - strcpy(Fstream, tmp); + strcpy(Fstream, card.filename); if (card.flag.filenameIsDir && recu_level <= 10) strcat_P(Fstream, PSTR(".DIR")); + strcat_P(Fstream, PSTR(" 0")); // report 0 file size + + if (with_longnames) { + strcat_P(Fstream, PSTR(" ")); + strcat_P(Fstream, card.longest_filename()); + } + strcat_P(Fstream, PSTR("\r\n")); send_to_wifi((uint8_t*)Fstream, strlen(Fstream)); } @@ -837,434 +850,449 @@ uint8_t Explore_Disk(char *path , uint8_t recu_level) { return fileCnt; } -static void wifi_gcode_exec(uint8_t *cmd_line) { +static void wifi_gcode_exec(uint8_t * const cmd_line) { int8_t tempBuf[100] = { 0 }; - uint8_t *tmpStr = 0; int cmd_value; volatile int print_rate; - if (strchr((char *)cmd_line, '\n') && (strchr((char *)cmd_line, 'G') || strchr((char *)cmd_line, 'M') || strchr((char *)cmd_line, 'T'))) { - tmpStr = (uint8_t *)strchr((char *)cmd_line, '\n'); - if (tmpStr) *tmpStr = '\0'; - - tmpStr = (uint8_t *)strchr((char *)cmd_line, '\r'); - if (tmpStr) *tmpStr = '\0'; - tmpStr = (uint8_t *)strchr((char *)cmd_line, '*'); - if (tmpStr) *tmpStr = '\0'; + // Only accept commands with a linefeed + char * const lfStr = strchr((char *)cmd_line, '\n'); + if (!lfStr) return; + + // Only accept commands with G, M, or T somewhere + const char * const gStr = strchr((char *)cmd_line, 'G'); + const char * const mStr = strchr((char *)cmd_line, 'M'); + const char * const tStr = strchr((char *)cmd_line, 'T'); + if (!(gStr || mStr || tStr)) return; + + // Replace the linefeed with nul terminator + *lfStr = '\0'; + + // Terminate on the first cr, if any + char * const crStr = strchr((char *)cmd_line, '\r'); + if (crStr) *crStr = '\0'; + + // Terminate on the checksum marker, if any + char * const aStr = strchr((char *)cmd_line, '*'); + if (aStr) *aStr = '\0'; + + // Handle some M commands here + if (mStr) { + cmd_value = atoi(mStr + 1); + char * const spStr = strchr(mStr, ' '); + + switch (cmd_value) { + + case 20: // M20: Print SD / µdisk file + file_writer.fileTransfer = 0; + if (uiCfg.print_state == IDLE) { + int index = 0; + if (spStr == nullptr) { + gCfgItems.fileSysType = FILE_SYS_SD; + send_to_wifi((uint8_t *)(STR_BEGIN_FILE_LIST "\r\n"), strlen(STR_BEGIN_FILE_LIST "\r\n")); + get_file_list("0:/", false); + send_to_wifi((uint8_t *)(STR_END_FILE_LIST "\r\n"), strlen(STR_END_FILE_LIST "\r\n")); + send_ok_to_wifi(); + break; + } - tmpStr = (uint8_t *)strchr((char *)cmd_line, 'M'); - if (tmpStr) { - cmd_value = atoi((char *)(tmpStr + 1)); - tmpStr = (uint8_t *)strchr((char *)tmpStr, ' '); + while (mStr[index] == ' ') index++; - switch (cmd_value) { + if (gCfgItems.wifi_type == ESP_WIFI) { + char * const path = (char *)tempBuf; + if (strlen(&mStr[index]) < 80) { + send_to_wifi((uint8_t *)(STR_BEGIN_FILE_LIST "\r\n"), strlen(STR_BEGIN_FILE_LIST "\r\n")); - case 20: // M20: Print SD / µdisk file - file_writer.fileTransfer = 0; - if (uiCfg.print_state == IDLE) { - int index = 0; + if (strncmp(&mStr[index], "1:", 2) == 0) + gCfgItems.fileSysType = FILE_SYS_SD; + else if (strncmp(&mStr[index], "0:", 2) == 0) + gCfgItems.fileSysType = FILE_SYS_USB; - if (tmpStr == 0) { - gCfgItems.fileSysType = FILE_SYS_SD; - send_to_wifi((uint8_t *)(STR_BEGIN_FILE_LIST "\r\n"), strlen(STR_BEGIN_FILE_LIST "\r\n")); - get_file_list((char *)"0:/"); + strcpy(path, &mStr[index]); + const bool with_longnames = strchr(mStr, 'L') != nullptr; + get_file_list(path, with_longnames); send_to_wifi((uint8_t *)(STR_END_FILE_LIST "\r\n"), strlen(STR_END_FILE_LIST "\r\n")); - SEND_OK_TO_WIFI; - break; } + send_ok_to_wifi(); + } + } + break; - while (tmpStr[index] == ' ') index++; + case 21: send_ok_to_wifi(); break; // Init SD card - if (gCfgItems.wifi_type == ESP_WIFI) { - char *path = (char *)tempBuf; + case 23: + // Select the file + if (uiCfg.print_state == IDLE) { + int index = 0; + while (mStr[index] == ' ') index++; - if (strlen((char *)&tmpStr[index]) < 80) { - send_to_wifi((uint8_t *)(STR_BEGIN_FILE_LIST "\r\n"), strlen(STR_BEGIN_FILE_LIST "\r\n")); + if (strstr_P(&mStr[index], PSTR(".g")) || strstr_P(&mStr[index], PSTR(".G"))) { + if (strlen(&mStr[index]) < 80) { + ZERO(list_file.file_name[sel_id]); + ZERO(list_file.long_name[sel_id]); + uint8_t has_path_selected = 0; - if (strncmp((char *)&tmpStr[index], "1:", 2) == 0) + if (gCfgItems.wifi_type == ESP_WIFI) { + if (strncmp_P(&mStr[index], PSTR("1:"), 2) == 0) { gCfgItems.fileSysType = FILE_SYS_SD; - else if (strncmp((char *)&tmpStr[index], "0:", 2) == 0) + has_path_selected = 1; + } + else if (strncmp_P(&mStr[index], PSTR("0:"), 2) == 0) { gCfgItems.fileSysType = FILE_SYS_USB; + has_path_selected = 1; + } + else if (mStr[index] != '/') + strcat_P((char *)list_file.file_name[sel_id], PSTR("/")); + + if (file_writer.fileTransfer == 1) { + char dosName[FILENAME_LENGTH]; + uint8_t fileName[sizeof(list_file.file_name[sel_id])]; + fileName[0] = '\0'; + if (has_path_selected == 1) { + strcat((char *)fileName, &mStr[index + 3]); + strcat_P((char *)list_file.file_name[sel_id], PSTR("/")); + } + else strcat((char *)fileName, &mStr[index]); + if (!longName2DosName((const char *)fileName, dosName)) + strcpy_P(list_file.file_name[sel_id], PSTR("notValid")); + strcat((char *)list_file.file_name[sel_id], dosName); + strcat((char *)list_file.long_name[sel_id], (const char *)fileName); + } + else { + strcat((char *)list_file.file_name[sel_id], &mStr[index]); + strcat((char *)list_file.long_name[sel_id], &mStr[index]); + } + + } + else + strcpy(list_file.file_name[sel_id], &mStr[index]); + + char *cur_name = strrchr(list_file.file_name[sel_id],'/'); + + card.openFileRead(cur_name); - strcpy((char *)path, (char *)&tmpStr[index]); - get_file_list(path); - send_to_wifi((uint8_t *)(STR_END_FILE_LIST "\r\n"), strlen(STR_END_FILE_LIST "\r\n")); + if (card.isFileOpen()) + send_to_wifi((uint8_t *)"File selected\r\n", strlen("File selected\r\n")); + else { + send_to_wifi((uint8_t *)"file.open failed\r\n", strlen("file.open failed\r\n")); + strcpy_P(list_file.file_name[sel_id], PSTR("notValid")); } - SEND_OK_TO_WIFI; + send_ok_to_wifi(); } } - break; - - case 21: SEND_OK_TO_WIFI; break; // Init SD card + } + break; - case 23: - // Select the file + case 24: + if (strcmp_P(list_file.file_name[sel_id], PSTR("notValid")) != 0) { if (uiCfg.print_state == IDLE) { - int index = 0; - while (tmpStr[index] == ' ') index++; - - if (strstr_P((char *)&tmpStr[index], PSTR(".g")) || strstr_P((char *)&tmpStr[index], PSTR(".G"))) { - if (strlen((char *)&tmpStr[index]) < 80) { - ZERO(list_file.file_name[sel_id]); - ZERO(list_file.long_name[sel_id]); - uint8_t has_path_selected = 0; - - if (gCfgItems.wifi_type == ESP_WIFI) { - if (strncmp_P((char *)&tmpStr[index], PSTR("1:"), 2) == 0) { - gCfgItems.fileSysType = FILE_SYS_SD; - has_path_selected = 1; - } - else if (strncmp_P((char *)&tmpStr[index], PSTR("0:"), 2) == 0) { - gCfgItems.fileSysType = FILE_SYS_USB; - has_path_selected = 1; - } - else if (tmpStr[index] != '/') - strcat_P((char *)list_file.file_name[sel_id], PSTR("/")); + clear_cur_ui(); + reset_print_time(); + start_print_time(); + preview_gcode_prehandle(list_file.file_name[sel_id]); + uiCfg.print_state = WORKING; + lv_draw_printing(); - if (file_writer.fileTransfer == 1) { - char dosName[FILENAME_LENGTH]; - uint8_t fileName[sizeof(list_file.file_name[sel_id])]; - fileName[0] = '\0'; - if (has_path_selected == 1) { - strcat((char *)fileName, (char *)&tmpStr[index + 3]); - strcat_P((char *)list_file.file_name[sel_id], PSTR("/")); - } - else strcat((char *)fileName, (char *)&tmpStr[index]); - if (!longName2DosName((const char *)fileName, dosName)) - strcpy_P(list_file.file_name[sel_id], PSTR("notValid")); - strcat((char *)list_file.file_name[sel_id], dosName); - strcat((char *)list_file.long_name[sel_id], dosName); - } - else { - strcat((char *)list_file.file_name[sel_id], (char *)&tmpStr[index]); - strcat((char *)list_file.long_name[sel_id], (char *)&tmpStr[index]); - } + #if HAS_MEDIA + if (!gcode_preview_over) { + char *cur_name = strrchr(list_file.file_name[sel_id], '/'); + MediaFile file; + MediaFile *curDir; + card.abortFilePrintNow(); + const char * const fname = card.diveToFile(false, curDir, cur_name); + if (!fname) return; + if (file.open(curDir, fname, O_READ)) { + gCfgItems.curFilesize = file.fileSize(); + file.close(); + update_spi_flash(); } - else - strcpy(list_file.file_name[sel_id], (char *)&tmpStr[index]); - - char *cur_name=strrchr(list_file.file_name[sel_id],'/'); - card.openFileRead(cur_name); - - if (card.isFileOpen()) - send_to_wifi((uint8_t *)"File selected\r\n", strlen("File selected\r\n")); - else { - send_to_wifi((uint8_t *)"file.open failed\r\n", strlen("file.open failed\r\n")); - strcpy_P(list_file.file_name[sel_id], PSTR("notValid")); + if (card.isFileOpen()) { + //saved_feedrate_percentage = feedrate_percentage; + feedrate_percentage = 100; + #if HAS_EXTRUDERS + planner.flow_percentage[0] = 100; + planner.e_factor[0] = planner.flow_percentage[0] * 0.01f; + #endif + #if HAS_MULTI_EXTRUDER + planner.flow_percentage[1] = 100; + planner.e_factor[1] = planner.flow_percentage[1] * 0.01f; + #endif + card.startOrResumeFilePrinting(); + TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); + once_flag = false; } - SEND_OK_TO_WIFI; } - } - } - break; - - case 24: - if (strcmp_P(list_file.file_name[sel_id], PSTR("notValid")) != 0) { - if (uiCfg.print_state == IDLE) { - clear_cur_ui(); - reset_print_time(); - start_print_time(); - preview_gcode_prehandle(list_file.file_name[sel_id]); - uiCfg.print_state = WORKING; - lv_draw_printing(); - - #if ENABLED(SDSUPPORT) - if (!gcode_preview_over) { - char *cur_name = strrchr(list_file.file_name[sel_id], '/'); - - MediaFile file; - MediaFile *curDir; - card.abortFilePrintNow(); - const char * const fname = card.diveToFile(false, curDir, cur_name); - if (!fname) return; - if (file.open(curDir, fname, O_READ)) { - gCfgItems.curFilesize = file.fileSize(); - file.close(); - update_spi_flash(); - } - card.openFileRead(cur_name); - if (card.isFileOpen()) { - //saved_feedrate_percentage = feedrate_percentage; - feedrate_percentage = 100; - #if HAS_EXTRUDERS - planner.flow_percentage[0] = 100; - planner.e_factor[0] = planner.flow_percentage[0] * 0.01f; - #endif - #if HAS_MULTI_EXTRUDER - planner.flow_percentage[1] = 100; - planner.e_factor[1] = planner.flow_percentage[1] * 0.01f; - #endif - card.startOrResumeFilePrinting(); - TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); - once_flag = false; - } - } - #endif - } - else if (uiCfg.print_state == PAUSED) { - uiCfg.print_state = RESUMING; - clear_cur_ui(); - start_print_time(); - - if (gCfgItems.from_flash_pic) - flash_preview_begin = true; - else - default_preview_flg = true; - lv_draw_printing(); - } - else if (uiCfg.print_state == REPRINTING) { - uiCfg.print_state = REPRINTED; - clear_cur_ui(); - start_print_time(); - if (gCfgItems.from_flash_pic) - flash_preview_begin = true; - else - default_preview_flg = true; - lv_draw_printing(); - } + #endif } - SEND_OK_TO_WIFI; - break; - - case 25: - // Pause print file - if (uiCfg.print_state == WORKING) { - stop_print_time(); - + else if (uiCfg.print_state == PAUSED) { + uiCfg.print_state = RESUMING; clear_cur_ui(); + start_print_time(); - #if ENABLED(SDSUPPORT) - card.pauseSDPrint(); - uiCfg.print_state = PAUSING; - #endif if (gCfgItems.from_flash_pic) flash_preview_begin = true; else default_preview_flg = true; lv_draw_printing(); - SEND_OK_TO_WIFI; } - break; - - case 26: - // Stop print file - if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED) || (uiCfg.print_state == REPRINTING)) { - stop_print_time(); - + else if (uiCfg.print_state == REPRINTING) { + uiCfg.print_state = REPRINTED; clear_cur_ui(); - #if ENABLED(SDSUPPORT) - uiCfg.print_state = IDLE; - card.abortFilePrintSoon(); - #endif + start_print_time(); + if (gCfgItems.from_flash_pic) + flash_preview_begin = true; + else + default_preview_flg = true; + lv_draw_printing(); + } + } + send_ok_to_wifi(); + break; - lv_draw_ready_print(); + case 25: + // Pause print file + if (uiCfg.print_state == WORKING) { + stop_print_time(); - SEND_OK_TO_WIFI; - } - break; - - case 27: - // Report print rate - if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED)|| (uiCfg.print_state == REPRINTING)) { - print_rate = uiCfg.totalSend; - ZERO(tempBuf); - sprintf_P((char *)tempBuf, PSTR("M27 %d\r\n"), print_rate); - send_to_wifi((uint8_t *)tempBuf, strlen((char *)tempBuf)); - } - break; + clear_cur_ui(); - case 28: - // Begin to transfer file to filesys - if (uiCfg.print_state == IDLE) { + #if HAS_MEDIA + card.pauseSDPrint(); + uiCfg.print_state = PAUSING; + #endif + if (gCfgItems.from_flash_pic) + flash_preview_begin = true; + else + default_preview_flg = true; + lv_draw_printing(); + send_ok_to_wifi(); + } + break; - int index = 0; - while (tmpStr[index] == ' ') index++; + case 26: + // Stop print file + if (uiCfg.print_state == WORKING || uiCfg.print_state == PAUSED || uiCfg.print_state == REPRINTING) { + stop_print_time(); - if (strstr_P((char *)&tmpStr[index], PSTR(".g")) || strstr_P((char *)&tmpStr[index], PSTR(".G"))) { - strcpy((char *)file_writer.saveFileName, (char *)&tmpStr[index]); + clear_cur_ui(); + #if HAS_MEDIA + uiCfg.print_state = IDLE; + card.abortFilePrintSoon(); + #endif - if (gCfgItems.fileSysType == FILE_SYS_SD) { - ZERO(tempBuf); - sprintf_P((char *)tempBuf, PSTR("%s"), file_writer.saveFileName); - } - else if (gCfgItems.fileSysType == FILE_SYS_USB) { - ZERO(tempBuf); - sprintf_P((char *)tempBuf, PSTR("%s"), (char *)file_writer.saveFileName); - } - mount_file_sys(gCfgItems.fileSysType); + lv_draw_ready_print(); - #if ENABLED(SDSUPPORT) - char *cur_name = strrchr(list_file.file_name[sel_id], '/'); - card.openFileWrite(cur_name); - if (card.isFileOpen()) { - ZERO(file_writer.saveFileName); - strcpy((char *)file_writer.saveFileName, (char *)&tmpStr[index]); - ZERO(tempBuf); - sprintf_P((char *)tempBuf, PSTR("Writing to file: %s\r\n"), (char *)file_writer.saveFileName); - wifi_ret_ack(); - send_to_wifi((uint8_t *)tempBuf, strlen((char *)tempBuf)); - wifi_link_state = WIFI_WAIT_TRANS_START; - } - else { - wifi_link_state = WIFI_CONNECTED; - clear_cur_ui(); - lv_draw_dialog(DIALOG_TRANSFER_NO_DEVICE); - } - #endif - } - } - break; + send_ok_to_wifi(); + } + break; - case 105: - case 991: + case 27: + // Report print rate + if (uiCfg.print_state == WORKING || uiCfg.print_state == PAUSED|| uiCfg.print_state == REPRINTING) { + print_rate = uiCfg.totalSend; ZERO(tempBuf); - if (cmd_value == 105) { - - SEND_OK_TO_WIFI; + sprintf_P((char *)tempBuf, PSTR("M27 %d\r\n"), print_rate); + send_to_wifi((uint8_t *)tempBuf, strlen((char *)tempBuf)); + } + break; - char *outBuf = (char *)tempBuf; - char tbuf[34]; + case 28: + // Begin to transfer file to filesys + if (uiCfg.print_state == IDLE) { - sprintf_P(tbuf, PSTR("%d /%d"), thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0)); + int index = 0; + while (mStr[index] == ' ') index++; - const int tlen = strlen(tbuf); - sprintf_P(outBuf, PSTR("T:%s"), tbuf); - outBuf += 2 + tlen; + if (strstr_P(&mStr[index], PSTR(".g")) || strstr_P(&mStr[index], PSTR(".G"))) { + strcpy((char *)file_writer.saveFileName, &mStr[index]); - strcpy_P(outBuf, PSTR(" B:")); - outBuf += 3; - #if HAS_HEATED_BED - sprintf_P(outBuf, PSTR("%d /%d"), thermalManager.wholeDegBed(), thermalManager.degTargetBed()); - #else - strcpy_P(outBuf, PSTR("0 /0")); - #endif - outBuf += 4; - - strcat_P(outBuf, PSTR(" T0:")); - strcat(outBuf, tbuf); - outBuf += 4 + tlen; - - strcat_P(outBuf, PSTR(" T1:")); - outBuf += 4; - #if HAS_MULTI_HOTEND - sprintf_P(outBuf, PSTR("%d /%d"), thermalManager.wholeDegHotend(1), thermalManager.degTargetHotend(1)); - #else - strcpy_P(outBuf, PSTR("0 /0")); + if (gCfgItems.fileSysType == FILE_SYS_SD) { + ZERO(tempBuf); + sprintf_P((char *)tempBuf, PSTR("%s"), file_writer.saveFileName); + } + else if (gCfgItems.fileSysType == FILE_SYS_USB) { + ZERO(tempBuf); + sprintf_P((char *)tempBuf, PSTR("%s"), (char *)file_writer.saveFileName); + } + mount_file_sys(gCfgItems.fileSysType); + + #if HAS_MEDIA + char *cur_name = strrchr(list_file.file_name[sel_id], '/'); + card.openFileWrite(cur_name); + if (card.isFileOpen()) { + ZERO(file_writer.saveFileName); + strcpy((char *)file_writer.saveFileName, &mStr[index]); + ZERO(tempBuf); + sprintf_P((char *)tempBuf, PSTR("Writing to file: %s\r\n"), (char *)file_writer.saveFileName); + wifi_ret_ack(); + send_to_wifi((uint8_t *)tempBuf, strlen((char *)tempBuf)); + wifi_link_state = WIFI_WAIT_TRANS_START; + } + else { + wifi_link_state = WIFI_CONNECTED; + clear_cur_ui(); + lv_draw_dialog(DIALOG_TRANSFER_NO_DEVICE); + } #endif - outBuf += 4; - - strcat_P(outBuf, PSTR(" @:0 B@:0\r\n")); - } - else { - sprintf_P((char *)tempBuf, PSTR("T:%d /%d B:%d /%d T0:%d /%d T1:%d /%d @:0 B@:0\r\n"), - thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0), - TERN0(HAS_HEATED_BED, thermalManager.wholeDegBed()), - TERN0(HAS_HEATED_BED, thermalManager.degTargetBed()), - thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0), - TERN0(HAS_MULTI_HOTEND, thermalManager.wholeDegHotend(1)), - TERN0(HAS_MULTI_HOTEND, thermalManager.degTargetHotend(1)) - ); } + } + break; - send_to_wifi((uint8_t *)tempBuf, strlen((char *)tempBuf)); - queue.enqueue_one(F("M105")); - break; + case 105: + case 991: + ZERO(tempBuf); + if (cmd_value == 105) { + + send_ok_to_wifi(); + + char *outBuf = (char *)tempBuf; + char tbuf[34]; + + sprintf_P(tbuf, PSTR("%d /%d"), thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0)); + + const int tlen = strlen(tbuf); + sprintf_P(outBuf, PSTR("T:%s"), tbuf); + outBuf += 2 + tlen; + + strcpy_P(outBuf, PSTR(" B:")); + outBuf += 3; + #if HAS_HEATED_BED + sprintf_P(outBuf, PSTR("%d /%d"), thermalManager.wholeDegBed(), thermalManager.degTargetBed()); + #else + strcpy_P(outBuf, PSTR("0 /0")); + #endif + outBuf += 4; + + strcat_P(outBuf, PSTR(" T0:")); + strcat(outBuf, tbuf); + outBuf += 4 + tlen; + + strcat_P(outBuf, PSTR(" T1:")); + outBuf += 4; + #if HAS_MULTI_HOTEND + sprintf_P(outBuf, PSTR("%d /%d"), thermalManager.wholeDegHotend(1), thermalManager.degTargetHotend(1)); + #else + strcpy_P(outBuf, PSTR("0 /0")); + #endif + outBuf += 4; + + strcat_P(outBuf, PSTR(" @:0 B@:0\r\n")); + } + else { + sprintf_P((char *)tempBuf, PSTR("T:%d /%d B:%d /%d T0:%d /%d T1:%d /%d @:0 B@:0\r\n"), + thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0), + TERN0(HAS_HEATED_BED, thermalManager.wholeDegBed()), + TERN0(HAS_HEATED_BED, thermalManager.degTargetBed()), + thermalManager.wholeDegHotend(0), thermalManager.degTargetHotend(0), + TERN0(HAS_MULTI_HOTEND, thermalManager.wholeDegHotend(1)), + TERN0(HAS_MULTI_HOTEND, thermalManager.degTargetHotend(1)) + ); + } - case 992: - if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED)) { - ZERO(tempBuf); - sprintf_P((char *)tempBuf, PSTR("M992 %d%d:%d%d:%d%d\r\n"), print_time.hours/10, print_time.hours%10, print_time.minutes/10, print_time.minutes%10, print_time.seconds/10, print_time.seconds%10); - wifi_ret_ack(); - send_to_wifi((uint8_t *)tempBuf, strlen((char *)tempBuf)); - } - break; + send_to_wifi((uint8_t *)tempBuf, strlen((char *)tempBuf)); + queue.enqueue_one(F("M105")); + break; - case 994: - if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED)) { - ZERO(tempBuf); - if (strlen((char *)list_file.file_name[sel_id]) > (100 - 1)) return; - sprintf_P((char *)tempBuf, PSTR("M994 %s;%d\n"), list_file.file_name[sel_id], (int)gCfgItems.curFilesize); - wifi_ret_ack(); - send_to_wifi((uint8_t *)tempBuf, strlen((char *)tempBuf)); - } - break; + case 992: + if (uiCfg.print_state == WORKING || uiCfg.print_state == PAUSED) { + ZERO(tempBuf); + sprintf_P((char *)tempBuf, PSTR("M992 %d%d:%d%d:%d%d\r\n"), print_time.hours/10, print_time.hours%10, print_time.minutes/10, print_time.minutes%10, print_time.seconds/10, print_time.seconds%10); + wifi_ret_ack(); + send_to_wifi((uint8_t *)tempBuf, strlen((char *)tempBuf)); + } + break; - case 997: - if (uiCfg.print_state == IDLE) { + case 994: + if (uiCfg.print_state == WORKING || uiCfg.print_state == PAUSED) { + ZERO(tempBuf); + if (strlen((char *)list_file.file_name[sel_id]) > (100 - 1)) return; + sprintf_P((char *)tempBuf, PSTR("M994 %s;%d\n"), list_file.file_name[sel_id], (int)gCfgItems.curFilesize); + wifi_ret_ack(); + send_to_wifi((uint8_t *)tempBuf, strlen((char *)tempBuf)); + } + break; + + case 997: + #define SENDIDLE "M997 IDLE\r\n" + #define SENDPRINTING "M997 PRINTING\r\n" + #define SENDPAUSE "M997 PAUSE\r\n" + switch (uiCfg.print_state) { + default: break; + case IDLE: wifi_ret_ack(); - send_to_wifi((uint8_t *)"M997 IDLE\r\n", strlen("M997 IDLE\r\n")); - } - else if (uiCfg.print_state == WORKING) { + send_to_wifi((uint8_t *)SENDIDLE, strlen(SENDIDLE)); + break; + case WORKING: wifi_ret_ack(); - send_to_wifi((uint8_t *)"M997 PRINTING\r\n", strlen("M997 PRINTING\r\n")); - } - else if (uiCfg.print_state == PAUSED) { + send_to_wifi((uint8_t *)SENDPRINTING, strlen(SENDPRINTING)); + break; + case PAUSED: wifi_ret_ack(); - send_to_wifi((uint8_t *)"M997 PAUSE\r\n", strlen("M997 PAUSE\r\n")); - } - else if (uiCfg.print_state == REPRINTING) { + send_to_wifi((uint8_t *)SENDPAUSE, strlen(SENDPAUSE)); + break; + case REPRINTING: wifi_ret_ack(); - send_to_wifi((uint8_t *)"M997 PAUSE\r\n", strlen("M997 PAUSE\r\n")); - } - if (!uiCfg.command_send) get_wifi_list_command_send(); - break; + send_to_wifi((uint8_t *)SENDPAUSE, strlen(SENDPAUSE)); + break; + } + if (!uiCfg.command_send) get_wifi_list_command_send(); + break; - case 998: - if (uiCfg.print_state == IDLE) { - const int v = atoi((char *)tmpStr); - if (v == 0 || v == 1) set_cur_file_sys(v); - wifi_ret_ack(); - } - break; + case 998: + if (uiCfg.print_state == IDLE) { + const int v = atoi(mStr); + if (v == 0 || v == 1) set_cur_file_sys(v); + wifi_ret_ack(); + } + break; - case 115: - ZERO(tempBuf); - SEND_OK_TO_WIFI; - send_to_wifi((uint8_t *)"FIRMWARE_NAME:Robin_nano\r\n", strlen("FIRMWARE_NAME:Robin_nano\r\n")); - break; - - default: - strcat_P((char *)cmd_line, PSTR("\n")); - - if (espGcodeFifo.wait_tick > 5) { - const uint32_t left = espGcodeFifo.r > espGcodeFifo.w - ? espGcodeFifo.r - espGcodeFifo.w - 1 - : WIFI_GCODE_BUFFER_SIZE + espGcodeFifo.r - espGcodeFifo.w - 1; - - if (left >= strlen((const char *)cmd_line)) { - for (uint32_t index = 0; index < strlen((const char *)cmd_line); index++) { - espGcodeFifo.Buffer[espGcodeFifo.w] = cmd_line[index] ; - espGcodeFifo.w = (espGcodeFifo.w + 1) % WIFI_GCODE_BUFFER_SIZE; - } - if (left - WIFI_GCODE_BUFFER_LEAST_SIZE >= strlen((const char *)cmd_line)) - SEND_OK_TO_WIFI; - else - need_ok_later = true; + case 115: + ZERO(tempBuf); + send_ok_to_wifi(); + #define SENDFW "FIRMWARE_NAME:Robin_nano\r\n" + send_to_wifi((uint8_t *)SENDFW, strlen(SENDFW)); + break; + + default: + strcat_P((char *)cmd_line, PSTR("\n")); + + if (espGcodeFifo.wait_tick > 5) { + uint32_t left = espGcodeFifo.r - espGcodeFifo.w - 1; + if (espGcodeFifo.r > espGcodeFifo.w) left += WIFI_GCODE_BUFFER_SIZE; + + if (left >= strlen((const char *)cmd_line)) { + for (uint32_t index = 0; index < strlen((const char *)cmd_line); index++) { + espGcodeFifo.Buffer[espGcodeFifo.w] = cmd_line[index]; + espGcodeFifo.w = (espGcodeFifo.w + 1) % (WIFI_GCODE_BUFFER_SIZE); } + if (left - (WIFI_GCODE_BUFFER_LEAST_SIZE) >= strlen((const char *)cmd_line)) + send_ok_to_wifi(); + else + need_ok_later = true; } - break; - } + } + break; } - else { - strcat_P((char *)cmd_line, PSTR("\n")); + } + else { + // Add another linefeed to the command, terminate with null + strcat_P((char *)cmd_line, PSTR("\n")); - if (espGcodeFifo.wait_tick > 5) { - const uint32_t left_g = espGcodeFifo.r > espGcodeFifo.w - ? espGcodeFifo.r - espGcodeFifo.w - 1 - : WIFI_GCODE_BUFFER_SIZE + espGcodeFifo.r - espGcodeFifo.w - 1; + if (espGcodeFifo.wait_tick > 5) { + uint32_t left_g = espGcodeFifo.r - espGcodeFifo.w - 1; + if (espGcodeFifo.r > espGcodeFifo.w) left_g += WIFI_GCODE_BUFFER_SIZE; - if (left_g >= strlen((const char *)cmd_line)) { - for (uint32_t index = 0; index < strlen((const char *)cmd_line); index++) { - espGcodeFifo.Buffer[espGcodeFifo.w] = cmd_line[index] ; - espGcodeFifo.w = (espGcodeFifo.w + 1) % WIFI_GCODE_BUFFER_SIZE; - } - if (left_g - WIFI_GCODE_BUFFER_LEAST_SIZE >= strlen((const char *)cmd_line)) - SEND_OK_TO_WIFI; - else - need_ok_later = true; + if (left_g >= strlen((char * const)cmd_line)) { + for (uint32_t index = 0; index < strlen((char * const)cmd_line); index++) { + espGcodeFifo.Buffer[espGcodeFifo.w] = cmd_line[index]; + espGcodeFifo.w = (espGcodeFifo.w + 1) % (WIFI_GCODE_BUFFER_SIZE); } + if (left_g - (WIFI_GCODE_BUFFER_LEAST_SIZE) >= strlen((char * const)cmd_line)) + send_ok_to_wifi(); + else + need_ok_later = true; } } } @@ -1281,7 +1309,7 @@ void get_wifi_list_command_send() { raw_send_to_wifi(cmd_wifi_list, COUNT(cmd_wifi_list)); } -static void net_msg_handle(uint8_t * msg, uint16_t msgLen) { +static void net_msg_handle(const uint8_t * const msg, const uint16_t msgLen) { int wifiNameLen, wifiKeyLen, hostLen, id_len, ver_len; if (msgLen <= 0) return; @@ -1316,7 +1344,7 @@ static void net_msg_handle(uint8_t * msg, uint16_t msgLen) { } } - cloud_para.state =msg[10 + wifiNameLen + wifiKeyLen]; + cloud_para.state = msg[10 + wifiNameLen + wifiKeyLen]; hostLen = msg[11 + wifiNameLen + wifiKeyLen]; if (cloud_para.state) { if (hostLen < 96) { @@ -1356,7 +1384,7 @@ static void net_msg_handle(uint8_t * msg, uint16_t msgLen) { } } -static void wifi_list_msg_handle(uint8_t * msg, uint16_t msgLen) { +static void wifi_list_msg_handle(const uint8_t * const msg, const uint16_t msgLen) { int wifiNameLen,wifiMsgIdex = 1; int8_t wifi_name_is_same = 0; int8_t i, j; @@ -1415,16 +1443,15 @@ static void wifi_list_msg_handle(uint8_t * msg, uint16_t msgLen) { } } -static void gcode_msg_handle(uint8_t * msg, uint16_t msgLen) { +static void gcode_msg_handle(const uint8_t * const msg, const uint16_t msgLen) { uint8_t gcodeBuf[100] = { 0 }; - char *index_s, *index_e; if (msgLen <= 0) return; - index_s = (char *)msg; - index_e = (char *)strchr((char *)msg, '\n'); + char *index_s = (char *)msg, + *index_e = strchr((char *)msg, '\n'); if (*msg == 'N') { - index_s = (char *)strchr((char *)msg, ' '); + index_s = strchr((char *)msg, ' '); while (*index_s == ' ') index_s++; } while ((index_e != 0) && ((int)index_s < (int)index_e)) { @@ -1435,7 +1462,7 @@ static void gcode_msg_handle(uint8_t * msg, uint16_t msgLen) { } while ((*index_e == '\r') || (*index_e == '\n')) index_e++; index_s = index_e; - index_e = (char *)strchr(index_s, '\n'); + index_e = strchr(index_s, '\n'); } } @@ -1482,8 +1509,8 @@ void utf8_2_unicode(uint8_t *source, uint8_t Len) { COPY(source, FileName_unicode); } -static void file_first_msg_handle(uint8_t * msg, uint16_t msgLen) { - uint8_t fileNameLen = *msg; +static void file_first_msg_handle(const uint8_t * const msg, const uint16_t msgLen) { + const uint8_t fileNameLen = *msg; if (msgLen != fileNameLen + 5) return; @@ -1502,7 +1529,7 @@ static void file_first_msg_handle(uint8_t * msg, uint16_t msgLen) { ZERO(saveFilePath); if (gCfgItems.fileSysType == FILE_SYS_SD) { - TERN_(SDSUPPORT, card.mount()); + TERN_(HAS_MEDIA, card.mount()); } else if (gCfgItems.fileSysType == FILE_SYS_USB) { // nothing @@ -1514,11 +1541,11 @@ static void file_first_msg_handle(uint8_t * msg, uint16_t msgLen) { wifiTransError.start_tick = 0; wifiTransError.now_tick = 0; - TERN_(SDSUPPORT, card.closefile()); + TERN_(HAS_MEDIA, card.closefile()); wifi_delay(1000); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA char dosName[FILENAME_LENGTH]; @@ -1547,7 +1574,7 @@ static void file_first_msg_handle(uint8_t * msg, uint16_t msgLen) { return; } - #endif // SDSUPPORT + #endif // HAS_MEDIA wifi_link_state = WIFI_TRANS_FILE; @@ -1565,8 +1592,8 @@ static void file_first_msg_handle(uint8_t * msg, uint16_t msgLen) { #define FRAG_MASK ~_BV32(31) -static void file_fragment_msg_handle(uint8_t * msg, uint16_t msgLen) { - uint32_t frag = *((uint32_t *)msg); +static void file_fragment_msg_handle(const uint8_t * const msg, const uint16_t msgLen) { + const uint32_t frag = *((uint32_t *)msg); if ((frag & FRAG_MASK) != (uint32_t)(lastFragment + 1)) { ZERO(public_buf); file_writer.write_index = 0; @@ -1747,7 +1774,7 @@ void stopEspTransfer() { if (wifi_link_state == WIFI_TRANS_FILE) wifi_link_state = WIFI_CONNECTED; - TERN_(SDSUPPORT, card.closefile()); + TERN_(HAS_MEDIA, card.closefile()); if (upload_result != 3) { wifiTransError.flag = 1; @@ -1777,7 +1804,8 @@ void stopEspTransfer() { W25QXX.init(SPI_QUARTER_SPEED); - TERN_(HAS_TFT_LVGL_UI_SPI, SPI_TFT.spi_init(SPI_FULL_SPEED)); + // ?? Workaround for SPI / Servo issues ?? + TERN_(HAS_TFT_LVGL_UI_SPI, SPI_TFT.spiInit(SPI_FULL_SPEED)); TERN_(HAS_SERVOS, servo_init()); TERN_(HAS_Z_SERVO_PROBE, probe.servo_probe_init()); @@ -1842,7 +1870,7 @@ void wifi_rcv_handle() { } if (need_ok_later && !queue.ring_buffer.full()) { need_ok_later = false; - send_to_wifi((uint8_t *)"ok\r\n", strlen("ok\r\n")); + send_ok_to_wifi(); } } @@ -1872,7 +1900,7 @@ void wifi_rcv_handle() { if (wifiTransError.flag == 0x1) { wifiTransError.now_tick = getWifiTick(); - if (getWifiTickDiff(wifiTransError.start_tick, wifiTransError.now_tick) > WAIT_ESP_TRANS_TIMEOUT_TICK) { + if (getWifiTickDiff(wifiTransError.start_tick, wifiTransError.now_tick) > (WAIT_ESP_TRANS_TIMEOUT_TICK)) { wifiTransError.flag = 0; WIFI_IO1_RESET(); } @@ -1992,7 +2020,7 @@ void get_wifi_commands() { char wifi_char = espGcodeFifo.Buffer[espGcodeFifo.r]; - espGcodeFifo.r = (espGcodeFifo.r + 1) % WIFI_GCODE_BUFFER_SIZE; + espGcodeFifo.r = (espGcodeFifo.r + 1) % (WIFI_GCODE_BUFFER_SIZE); /** * If the character ends the line diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.h b/Marlin/src/lcd/extui/mks_ui/wifi_module.h index 36998899b483..851e85c512a0 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.h +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.h @@ -163,8 +163,8 @@ typedef struct { //uint8_t uartTxBuffer[UART_FIFO_BUFFER_SIZE]; } SZ_USART_FIFO; -#define WIFI_GCODE_BUFFER_LEAST_SIZE 96 -#define WIFI_GCODE_BUFFER_SIZE (WIFI_GCODE_BUFFER_LEAST_SIZE * 3) +#define WIFI_GCODE_BUFFER_LEAST_SIZE 96 +#define WIFI_GCODE_BUFFER_SIZE (WIFI_GCODE_BUFFER_LEAST_SIZE * 3) typedef struct { uint8_t wait_tick; uint8_t Buffer[WIFI_GCODE_BUFFER_SIZE]; @@ -179,14 +179,14 @@ extern CLOUD_PARA cloud_para; extern WIFI_GCODE_BUFFER espGcodeFifo; -uint32_t getWifiTick(); -uint32_t getWifiTickDiff(int32_t lastTick, int32_t curTick); +millis_t getWifiTick(); +millis_t getWifiTickDiff(const millis_t lastTick, const millis_t curTick); void mks_esp_wifi_init(); extern int cfg_cloud_flag; -int send_to_wifi(uint8_t *buf, int len); +int send_to_wifi(uint8_t * const buf, const int len); void wifi_looping(); -int raw_send_to_wifi(uint8_t *buf, int len); +int raw_send_to_wifi(uint8_t * const buf, const int len); int package_to_wifi(WIFI_RET_TYPE type, uint8_t *buf, int len); void get_wifi_list_command_send(); void get_wifi_commands(); diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp index 18a311303ccf..3e1ecf415713 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) +#if ALL(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "draw_ui.h" #include "wifi_module.h" @@ -38,10 +38,8 @@ extern SZ_USART_FIFO WifiRxFifo; -extern int readUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len); -extern int writeUsartFifo(SZ_USART_FIFO * fifo, int8_t * buf, int32_t len); void esp_port_begin(uint8_t interrupt); -void wifi_delay(int n); +void wifi_delay(const uint16_t n); #define ARRAY_SIZE(a) sizeof(a) / sizeof((a)[0]) @@ -79,13 +77,13 @@ const uint32_t ESP_FLASH_ADDR = 0x40200000; // address of start of Flash UPLOAD_STRUCT esp_upload; -static const unsigned int retriesPerReset = 3; -static const uint32_t connectAttemptInterval = 50; -static const unsigned int percentToReportIncrement = 5; // how often we report % complete -static const uint32_t defaultTimeout = 500; -static const uint32_t eraseTimeout = 15000; -static const uint32_t blockWriteTimeout = 200; -static const uint32_t blockWriteInterval = 15; // 15ms is long enough, 10ms is mostly too short +static const uint16_t retriesPerReset = 3; +static const millis_t connectAttemptInterval = 50; +static const uint16_t percentToReportIncrement = 5; // how often we report % complete +static const millis_t defaultTimeout = 500; +static const millis_t eraseTimeout = 15000; +static const millis_t blockWriteTimeout = 200; +static const millis_t blockWriteInterval = 15; // 15ms is long enough, 10ms is mostly too short static MediaFile update_file, *update_curDir; // Messages corresponding to result codes, should make sense when followed by " error" @@ -103,15 +101,17 @@ const char *resultMessages[] = { "slip data" }; -// A note on baud rates. -// The ESP8266 supports 921600, 460800, 230400, 115200, 74880 and some lower baud rates. -// 921600b is not reliable because even though it sometimes succeeds in connecting, we get a bad response during uploading after a few blocks. -// Probably our UART ISR cannot receive bytes fast enough, perhaps because of the latency of the system tick ISR. -// 460800b doesn't always manage to connect, but if it does then uploading appears to be reliable. -// 230400b always manages to connect. +/** + * Baud Rate Notes: + * The ESP8266 supports 921600, 460800, 230400, 115200, 74880 and some lower baud rates. + * 921600b is not reliable because even though it sometimes succeeds in connecting, we get a bad response during uploading after a few blocks. + * Probably our UART ISR cannot receive bytes fast enough, perhaps because of the latency of the system tick ISR. + * 460800b doesn't always manage to connect, but if it does then uploading appears to be reliable. + * 230400b always manages to connect. + */ static const uint32_t uploadBaudRates[] = { 460800, 230400, 115200, 74880 }; -signed char IsReady() { +signed char isReady() { return esp_upload.state == upload_idle; } @@ -151,7 +151,7 @@ void flushInput() { uint32_t getData(unsigned byteCnt, const uint8_t *buf, int ofst) { uint32_t val = 0; if (buf && byteCnt) { - unsigned int shiftCnt = 0; + uint16_t shiftCnt = 0; NOMORE(byteCnt, 4U); do { val |= (uint32_t)buf[ofst++] << shiftCnt; @@ -172,15 +172,17 @@ void putData(uint32_t val, unsigned byteCnt, uint8_t *buf, int ofst) { } } -// Read a byte optionally performing SLIP decoding. The return values are: -// -// 2 - an escaped byte was read successfully -// 1 - a non-escaped byte was read successfully -// 0 - no data was available -// -1 - the value 0xC0 was encountered (shouldn't happen) -// -2 - a SLIP escape byte was found but the following byte wasn't available -// -3 - a SLIP escape byte was followed by an invalid byte -int ReadByte(uint8_t *data, signed char slipDecode) { +/** + * Read a byte optionally performing SLIP decoding. The return values are: + * + * 2 - an escaped byte was read successfully + * 1 - a non-escaped byte was read successfully + * 0 - no data was available + * -1 - the value 0xC0 was encountered (shouldn't happen) + * -2 - a SLIP escape byte was found but the following byte wasn't available + * -3 - a SLIP escape byte was followed by an invalid byte + */ +int readByte(uint8_t *data, signed char slipDecode) { if (uploadPort_available() == 0) return 0; // At least one byte is available @@ -208,32 +210,34 @@ void _writePacketRaw(const uint8_t *buf, size_t len) { } // Write a byte to the serial port optionally SLIP encoding. Return the number of bytes actually written. -void WriteByteRaw(uint8_t b) { +void writeByteRaw(uint8_t b) { uploadPort_write((const uint8_t *)&b, 1); } // Write a byte to the serial port optionally SLIP encoding. Return the number of bytes actually written. -void WriteByteSlip(const uint8_t b) { +void writeByteSlip(const uint8_t b) { if (b == 0xC0) { - WriteByteRaw(0xDB); - WriteByteRaw(0xDC); + writeByteRaw(0xDB); + writeByteRaw(0xDC); } else if (b == 0xDB) { - WriteByteRaw(0xDB); - WriteByteRaw(0xDD); + writeByteRaw(0xDB); + writeByteRaw(0xDD); } else uploadPort_write((const uint8_t *)&b, 1); } -// Wait for a data packet to be returned. If the body of the packet is -// non-zero length, return an allocated buffer indirectly containing the -// data and return the data length. Note that if the pointer for returning -// the data buffer is nullptr, the response is expected to be two bytes of zero. -// -// If an error occurs, return a negative value. Otherwise, return the number -// of bytes in the response (or zero if the response was not the standard "two bytes of zero"). -EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t msTimeout) { +/** + * Wait for a data packet to be returned. If the body of the packet is + * non-zero length, return an allocated buffer indirectly containing the + * data and return the data length. Note that if the pointer for returning + * the data buffer is nullptr, the response is expected to be two bytes of zero. + * + * If an error occurs, return a negative value. Otherwise, return the number + * of bytes in the response (or zero if the response was not the standard "two bytes of zero"). + */ +EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, millis_t msTimeout) { typedef enum { begin = 0, header, @@ -246,7 +250,7 @@ EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t const size_t headerLength = 8; - uint32_t startTime = getWifiTick(); + const millis_t startTime = getWifiTick(); uint8_t hdr[headerLength]; uint16_t hdrIdx = 0; @@ -294,7 +298,7 @@ EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t case body: { // reading the response body int rslt; // retrieve a byte with SLIP decoding - rslt = ReadByte(&c, 1); + rslt = readByte(&c, 1); if (rslt != 1 && rslt != 2) { // some error occurred stat = (rslt == 0 || rslt == -2) ? slipData : slipFrame; @@ -348,7 +352,7 @@ EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t // Send a block of data performing SLIP encoding of the content. void _writePacket(const uint8_t *data, size_t len) { unsigned char outBuf[2048] = {0}; - unsigned int outIndex = 0; + uint16_t outIndex = 0; while (len != 0) { if (*data == 0xC0) { outBuf[outIndex++] = 0xDB; @@ -372,19 +376,19 @@ void _writePacket(const uint8_t *data, size_t len) { // 0xC0 and 0xDB replaced by the two-byte sequences {0xDB, 0xDC} and {0xDB, 0xDD} respectively. void writePacket(const uint8_t *hdr, size_t hdrLen, const uint8_t *data, size_t dataLen) { - WriteByteRaw(0xC0); // send the packet start character + writeByteRaw(0xC0); // send the packet start character _writePacket(hdr, hdrLen); // send the header _writePacket(data, dataLen); // send the data block - WriteByteRaw(0xC0); // send the packet end character + writeByteRaw(0xC0); // send the packet end character } // Send a packet to the serial port while performing SLIP framing. The packet data comprises a header and an optional data block. // This is like writePacket except that it does a fast block write for both the header and the main data with no SLIP encoding. Used to send sync commands. void writePacketRaw(const uint8_t *hdr, size_t hdrLen, const uint8_t *data, size_t dataLen) { - WriteByteRaw(0xC0); // send the packet start character + writeByteRaw(0xC0); // send the packet start character _writePacketRaw(hdr, hdrLen); // send the header _writePacketRaw(data, dataLen); // send the data block in raw mode - WriteByteRaw(0xC0); // send the packet end character + writeByteRaw(0xC0); // send the packet end character } // Send a command to the attached device together with the supplied data, if any. @@ -405,7 +409,7 @@ void sendCommand(uint8_t op, uint32_t checkVal, const uint8_t *data, size_t data } // Send a command to the attached device together with the supplied data, if any, and get the response -EspUploadResult doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint32_t checkVal, uint32_t *valp, uint32_t msTimeout) { +EspUploadResult doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint32_t checkVal, uint32_t *valp, millis_t msTimeout) { size_t bodyLen; EspUploadResult stat; @@ -420,7 +424,7 @@ EspUploadResult doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint3 // Send a synchronising packet to the serial port in an attempt to induce // the ESP8266 to auto-baud lock on the baud rate. -EspUploadResult Sync(uint16_t timeout) { +EspUploadResult sync(uint16_t timeout) { uint8_t buf[36]; EspUploadResult stat; int i; @@ -459,7 +463,7 @@ EspUploadResult flashBegin(uint32_t addr, uint32_t size) { // determine the number of blocks represented by the size uint32_t blkCnt; uint8_t buf[16]; - uint32_t timeout; + millis_t timeout; blkCnt = (size + EspFlashBlockSize - 1) / EspFlashBlockSize; @@ -555,7 +559,7 @@ void upload_spin() { case connecting: if ((getWifiTickDiff(esp_upload.lastAttemptTime, getWifiTick()) >= connectAttemptInterval) && (getWifiTickDiff(esp_upload.lastResetTime, getWifiTick()) >= 500)) { - EspUploadResult res = Sync(5000); + EspUploadResult res = sync(5000); esp_upload.lastAttemptTime = getWifiTick(); if (res == success) esp_upload.state = erasing; @@ -597,7 +601,7 @@ void upload_spin() { case uploading: // The ESP needs several milliseconds to recover from one packet before it will accept another if (getWifiTickDiff(esp_upload.lastAttemptTime, getWifiTick()) >= 15) { - unsigned int percentComplete; + uint16_t percentComplete; const uint32_t blkCnt = (esp_upload.fileSize + EspFlashBlockSize - 1) / EspFlashBlockSize; if (esp_upload.uploadBlockNumber < blkCnt) { esp_upload.uploadResult = flashWriteBlock(0, 0); @@ -624,7 +628,7 @@ void upload_spin() { } // Try to upload the given file at the given address -void SendUpdateFile(const char *file, uint32_t address) { +void sendUpdateFile(const char *file, uint32_t address) { const char * const fname = card.diveToFile(false, update_curDir, ESP_FIRMWARE_FILE); if (!update_file.open(update_curDir, fname, O_READ)) return; @@ -642,7 +646,7 @@ void SendUpdateFile(const char *file, uint32_t address) { static const uint32_t FirmwareAddress = 0x00000000, WebFilesAddress = 0x00100000; -void ResetWiFiForUpload(int begin_or_end) { +void resetWiFiForUpload(int begin_or_end) { //#if 0 uint32_t start = getWifiTick(); @@ -662,12 +666,12 @@ void ResetWiFiForUpload(int begin_or_end) { int32_t wifi_upload(int type) { esp_upload.retriesPerBaudRate = 9; - ResetWiFiForUpload(0); + resetWiFiForUpload(0); switch (type) { - case 0: SendUpdateFile(ESP_FIRMWARE_FILE, FirmwareAddress); break; - case 1: SendUpdateFile(ESP_WEB_FIRMWARE_FILE, FirmwareAddress); break; - case 2: SendUpdateFile(ESP_WEB_FILE, WebFilesAddress); break; + case 0: sendUpdateFile(ESP_FIRMWARE_FILE, FirmwareAddress); break; + case 1: sendUpdateFile(ESP_WEB_FIRMWARE_FILE, FirmwareAddress); break; + case 2: sendUpdateFile(ESP_WEB_FILE, WebFilesAddress); break; default: return -1; } @@ -676,7 +680,7 @@ int32_t wifi_upload(int type) { hal.watchdog_refresh(); } - ResetWiFiForUpload(1); + resetWiFiForUpload(1); return esp_upload.uploadResult == success ? 0 : -1; } diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.h b/Marlin/src/lcd/extui/mks_ui/wifi_upload.h index 2daa505d9088..524fb28f85fe 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_upload.h +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.h @@ -59,8 +59,8 @@ typedef struct { UploadState state; uint32_t retriesPerBaudRate; uint32_t connectAttemptNumber; - uint32_t lastAttemptTime; - uint32_t lastResetTime; + millis_t lastAttemptTime; + millis_t lastResetTime; uint32_t uploadBlockNumber; uint32_t uploadNextPercentToReport; EspUploadResult uploadResult; diff --git a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp index 0e84fd33cf4f..75bcf6ad9db6 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp @@ -41,7 +41,7 @@ namespace ExtUI { void onMediaInserted() {} void onMediaError() {} void onMediaRemoved() {} - void onPlayTone(const uint16_t frequency, const uint16_t duration) {} + void onPlayTone(const uint16_t frequency, const uint16_t duration/*=0*/) {} void onPrintTimerStarted() {} void onPrintTimerPaused() {} void onPrintTimerStopped() {} @@ -79,20 +79,22 @@ namespace ExtUI { // Called after loading or resetting stored settings } - void onSettingsStored(bool success) { + void onSettingsStored(const bool success) { // Called after the entire EEPROM has been written, // whether successful or not. } - void onSettingsLoaded(bool success) { + void onSettingsLoaded(const bool success) { // Called after the entire EEPROM has been read, // whether successful or not. } - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { // Called when any mesh points are updated } @@ -103,6 +105,12 @@ namespace ExtUI { #endif #if ENABLED(POWER_LOSS_RECOVERY) + void onSetPowerLoss(const bool onoff) { + // Called when power-loss is enabled/disabled + } + void onPowerLoss() { + // Called when power-loss state is detected + } void onPowerLossResume() { // Called on resume from power-loss } diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp index 63c25177a679..14a7f9996c0b 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -139,10 +139,10 @@ bool NextionTFT::ReadTFTCommand() { #if NEXDEBUG(N_SOME) uint8_t req = atoi(&nextion_command[1]); if (req > 7 && req != 20) - DEBUG_ECHOLNPGM( "> ", AS_CHAR(nextion_command[0]), - "\n> ", AS_CHAR(nextion_command[1]), - "\n> ", AS_CHAR(nextion_command[2]), - "\n> ", AS_CHAR(nextion_command[3]), + DEBUG_ECHOLNPGM( "> ", C(nextion_command[0]), + "\n> ", C(nextion_command[1]), + "\n> ", C(nextion_command[2]), + "\n> ", C(nextion_command[3]), "\nprinter_state:", printer_state); #endif } @@ -294,7 +294,7 @@ void NextionTFT::PanelInfo(uint8_t req) { break; case 26: // TMC Hybrid Threshold Speed - #if 0 && BOTH(HAS_TRINAMIC_CONFIG, HYBRID_THRESHOLD) + #if 0 && ALL(HAS_TRINAMIC_CONFIG, HYBRID_THRESHOLD) #define SEND_TRINAMIC_THRS(A, B) SEND_VALasTXT(A, getAxisPWMthrs(B)) #else #define SEND_TRINAMIC_THRS(A, B) SEND_NA(A) @@ -445,9 +445,9 @@ void NextionTFT::PanelInfo(uint8_t req) { #elif Z_HOME_TO_MAX SEND_VALasTXT("z2", READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING ? "triggered" : "open"); #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN SEND_VALasTXT("z2", READ(Z2_MIN_PIN) != Z2_MIN_ENDSTOP_INVERTING ? "triggered" : "open"); - #elif HAS_Z2_MAX + #elif USE_Z2_MAX SEND_VALasTXT("z2", READ(Z2_MAX_PIN) != Z2_MAX_ENDSTOP_INVERTING ? "triggered" : "open"); #endif #if HAS_BED_PROBE @@ -463,7 +463,7 @@ void NextionTFT::PanelInfo(uint8_t req) { #else #define SEND_PID_INFO_0(A, B) SEND_NA(A) #endif - #if BOTH(PIDTEMP, HAS_MULTI_EXTRUDER) + #if ALL(PIDTEMP, HAS_MULTI_EXTRUDER) #define SEND_PID_INFO_1(A, B) SEND_VALasTXT(A, getPID_K##B(E1)) #else #define SEND_PID_INFO_1(A, B) SEND_NA(A) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 576fc56b7863..c0ea3461a311 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -112,9 +112,9 @@ namespace ExtUI { static struct { - uint8_t printer_killed : 1; + bool printer_killed : 1; #if ENABLED(JOYSTICK) - uint8_t jogging : 1; + bool jogging : 1; #endif } flags; @@ -172,35 +172,6 @@ namespace ExtUI { if (!flags.printer_killed) thermalManager.task(); } - void enableHeater(const extruder_t extruder) { - #if HAS_HOTEND && HEATER_IDLE_HANDLER - thermalManager.reset_hotend_idle_timer(extruder - E0); - #else - UNUSED(extruder); - #endif - } - - void enableHeater(const heater_t heater) { - #if HEATER_IDLE_HANDLER - switch (heater) { - #if HAS_HEATED_BED - case BED: thermalManager.reset_bed_idle_timer(); return; - #endif - #if HAS_HEATED_CHAMBER - case CHAMBER: return; // Chamber has no idle timer - #endif - #if HAS_COOLER - case COOLER: return; // Cooler has no idle timer - #endif - default: - TERN_(HAS_HOTEND, thermalManager.reset_hotend_idle_timer(heater - H0)); - break; - } - #else - UNUSED(heater); - #endif - } - #if ENABLED(JOYSTICK) /** * Jogs in the direction given by the vector (dx, dy, dz). @@ -237,6 +208,39 @@ namespace ExtUI { } #endif + // + // Heaters locked / idle + // + + void enableHeater(const extruder_t extruder) { + #if HAS_HOTEND && HEATER_IDLE_HANDLER + thermalManager.reset_hotend_idle_timer(extruder - E0); + #else + UNUSED(extruder); + #endif + } + + void enableHeater(const heater_t heater) { + #if HEATER_IDLE_HANDLER + switch (heater) { + #if HAS_HEATED_BED + case BED: thermalManager.reset_bed_idle_timer(); return; + #endif + #if HAS_HEATED_CHAMBER + case CHAMBER: return; // Chamber has no idle timer + #endif + #if HAS_COOLER + case COOLER: return; // Cooler has no idle timer + #endif + default: + TERN_(HAS_HOTEND, thermalManager.reset_hotend_idle_timer(heater - H0)); + break; + } + #else + UNUSED(heater); + #endif + } + bool isHeaterIdle(const extruder_t extruder) { #if HAS_HOTEND && HEATER_IDLE_HANDLER return thermalManager.heater_idle[extruder - E0].timed_out; @@ -302,6 +306,9 @@ namespace ExtUI { return GET_TEMP_ADJUSTMENT(thermalManager.degTargetHotend(extruder - E0)); } + // + // Fan target/actual speed + // float getTargetFan_percent(const fan_t fan) { UNUSED(fan); return TERN0(HAS_FAN, thermalManager.fanSpeedPercent(fan - FAN0)); @@ -312,6 +319,9 @@ namespace ExtUI { return TERN0(HAS_FAN, thermalManager.scaledFanSpeedPercent(fan - FAN0)); } + // + // High level axis and extruder positions + // float getAxisPosition_mm(const axis_t axis) { return current_position[axis]; } @@ -349,6 +359,9 @@ namespace ExtUI { line_to_current_position(feedrate ?: manual_feedrate_mm_s.e); } + // + // Tool changing + // void setActiveTool(const extruder_t extruder, bool no_move) { #if HAS_MULTI_EXTRUDER const uint8_t e = extruder - E0; @@ -370,12 +383,18 @@ namespace ExtUI { extruder_t getActiveTool() { return getTool(active_extruder); } + // + // Moving axes and extruders + // bool isMoving() { return planner.has_blocks_queued(); } + // + // Motion might be blocked by NO_MOTION_BEFORE_HOMING + // bool canMove(const axis_t axis) { switch (axis) { - #if IS_KINEMATIC || ENABLED(NO_MOTION_BEFORE_HOMING) - case X: return !axis_should_home(X_AXIS); + #if ANY(IS_KINEMATIC, NO_MOTION_BEFORE_HOMING) + OPTCODE(HAS_X_AXIS, case X: return !axis_should_home(X_AXIS)) OPTCODE(HAS_Y_AXIS, case Y: return !axis_should_home(Y_AXIS)) OPTCODE(HAS_Z_AXIS, case Z: return !axis_should_home(Z_AXIS)) #else @@ -385,20 +404,34 @@ namespace ExtUI { } } + // + // E Motion might be prevented by cold material + // bool canMove(const extruder_t extruder) { return !thermalManager.tooColdToExtrude(extruder - E0); } + // + // Host Keepalive, used by awaitingUserConfirm + // #if ENABLED(HOST_KEEPALIVE_FEATURE) GcodeSuite::MarlinBusyState getHostKeepaliveState() { return gcode.busy_state; } bool getHostKeepaliveIsPaused() { return gcode.host_keepalive_is_paused(); } #endif + // + // Soft Endstops Enabled/Disabled State + // + #if HAS_SOFTWARE_ENDSTOPS bool getSoftEndstopState() { return soft_endstop._enabled; } void setSoftEndstopState(const bool value) { soft_endstop._enabled = value; } #endif + // + // Trinamic Current / Bump Sensitivity + // + #if HAS_TRINAMIC_CONFIG float getAxisCurrent_mA(const axis_t axis) { switch (axis) { @@ -626,6 +659,10 @@ namespace ExtUI { } #endif + // + // Planner Accessors / Setters + // + float getAxisSteps_per_mm(const axis_t axis) { return planner.settings.axis_steps_per_mm[axis]; } @@ -773,7 +810,9 @@ namespace ExtUI { bool babystepAxis_steps(const int16_t steps, const axis_t axis) { switch (axis) { #if ENABLED(BABYSTEP_XY) - case X: babystep.add_steps(X_AXIS, steps); break; + #if HAS_X_AXIS + case X: babystep.add_steps(X_AXIS, steps); break; + #endif #if HAS_Y_AXIS case Y: babystep.add_steps(Y_AXIS, steps); break; #endif @@ -818,7 +857,7 @@ namespace ExtUI { if (e != active_extruder) hotend_offset[e][axis] += mm; - normalizeNozzleOffset(X); + TERN_(HAS_X_AXIS, normalizeNozzleOffset(X)); TERN_(HAS_Y_AXIS, normalizeNozzleOffset(Y)); TERN_(HAS_Z_AXIS, normalizeNozzleOffset(Z)); } @@ -917,7 +956,7 @@ namespace ExtUI { bool getLevelingActive() { return planner.leveling_active; } void setLevelingActive(const bool state) { set_bed_leveling_enabled(state); } - bool getMeshValid() { return leveling_is_valid(); } + bool getLevelingIsValid() { return leveling_is_valid(); } #if HAS_MESH @@ -926,28 +965,27 @@ namespace ExtUI { void setMeshPoint(const xy_uint8_t &pos, const_float_t zoff) { if (WITHIN(pos.x, 0, (GRID_MAX_POINTS_X) - 1) && WITHIN(pos.y, 0, (GRID_MAX_POINTS_Y) - 1)) { bedlevel.z_values[pos.x][pos.y] = zoff; - TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate()); + TERN_(ABL_BILINEAR_SUBDIVISION, bedlevel.refresh_bed_level()); } } void moveToMeshPoint(const xy_uint8_t &pos, const_float_t z) { - #if EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) - const feedRate_t old_feedrate = feedrate_mm_s; + #if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) + REMEMBER(fr, feedrate_mm_s); const float x_target = MESH_MIN_X + pos.x * (MESH_X_DIST), y_target = MESH_MIN_Y + pos.y * (MESH_Y_DIST); if (x_target != current_position.x || y_target != current_position.y) { // If moving across bed, raise nozzle to safe height over bed - feedrate_mm_s = Z_PROBE_FEEDRATE_FAST; + feedrate_mm_s = MMM_TO_MMS(Z_PROBE_FEEDRATE_FAST); destination.set(current_position.x, current_position.y, Z_CLEARANCE_BETWEEN_PROBES); prepare_line_to_destination(); - feedrate_mm_s = XY_PROBE_FEEDRATE; + feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S; destination.set(x_target, y_target); prepare_line_to_destination(); } - feedrate_mm_s = Z_PROBE_FEEDRATE_FAST; + feedrate_mm_s = MMM_TO_MMS(Z_PROBE_FEEDRATE_FAST); destination.z = z; prepare_line_to_destination(); - feedrate_mm_s = old_feedrate; #else UNUSED(pos); UNUSED(z); @@ -1083,14 +1121,14 @@ namespace ExtUI { #endif void printFile(const char *filename) { - TERN(SDSUPPORT, card.openAndPrintFile(filename), UNUSED(filename)); + TERN(HAS_MEDIA, card.openAndPrintFile(filename), UNUSED(filename)); } bool isPrintingFromMediaPaused() { - return TERN0(SDSUPPORT, IS_SD_PAUSED()); + return TERN0(HAS_MEDIA, IS_SD_PAUSED()); } - bool isPrintingFromMedia() { return TERN0(SDSUPPORT, IS_SD_PRINTING() || IS_SD_PAUSED()); } + bool isPrintingFromMedia() { return TERN0(HAS_MEDIA, IS_SD_PRINTING() || IS_SD_PAUSED()); } bool isPrinting() { return commandsInQueue() || isPrintingFromMedia() || printJobOngoing() || printingIsPaused(); @@ -1100,8 +1138,9 @@ namespace ExtUI { return isPrinting() && (isPrintingFromMediaPaused() || print_job_timer.isPaused()); } - bool isMediaInserted() { return TERN0(SDSUPPORT, IS_SD_INSERTED()); } + bool isMediaInserted() { return TERN0(HAS_MEDIA, IS_SD_INSERTED()); } + // Pause/Resume/Stop are implemented in MarlinUI void pausePrint() { ui.pause_print(); } void resumePrint() { ui.resume_print(); } void stopPrint() { ui.abort_print(); } @@ -1129,12 +1168,12 @@ namespace ExtUI { FileList::FileList() { refresh(); } - void FileList::refresh() { num_files = 0xFFFF; } + void FileList::refresh() { } bool FileList::seek(const uint16_t pos, const bool skip_range_check) { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (!skip_range_check && (pos + 1) > count()) return false; - card.getfilename_sorted(SD_ORDER(pos, count())); + card.selectFileByIndexSorted(pos); return card.filename[0] != '\0'; #else UNUSED(pos); @@ -1144,43 +1183,35 @@ namespace ExtUI { } const char* FileList::filename() { - return TERN(SDSUPPORT, card.longest_filename(), ""); + return TERN(HAS_MEDIA, card.longest_filename(), ""); } const char* FileList::shortFilename() { - return TERN(SDSUPPORT, card.filename, ""); + return TERN(HAS_MEDIA, card.filename, ""); } const char* FileList::longFilename() { - return TERN(SDSUPPORT, card.longFilename, ""); + return TERN(HAS_MEDIA, card.longFilename, ""); } bool FileList::isDir() { - return TERN0(SDSUPPORT, card.flag.filenameIsDir); + return TERN0(HAS_MEDIA, card.flag.filenameIsDir); } uint16_t FileList::count() { - return TERN0(SDSUPPORT, (num_files = (num_files == 0xFFFF ? card.get_num_Files() : num_files))); + return TERN0(HAS_MEDIA, card.get_num_items()); } bool FileList::isAtRootDir() { - return TERN1(SDSUPPORT, card.flag.workDirIsRoot); + return TERN1(HAS_MEDIA, card.flag.workDirIsRoot); } void FileList::upDir() { - #if ENABLED(SDSUPPORT) - card.cdup(); - num_files = 0xFFFF; - #endif + TERN_(HAS_MEDIA, card.cdup()); } void FileList::changeDir(const char * const dirname) { - #if ENABLED(SDSUPPORT) - card.cd(dirname); - num_files = 0xFFFF; - #else - UNUSED(dirname); - #endif + TERN(HAS_MEDIA, card.cd(dirname), UNUSED(dirname)); } } // namespace ExtUI diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index c2ce52ba4c1e..a250180393c1 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -43,8 +43,10 @@ ****************************************************************************/ #include "../../inc/MarlinConfig.h" + #include "../marlinui.h" #include "../../gcode/gcode.h" + #if M600_PURGE_MORE_RESUMABLE #include "../../feature/pause.h" #endif @@ -71,6 +73,28 @@ namespace ExtUI { typedef float bed_mesh_t[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; #endif + /** + * The Extensible UI API is a utility class that can be used to implement: + * - An LCD view that responds to standard events, e.g., onMediaInserted(...) + * - An LCD that polls firmware states and settings in a standard manner. + * (e.g., With tool indexes and extruder indexes). + * - Standard hooks to send data to a serial-based controller. + * + * ExtUI is best used when: + * - The display handles LCD touch / buttons so the firmware doesn't see these events. + * - Commands and value edits are sent over serial to Marlin as G-codes. + * - The display can get data from Marlin, but is not necessarily drawn by Marlin. + * - The display cannot implement a MarlinUI menu. + * - The display is implemented with code callbacks alongside ExtUI callbacks. + * + * Building an ExtUI layer: + * - Start by making an lcd/extui subfolder. Copy 'example' or another display. + * - Many of these methods are optional. Implement them according to your UI needs. + * - If your display needs information from Marlin, add an accessor to ExtUI. + * - If some addition seems like it should be standard part of ExtUI, submit a PR with the new + * methods added to this API. Implement in the ExtUI example and/or with some existing displays. + */ + bool isMoving(); bool isAxisPositionKnown(const axis_t); bool isAxisPositionKnown(const extruder_t); @@ -88,11 +112,6 @@ namespace ExtUI { bool getHostKeepaliveIsPaused(); #endif - bool isHeaterIdle(const heater_t); - bool isHeaterIdle(const extruder_t); - void enableHeater(const heater_t); - void enableHeater(const extruder_t); - #if ENABLED(JOYSTICK) void jog(const xyz_float_t &dir); void _joystick_update(xyz_float_t &norm_jog); @@ -100,7 +119,7 @@ namespace ExtUI { /** * Getters and setters - * Should be used by the EXTENSIBLE_UI to query or change Marlin's state. + * Use to query or change Marlin's state. */ PGM_P getFirmwareName_str(); @@ -109,6 +128,7 @@ namespace ExtUI { void setSoftEndstopState(const bool); #endif + // Trinamic Current / Bump Sensitivity #if HAS_TRINAMIC_CONFIG float getAxisCurrent_mA(const axis_t); float getAxisCurrent_mA(const extruder_t); @@ -119,37 +139,50 @@ namespace ExtUI { void setTMCBumpSensitivity(const_float_t, const axis_t); #endif + // Actual and target accessors, by Heater ID, Extruder ID, Fan ID + void enableHeater(const heater_t); + void enableHeater(const extruder_t); + bool isHeaterIdle(const heater_t); + bool isHeaterIdle(const extruder_t); celsius_float_t getActualTemp_celsius(const heater_t); celsius_float_t getActualTemp_celsius(const extruder_t); celsius_float_t getTargetTemp_celsius(const heater_t); celsius_float_t getTargetTemp_celsius(const extruder_t); - float getTargetFan_percent(const fan_t); float getActualFan_percent(const fan_t); + float getTargetFan_percent(const fan_t); + + // High level positions, by Axis ID, Extruder ID float getAxisPosition_mm(const axis_t); float getAxisPosition_mm(const extruder_t); + // Axis steps-per-mm, by Axis ID, Extruder ID float getAxisSteps_per_mm(const axis_t); float getAxisSteps_per_mm(const extruder_t); + // Speed and acceleration limits, per Axis ID or Extruder ID feedRate_t getAxisMaxFeedrate_mm_s(const axis_t); feedRate_t getAxisMaxFeedrate_mm_s(const extruder_t); float getAxisMaxAcceleration_mm_s2(const axis_t); float getAxisMaxAcceleration_mm_s2(const extruder_t); + // Standard speeds, as set in the planner feedRate_t getMinFeedrate_mm_s(); feedRate_t getMinTravelFeedrate_mm_s(); feedRate_t getFeedrate_mm_s(); + // Standard accelerations, as set in the planner float getPrintingAcceleration_mm_s2(); float getRetractAcceleration_mm_s2(); float getTravelAcceleration_mm_s2(); + // A speed multiplier for overall printing float getFeedrate_percent(); + // The flow percentage of an extruder int16_t getFlow_percent(const extruder_t); + // Progress / Elapsed Time inline uint8_t getProgress_percent() { return ui.get_progress_percent(); } - #if HAS_PRINT_PROGRESS_PERMYRIAD inline uint16_t getProgress_permyriad() { return ui.get_progress_permyriad(); } #endif - uint32_t getProgress_seconds_elapsed(); + // Material Preheat Presets #if HAS_PREHEAT uint16_t getMaterial_preset_E(const uint16_t); #if HAS_HEATED_BED @@ -157,6 +190,7 @@ namespace ExtUI { #endif #endif + // IDEX Machine Mode #if ENABLED(DUAL_X_CARRIAGE) uint8_t getIDEX_Mode(); #endif @@ -169,16 +203,18 @@ namespace ExtUI { #endif #if HAS_LEVELING + // Global leveling state, events bool getLevelingActive(); void setLevelingActive(const bool); - bool getMeshValid(); + bool getLevelingIsValid(); + void onLevelingStart(); + void onLevelingDone(); #if HAS_MESH + // Mesh data, utilities, events bed_mesh_t& getMeshArray(); float getMeshPoint(const xy_uint8_t &pos); void setMeshPoint(const xy_uint8_t &pos, const_float_t zval); void moveToMeshPoint(const xy_uint8_t &pos, const_float_t z); - void onLevelingStart(); - void onLevelingDone(); void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval); inline void onMeshUpdate(const xy_int8_t &pos, const_float_t zval) { onMeshUpdate(pos.x, pos.y, zval); } @@ -197,10 +233,12 @@ namespace ExtUI { #endif #endif + // Send an 'M876 S' host response #if ENABLED(HOST_PROMPT_SUPPORT) void setHostResponse(const uint8_t); #endif + // Provide a simulated click to MarlinUI inline void simulateUserClick() { #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) ui.lcd_clicked = true; @@ -208,6 +246,7 @@ namespace ExtUI { } #if ENABLED(PRINTCOUNTER) + // Printcounter strings (See nextion_tft.cpp) char* getFailedPrints_str(char buffer[21]); char* getTotalPrints_str(char buffer[21]); char* getFinishedPrints_str(char buffer[21]); @@ -216,12 +255,17 @@ namespace ExtUI { char* getFilamentUsed_str(char buffer[21]); #endif + // Temperature Control void setTargetTemp_celsius(const_float_t, const heater_t); void setTargetTemp_celsius(const_float_t, const extruder_t); void setTargetFan_percent(const_float_t, const fan_t); void coolDown(); + + // Motion Control void setAxisPosition_mm(const_float_t, const axis_t, const feedRate_t=0); void setAxisPosition_mm(const_float_t, const extruder_t, const feedRate_t=0); + + // Planner Control void setAxisSteps_per_mm(const_float_t, const axis_t); void setAxisSteps_per_mm(const_float_t, const extruder_t); void setAxisMaxFeedrate_mm_s(const feedRate_t, const axis_t); @@ -236,20 +280,25 @@ namespace ExtUI { void setTravelAcceleration_mm_s2(const_float_t); void setFeedrate_percent(const_float_t); void setFlow_percent(const int16_t, const extruder_t); + + // Waiting for User Interaction bool awaitingUserConfirm(); void setUserConfirmed(); #if M600_PURGE_MORE_RESUMABLE + // "Purge More" has a control screen void setPauseMenuResponse(PauseMenuResponse); extern PauseMessage pauseModeStatus; PauseMode getPauseMode(); #endif #if ENABLED(LIN_ADVANCE) + // Linear Advance Control float getLinearAdvance_mm_mm_s(const extruder_t); void setLinearAdvance_mm_mm_s(const_float_t, const extruder_t); #endif + // JD or Jerk Control #if HAS_JUNCTION_DEVIATION float getJunctionDeviation_mm(); void setJunctionDeviation_mm(const_float_t); @@ -260,10 +309,12 @@ namespace ExtUI { void setAxisMaxJerk_mm_s(const_float_t, const extruder_t); #endif + // Tool Changing extruder_t getTool(const uint8_t extruder); extruder_t getActiveTool(); void setActiveTool(const extruder_t, bool no_move); + // Babystepping (axis, probe offset) #if ENABLED(BABYSTEPPING) int16_t mmToWholeSteps(const_float_t mm, const axis_t axis); float mmFromWholeSteps(int16_t steps, const axis_t axis); @@ -272,20 +323,24 @@ namespace ExtUI { void smartAdjustAxis_steps(const int16_t steps, const axis_t axis, bool linked_nozzles); #endif + // Hotend Offsets #if HAS_HOTEND_OFFSET float getNozzleOffset_mm(const axis_t, const extruder_t); void setNozzleOffset_mm(const_float_t, const axis_t, const extruder_t); void normalizeNozzleOffset(const axis_t axis); #endif + // The Probe Z Offset float getZOffset_mm(); void setZOffset_mm(const_float_t); + // The Probe XYZ Offset #if HAS_BED_PROBE float getProbeOffset_mm(const axis_t); void setProbeOffset_mm(const_float_t, const axis_t); #endif + // Backlash Control #if ENABLED(BACKLASH_GCODE) float getAxisBacklash_mm(const axis_t); void setAxisBacklash_mm(const_float_t, const axis_t); @@ -299,6 +354,7 @@ namespace ExtUI { #endif #endif + // Filament Runout Sensor #if HAS_FILAMENT_SENSOR bool getFilamentRunoutEnabled(); void setFilamentRunoutEnabled(const bool); @@ -311,6 +367,7 @@ namespace ExtUI { #endif #endif + // Case Light Control #if ENABLED(CASE_LIGHT_ENABLE) bool getCaseLightState(); void setCaseLightState(const bool); @@ -321,11 +378,13 @@ namespace ExtUI { #endif #endif + // Power-Loss Recovery #if ENABLED(POWER_LOSS_RECOVERY) bool getPowerLossRecoveryEnabled(); void setPowerLossRecoveryEnabled(const bool); #endif + // Hotend PID #if ENABLED(PIDTEMP) float getPID_Kp(const extruder_t); float getPID_Ki(const extruder_t); @@ -334,6 +393,7 @@ namespace ExtUI { void startPIDTune(const celsius_t, extruder_t); #endif + // Bed PID #if ENABLED(PIDTEMPBED) float getBedPID_Kp(); float getBedPID_Ki(); @@ -360,8 +420,7 @@ namespace ExtUI { /** * Media access routines - * - * Should be used by the EXTENSIBLE_UI to operate on files + * Use these to operate on files */ bool isMediaInserted(); bool isPrintingFromMediaPaused(); @@ -375,9 +434,6 @@ namespace ExtUI { void resumePrint(); class FileList { - private: - uint16_t num_files; - public: FileList(); void refresh(); @@ -396,15 +452,14 @@ namespace ExtUI { /** * Event callback routines - * - * Should be declared by EXTENSIBLE_UI and will be called by Marlin + * Must be defined, and will be called by Marlin as needed */ void onStartup(); void onIdle(); void onMediaInserted(); void onMediaError(); void onMediaRemoved(); - void onPlayTone(const uint16_t frequency, const uint16_t duration); + void onPlayTone(const uint16_t frequency, const uint16_t duration=0); void onPrinterKilled(FSTR_P const error, FSTR_P const component); void onPrintTimerStarted(); void onPrintTimerPaused(); @@ -423,9 +478,11 @@ namespace ExtUI { void onStoreSettings(char *); void onLoadSettings(const char *); void onPostprocessSettings(); - void onSettingsStored(bool success); - void onSettingsLoaded(bool success); + void onSettingsStored(const bool success); + void onSettingsLoaded(const bool success); #if ENABLED(POWER_LOSS_RECOVERY) + void onSetPowerLoss(const bool onoff); + void onPowerLoss(); void onPowerLossResume(); #endif #if HAS_PID_HEATING diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index 1d4801278ce2..e9d89c685f1d 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -41,7 +41,7 @@ namespace Language_an { LSTR MSG_MEDIA_INSERTED = _UxGT("Tarcheta mesa"); LSTR MSG_MEDIA_REMOVED = _UxGT("Tarcheta sacada"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters - LSTR MSG_MAIN = _UxGT("Menu prencipal"); + LSTR MSG_MAIN_MENU = _UxGT("Menu prencipal"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Inicio automatico"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Amortar motors"); LSTR MSG_HOMING = _UxGT("Orichen"); diff --git a/Marlin/src/lcd/language/language_bg.h b/Marlin/src/lcd/language/language_bg.h index 312ada7b10cd..74e31ab77d3f 100644 --- a/Marlin/src/lcd/language/language_bg.h +++ b/Marlin/src/lcd/language/language_bg.h @@ -39,7 +39,7 @@ namespace Language_bg { LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" Готов."); LSTR MSG_MEDIA_INSERTED = _UxGT("Картата е поставена"); LSTR MSG_MEDIA_REMOVED = _UxGT("Картата е извадена"); - LSTR MSG_MAIN = _UxGT("Меню"); + LSTR MSG_MAIN_MENU = _UxGT("Меню"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Автостарт"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Изкл. двигатели"); LSTR MSG_AUTO_HOME = _UxGT("Паркиране"); diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index 13b5d70837ad..c9fb734a2aee 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -37,7 +37,7 @@ namespace Language_ca { LSTR MSG_MEDIA_INSERTED = _UxGT("Targeta detectada."); LSTR MSG_MEDIA_REMOVED = _UxGT("Targeta extreta."); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); - LSTR MSG_MAIN = _UxGT("Menú principal"); + LSTR MSG_MAIN_MENU = _UxGT("Menú principal"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Inici automatic"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Desactiva motors"); LSTR MSG_DEBUG_MENU = _UxGT("Menu de depuracio"); diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index bb930eb7846c..51b302608d5d 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -54,7 +54,7 @@ namespace Language_cz { LSTR MSG_MEDIA_USB_FAILED = _UxGT("Chyba USB"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstopy"); // max 8 znaku LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstopy"); - LSTR MSG_MAIN = _UxGT("Hlavní nabídka"); + LSTR MSG_MAIN_MENU = _UxGT("Hlavní nabídka"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Další nastavení"); LSTR MSG_CONFIGURATION = _UxGT("Konfigurace"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostart"); @@ -334,7 +334,7 @@ namespace Language_cz { LSTR MSG_STOP_PRINT = _UxGT("Zastavit tisk"); LSTR MSG_PRINTING_OBJECT = _UxGT("Tisk objektu"); LSTR MSG_CANCEL_OBJECT = _UxGT("Zrušit objekt"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Zrušit objekt ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Zrušit objekt {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Obnova výpadku"); LSTR MSG_MEDIA_MENU = _UxGT("Tisknout z SD"); LSTR MSG_NO_MEDIA = _UxGT("Žádná SD karta"); @@ -512,7 +512,7 @@ namespace Language_cz { LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Vytáhněte, klikněte"); LSTR MSG_MIX = _UxGT("Mix"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponenta ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponenta {"); LSTR MSG_MIXER = _UxGT("Mixér"); LSTR MSG_GRADIENT = _UxGT("Přechod"); LSTR MSG_FULL_GRADIENT = _UxGT("Celý přechod"); diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index 56c53b84fd51..a668e8f3139e 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -39,7 +39,7 @@ namespace Language_da { LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" er klar"); LSTR MSG_MEDIA_INSERTED = _UxGT("Kort isat"); LSTR MSG_MEDIA_REMOVED = _UxGT("Kort fjernet"); - LSTR MSG_MAIN = _UxGT("Menu"); + LSTR MSG_MAIN_MENU = _UxGT("Menu"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Slå alle steppere fra"); LSTR MSG_AUTO_HOME = _UxGT("Auto Home"); // G28 LSTR MSG_LEVEL_BED_WAITING = _UxGT("Klik når du er klar"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 09b979b5f78b..4a1828e5704e 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -52,7 +52,7 @@ namespace Language_de { LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall überschritten"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstopp"); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Software-Endstopp"); - LSTR MSG_MAIN = _UxGT("Hauptmenü"); + LSTR MSG_MAIN_MENU = _UxGT("Hauptmenü"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Erw. Einstellungen"); LSTR MSG_TOOLBAR_SETUP = _UxGT("Toolbar Einstellung"); LSTR MSG_OPTION_DISABLED = _UxGT("Option Deaktiviert"); @@ -277,7 +277,7 @@ namespace Language_de { LSTR MSG_SET_LEDS_VIOLET = _UxGT("Violett"); LSTR MSG_SET_LEDS_WHITE = _UxGT("Weiß"); LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Standard"); - LSTR MSG_LED_CHANNEL_N = _UxGT("Kanal ="); + LSTR MSG_LED_CHANNEL_N = _UxGT("Kanal {"); LSTR MSG_LEDS2 = _UxGT("Lichter #2"); LSTR MSG_NEO2_PRESETS = _UxGT("Licht #2 Voreinst."); LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Helligkeit"); @@ -461,7 +461,7 @@ namespace Language_de { LSTR MSG_END_LOOPS = _UxGT("Wiederholung beenden"); LSTR MSG_PRINTING_OBJECT = _UxGT("Objekt drucken"); LSTR MSG_CANCEL_OBJECT = _UxGT("Objekt abbrechen"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Objekt abbrechen ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Objekt abbrechen {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Wiederh. n. Stroma."); LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Druckauftrag fortset."); LSTR MSG_MEDIA_MENU = _UxGT("Druck vom Medium"); @@ -692,7 +692,7 @@ namespace Language_de { LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Entfernen, klicken"); LSTR MSG_MIX = _UxGT("Mix"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponente ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponente {"); LSTR MSG_MIXER = _UxGT("Mixer"); LSTR MSG_GRADIENT = _UxGT("Gradient"); // equal Farbverlauf LSTR MSG_FULL_GRADIENT = _UxGT("Volle Gradient"); diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index 57af804147c5..978855588d83 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -51,7 +51,7 @@ namespace Language_el { LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB αφαιρέθη"); LSTR MSG_MEDIA_USB_FAILED = _UxGT("Αποτυχία εκκίνησης USB"); LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Αποτυχία αρχικοποίησης SD"); - LSTR MSG_MAIN = _UxGT("Αρχική Οθόνη"); + LSTR MSG_MAIN_MENU = _UxGT("Αρχική Οθόνη"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Αυτόματη εκκίνηση"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Απενεργοποίηση μοτέρ"); LSTR MSG_AUTO_HOME = _UxGT("Αυτόμ. επαναφορά XYZ"); diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index 08f647f705bb..207cf707bb91 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -40,7 +40,7 @@ namespace Language_el_gr { LSTR MSG_MEDIA_INSERTED = _UxGT("Εισαγωγή κάρτας"); LSTR MSG_MEDIA_REMOVED = _UxGT("Αφαίρεση κάρτας"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters - LSTR MSG_MAIN = _UxGT("Βασική Οθόνη"); + LSTR MSG_MAIN_MENU = _UxGT("Βασική Οθόνη"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Αυτόματη εκκίνηση"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Απενεργοποίηση βηματιστή"); LSTR MSG_AUTO_HOME = _UxGT("Αυτομ. επαναφορά στο αρχικό σημείο"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index e0240b6a10a6..24d760f66040 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -30,7 +30,7 @@ * Substitutions are applied for the following characters when used in menu items titles: * * $ displays an inserted string - * = displays '0'....'10' for indexes 0 - 10 + * { displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) * @ displays an axis name such as XYZUVW, or E for an extruder @@ -67,7 +67,7 @@ namespace Language_en { LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); - LSTR MSG_MAIN = _UxGT("Main"); + LSTR MSG_MAIN_MENU = _UxGT("Main"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Advanced Settings"); LSTR MSG_TOOLBAR_SETUP = _UxGT("Toolbar Setup"); LSTR MSG_OPTION_DISABLED = _UxGT("Option Disabled"); @@ -107,6 +107,7 @@ namespace Language_en { LSTR MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); LSTR MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets Applied"); + LSTR MSG_ERR_M428_TOO_FAR = _UxGT("MIN/MAX Too Far"); LSTR MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); LSTR MSG_SELECT_ORIGIN = _UxGT("Select Origin"); LSTR MSG_LAST_VALUE_SP = _UxGT("Last value "); @@ -270,8 +271,8 @@ namespace Language_en { LSTR MSG_MESH_SAVED = _UxGT("Mesh %i Saved"); LSTR MSG_MESH_ACTIVE = _UxGT("Mesh %i active"); LSTR MSG_UBL_NO_STORAGE = _UxGT("No Storage"); - LSTR MSG_UBL_SAVE_ERROR = _UxGT("Err: UBL Save"); - LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Err: UBL Restore"); + LSTR MSG_UBL_SAVE_ERROR = _UxGT("UBL Save Error"); + LSTR MSG_UBL_RESTORE_ERROR = _UxGT("UBL Restore Error"); LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: "); LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Offset Stopped"); LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Step-By-Step UBL"); @@ -295,7 +296,7 @@ namespace Language_en { LSTR MSG_SET_LEDS_VIOLET = _UxGT("Violet"); LSTR MSG_SET_LEDS_WHITE = _UxGT("White"); LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Default"); - LSTR MSG_LED_CHANNEL_N = _UxGT("Channel ="); + LSTR MSG_LED_CHANNEL_N = _UxGT("Channel {"); LSTR MSG_LEDS2 = _UxGT("Lights #2"); LSTR MSG_NEO2_PRESETS = _UxGT("Light #2 Presets"); LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Brightness"); @@ -360,7 +361,7 @@ namespace Language_en { LSTR MSG_LCD_ON = _UxGT("On"); LSTR MSG_LCD_OFF = _UxGT("Off"); LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); - LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("Autotune * PID"); LSTR MSG_PID_CYCLE = _UxGT("PID Cycles"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); LSTR MSG_PID_AUTOTUNE_FAILED = _UxGT("PID Autotune failed!"); @@ -435,6 +436,7 @@ namespace Language_en { LSTR MSG_DRAW_MIN_Y = _UxGT("Draw Min Y"); LSTR MSG_DRAW_MAX_Y = _UxGT("Draw Max Y"); LSTR MSG_MAX_BELT_LEN = _UxGT("Max Belt Len"); + LSTR MSG_LINEAR_ADVANCE = _UxGT("Linear Advance"); LSTR MSG_ADVANCE_K = _UxGT("Advance K"); LSTR MSG_ADVANCE_K_E = _UxGT("Advance K *"); LSTR MSG_CONTRAST = _UxGT("LCD Contrast"); @@ -495,7 +497,7 @@ namespace Language_en { LSTR MSG_HOST_START_PRINT = _UxGT("Start Host Print"); LSTR MSG_PRINTING_OBJECT = _UxGT("Printing Object"); LSTR MSG_CANCEL_OBJECT = _UxGT("Cancel Object"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancel Object ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancel Object {"); LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Continue Print Job"); LSTR MSG_MEDIA_MENU = _UxGT("Print from ") MEDIA_TYPE_EN; LSTR MSG_TURN_OFF = _UxGT("Turn off the printer"); @@ -504,7 +506,7 @@ namespace Language_en { LSTR MSG_HOST_START_PRINT = _UxGT("Host Start"); LSTR MSG_PRINTING_OBJECT = _UxGT("Print Obj"); LSTR MSG_CANCEL_OBJECT = _UxGT("Cancel Obj"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancel Obj ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancel Obj {"); LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Continue Job"); LSTR MSG_MEDIA_MENU = MEDIA_TYPE_EN _UxGT(" Print"); LSTR MSG_TURN_OFF = _UxGT("Turn off now"); @@ -745,7 +747,7 @@ namespace Language_en { LSTR MSG_MMU2_REMOVE_AND_CLICK = _UxGT("Remove and click..."); LSTR MSG_MIX = _UxGT("Mix"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("Component ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Component {"); LSTR MSG_MIXER = _UxGT("Mixer"); LSTR MSG_GRADIENT = _UxGT("Gradient"); LSTR MSG_FULL_GRADIENT = _UxGT("Full Gradient"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index eb39a8a08940..00a792f89778 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -49,7 +49,7 @@ namespace Language_es { LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbordamiento de subllamada"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); - LSTR MSG_MAIN = _UxGT("Menú principal"); + LSTR MSG_MAIN_MENU = _UxGT("Menú principal"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Ajustes avanzados"); LSTR MSG_CONFIGURATION = _UxGT("Configuración"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Inicio automático"); @@ -338,7 +338,7 @@ namespace Language_es { LSTR MSG_STOP_PRINT = _UxGT("Detener impresión"); LSTR MSG_PRINTING_OBJECT = _UxGT("Imprimiendo Objeto"); LSTR MSG_CANCEL_OBJECT = _UxGT("Cancelar Objeto"); - LSTR MSG_CANCEL_OBJECT_N = _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/FD"); LSTR MSG_NO_MEDIA = _UxGT("SD/FD no presente"); @@ -510,7 +510,7 @@ namespace Language_es { LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Retirar, y pulsar"); LSTR MSG_MIX = _UxGT("Mezcla"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("Componente ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Componente {"); LSTR MSG_MIXER = _UxGT("Miezclador"); LSTR MSG_GRADIENT = _UxGT("Degradado"); LSTR MSG_FULL_GRADIENT = _UxGT("Degradado Total"); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index 0c29cdd2aaba..78274dce4349 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -41,7 +41,7 @@ namespace Language_eu { LSTR MSG_BACK = _UxGT("Atzera"); LSTR MSG_MEDIA_INSERTED = _UxGT("Txartela sartuta"); LSTR MSG_MEDIA_REMOVED = _UxGT("Txartela kenduta"); - LSTR MSG_MAIN = _UxGT("Menu nagusia"); + LSTR MSG_MAIN_MENU = _UxGT("Menu nagusia"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Auto hasiera"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Itzali motoreak"); LSTR MSG_DEBUG_MENU = _UxGT("Arazketa Menua"); diff --git a/Marlin/src/lcd/language/language_fi.h b/Marlin/src/lcd/language/language_fi.h index 300da9b95652..57fc0a7c21b5 100644 --- a/Marlin/src/lcd/language/language_fi.h +++ b/Marlin/src/lcd/language/language_fi.h @@ -39,7 +39,7 @@ namespace Language_fi { LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" valmis."); LSTR MSG_MEDIA_INSERTED = _UxGT("Kortti asetettu"); LSTR MSG_MEDIA_REMOVED = _UxGT("Kortti poistettu"); - LSTR MSG_MAIN = _UxGT("Palaa"); + LSTR MSG_MAIN_MENU = _UxGT("Palaa"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Automaatti"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Vapauta moottorit"); LSTR MSG_AUTO_HOME = _UxGT("Aja referenssiin"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 8c2df5845239..f10023680215 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -49,7 +49,7 @@ namespace Language_fr { LSTR MSG_MEDIA_USB_FAILED = _UxGT("Erreur média USB"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Butées"); LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Butées SW"); - LSTR MSG_MAIN = _UxGT("Menu principal"); + LSTR MSG_MAIN_MENU = _UxGT("Menu principal"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Config. avancée"); LSTR MSG_CONFIGURATION = _UxGT("Configuration"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Exéc. auto.gcode"); @@ -353,7 +353,7 @@ namespace Language_fr { LSTR MSG_STOP_PRINT = _UxGT("Arrêter impr."); LSTR MSG_PRINTING_OBJECT = _UxGT("Impression objet"); LSTR MSG_CANCEL_OBJECT = _UxGT("Annuler objet"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Annuler objet ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Annuler objet {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Récup. coup."); LSTR MSG_MEDIA_MENU = _UxGT("Impression SD"); LSTR MSG_NO_MEDIA = _UxGT("Pas de média"); @@ -540,7 +540,7 @@ namespace Language_fr { LSTR MSG_MMU2_RESETTING = _UxGT("Réinit. MMU..."); LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Retrait, click"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("Composante ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Composante {"); LSTR MSG_MIXER = _UxGT("Mixeur"); LSTR MSG_GRADIENT = _UxGT("Dégradé"); LSTR MSG_FULL_GRADIENT = _UxGT("Dégradé complet"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 54ae62bac94d..16b5bf2e4f81 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -50,7 +50,7 @@ namespace Language_gl { LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbord. Subch."); LSTR MSG_LCD_ENDSTOPS = _UxGT("FinCarro"); LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("FinCarro SW"); - LSTR MSG_MAIN = _UxGT("Menú principal"); + LSTR MSG_MAIN_MENU = _UxGT("Menú principal"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Axustes avanzados"); LSTR MSG_CONFIGURATION = _UxGT("Configuración"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Autoarranque"); @@ -342,7 +342,7 @@ namespace Language_gl { LSTR MSG_STOP_PRINT = _UxGT("Deter impresión"); LSTR MSG_PRINTING_OBJECT = _UxGT("Imprimindo Obxecto"); LSTR MSG_CANCEL_OBJECT = _UxGT("Cancelar Obxecto"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Obxecto ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Obxecto {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Recuperar Impresión"); LSTR MSG_MEDIA_MENU = _UxGT("Tarxeta SD"); LSTR MSG_NO_MEDIA = _UxGT("Sen tarxeta SD"); @@ -525,7 +525,7 @@ namespace Language_gl { LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Expulsar, premer"); LSTR MSG_MIX = _UxGT("Mestura"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("Compoñente ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Compoñente {"); LSTR MSG_MIXER = _UxGT("Mesturadora"); LSTR MSG_GRADIENT = _UxGT("Degradado"); LSTR MSG_FULL_GRADIENT = _UxGT("Degradado Total"); diff --git a/Marlin/src/lcd/language/language_hr.h b/Marlin/src/lcd/language/language_hr.h index 36eaf78acb1a..c523898a8f8c 100644 --- a/Marlin/src/lcd/language/language_hr.h +++ b/Marlin/src/lcd/language/language_hr.h @@ -40,7 +40,7 @@ namespace Language_hr { LSTR MSG_MEDIA_INSERTED = _UxGT("SD kartica umetnuta"); LSTR MSG_MEDIA_REMOVED = _UxGT("SD kartica uklonjena"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters - LSTR MSG_MAIN = _UxGT("Main"); + LSTR MSG_MAIN_MENU = _UxGT("Main"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Auto pokretanje"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Ugasi steppere"); LSTR MSG_AUTO_HOME = _UxGT("Automatski homing"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 148a0fb64e26..2400a5434235 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -54,7 +54,7 @@ namespace Language_hu { LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Túlfolyás"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Végállás"); // Maximum 8 karakter LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Szoft. végállás"); - LSTR MSG_MAIN = _UxGT(""); + LSTR MSG_MAIN_MENU = _UxGT(""); LSTR MSG_ADVANCED_SETTINGS = _UxGT("További beállítások"); LSTR MSG_CONFIGURATION = _UxGT("Konfiguráció"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Fájl auto. futtatás"); @@ -240,7 +240,7 @@ namespace Language_hu { LSTR MSG_SET_LEDS_VIOLET = _UxGT("Viola"); LSTR MSG_SET_LEDS_WHITE = _UxGT("Fehér"); LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Alapérték"); - LSTR MSG_LED_CHANNEL_N = _UxGT("Csatorna ="); + LSTR MSG_LED_CHANNEL_N = _UxGT("Csatorna {"); LSTR MSG_LEDS2 = _UxGT("LED-ek #2"); LSTR MSG_NEO2_PRESETS = _UxGT("Fény #2 megadott"); LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Fényerö"); @@ -284,10 +284,10 @@ namespace Language_hu { LSTR MSG_FLOWMETER_SAFETY = _UxGT("Áramlásbiztonság"); LSTR MSG_LASER = _UxGT("Lézer"); LSTR MSG_FAN_SPEED = _UxGT("Hütés sebesség"); - LSTR MSG_FAN_SPEED_N = _UxGT("Hütés sebesség ="); - LSTR MSG_STORED_FAN_N = _UxGT("Tárolt hütés ="); + LSTR MSG_FAN_SPEED_N = _UxGT("Hütés sebesség {"); + LSTR MSG_STORED_FAN_N = _UxGT("Tárolt hütés {"); LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Extra hütés sebesség"); - LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra hütés sebesség ="); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra hütés sebesség {"); LSTR MSG_CONTROLLER_FAN = _UxGT("Hütésvezérlés"); LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Alapjárat"); LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Automatikus mód"); @@ -396,7 +396,7 @@ namespace Language_hu { LSTR MSG_END_LOOPS = _UxGT("Hurok ismétlés vége"); LSTR MSG_PRINTING_OBJECT = _UxGT("Objektum nyomtatása"); LSTR MSG_CANCEL_OBJECT = _UxGT("Objektum törlése"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Objektum törlése ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Objektum törlése {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Kiesés helyreáll."); LSTR MSG_MEDIA_MENU = _UxGT("Nyomtatás tárolóról"); LSTR MSG_NO_MEDIA = _UxGT("Nincs tároló"); @@ -587,7 +587,7 @@ namespace Language_hu { LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Kidob, kattint"); LSTR MSG_MIX = _UxGT("Kever"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("Összetevö ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Összetevö {"); LSTR MSG_MIXER = _UxGT("Keverö"); LSTR MSG_GRADIENT = _UxGT("Színátm."); LSTR MSG_FULL_GRADIENT = _UxGT("Teljes színátm."); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 41786f4d7bdf..f22564e66491 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -30,7 +30,7 @@ * Substitutions are applied for the following characters when used in menu items titles: * * $ displays an inserted string - * = displays '0'....'10' for indexes 0 - 10 + * { displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) * @ displays an axis name such as XYZUVW, or E for an extruder @@ -62,7 +62,7 @@ namespace Language_it { LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Overflow subchiamate"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Finecor."); // Max 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Finecorsa Soft"); - LSTR MSG_MAIN = _UxGT("Menu principale"); + LSTR MSG_MAIN_MENU = _UxGT("Menu principale"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Impostaz. avanzate"); LSTR MSG_TOOLBAR_SETUP = _UxGT("Cnf barra strumenti"); LSTR MSG_OPTION_DISABLED = _UxGT("Opzione disab."); @@ -293,7 +293,7 @@ namespace Language_it { LSTR MSG_SET_LEDS_VIOLET = _UxGT("Viola"); LSTR MSG_SET_LEDS_WHITE = _UxGT("Bianco"); LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Predefinito"); - LSTR MSG_LED_CHANNEL_N = _UxGT("Canale ="); + LSTR MSG_LED_CHANNEL_N = _UxGT("Canale {"); LSTR MSG_LEDS2 = _UxGT("Luci #2"); LSTR MSG_NEO2_PRESETS = _UxGT("Presets luce #2"); LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Luminosità"); @@ -440,6 +440,7 @@ namespace Language_it { LSTR MSG_DRAW_MIN_Y = _UxGT("Min Y area disegno"); LSTR MSG_DRAW_MAX_Y = _UxGT("Max Y area disegno"); LSTR MSG_MAX_BELT_LEN = _UxGT("Lungh.max cinghia"); + LSTR MSG_LINEAR_ADVANCE = _UxGT("Avanzam.Lineare"); LSTR MSG_ADVANCE_K = _UxGT("K Avanzamento"); LSTR MSG_ADVANCE_K_E = _UxGT("K Avanzamento *"); LSTR MSG_CONTRAST = _UxGT("Contrasto LCD"); @@ -498,7 +499,7 @@ namespace Language_it { LSTR MSG_END_LOOPS = _UxGT("Fine cicli di rip."); LSTR MSG_PRINTING_OBJECT = _UxGT("Stampa Oggetto"); LSTR MSG_CANCEL_OBJECT = _UxGT("Cancella Oggetto"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Canc. Oggetto ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Canc. Oggetto {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Ripresa da PowerLoss"); LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Cont.proc.stampa"); LSTR MSG_MEDIA_MENU = _UxGT("Stampa da media"); @@ -734,7 +735,7 @@ namespace Language_it { LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Rimuovi, click"); LSTR MSG_MIX = _UxGT("Miscela"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("Componente ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Componente {"); LSTR MSG_MIXER = _UxGT("Miscelatore"); LSTR MSG_GRADIENT = _UxGT("Gradiente"); LSTR MSG_FULL_GRADIENT = _UxGT("Gradiente pieno"); diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index 335d4533daa6..c271ec929361 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -46,7 +46,7 @@ namespace Language_jp_kana { LSTR MSG_MEDIA_REMOVED = _UxGT("メディアガアリマセン"); // "Card removed" LSTR MSG_RELEASE_MEDIA = _UxGT("メディアノトリダシ"); LSTR MSG_LCD_ENDSTOPS = _UxGT("エンドストップ"); // "Endstops" // Max length 8 characters - LSTR MSG_MAIN = _UxGT("メイン"); // "Main" + LSTR MSG_MAIN_MENU = _UxGT("メイン"); // "Main" LSTR MSG_RUN_AUTO_FILES = _UxGT("ジドウカイシ"); // "Autostart" LSTR MSG_DISABLE_STEPPERS = _UxGT("モーターデンゲン オフ"); // "Disable steppers" LSTR MSG_DEBUG_MENU = _UxGT("デバッグメニュー"); // "Debug Menu" diff --git a/Marlin/src/lcd/language/language_ko_KR.h b/Marlin/src/lcd/language/language_ko_KR.h index 50c73f69e9ae..e52ced2dad6f 100644 --- a/Marlin/src/lcd/language/language_ko_KR.h +++ b/Marlin/src/lcd/language/language_ko_KR.h @@ -39,7 +39,7 @@ namespace Language_ko_KR { LSTR MSG_MEDIA_REMOVED = _UxGT("카드 제거됨"); LSTR MSG_LCD_ENDSTOPS = _UxGT("엔드스탑"); LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("소프트 엔드스탑"); - LSTR MSG_MAIN = _UxGT("뒤로"); + LSTR MSG_MAIN_MENU = _UxGT("뒤로"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("고급 설정"); LSTR MSG_CONFIGURATION = _UxGT("설정"); LSTR MSG_RUN_AUTO_FILES = _UxGT("자동 시작"); diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index 9ad16bcd8c14..a55a95fc5a02 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -42,7 +42,7 @@ namespace Language_nl { LSTR MSG_MEDIA_INSERTED = _UxGT("Kaart ingestoken"); LSTR MSG_MEDIA_REMOVED = _UxGT("Kaart verwijderd"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters - LSTR MSG_MAIN = _UxGT("Hoofdmenu"); + LSTR MSG_MAIN_MENU = _UxGT("Hoofdmenu"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostart"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Motoren uit"); LSTR MSG_DEBUG_MENU = _UxGT("Debug Menu"); // accepted English terms diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 9273eb105c8a..864471ea24ca 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -30,7 +30,7 @@ * Substitutions are applied for the following characters when used in menu items titles: * * $ displays an inserted string - * = displays '0'....'10' for indexes 0 - 10 + * { displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) * @ displays an axis name such as XYZUVW, or E for an extruder @@ -58,7 +58,7 @@ namespace Language_pl { LSTR MSG_MEDIA_USB_FAILED = _UxGT("Błąd uruchomienia USB"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Krańców."); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Progr. Krańcówki"); - LSTR MSG_MAIN = _UxGT("Menu główne"); + LSTR MSG_MAIN_MENU = _UxGT("Menu główne"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Ustawienie zaawansowane"); LSTR MSG_CONFIGURATION = _UxGT("Konfiguracja"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostart"); @@ -221,7 +221,7 @@ namespace Language_pl { LSTR MSG_SET_LEDS_VIOLET = _UxGT("Fioletowy"); LSTR MSG_SET_LEDS_WHITE = _UxGT("Biały"); LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Domyślny"); - LSTR MSG_LED_CHANNEL_N = _UxGT("Kanał ="); + LSTR MSG_LED_CHANNEL_N = _UxGT("Kanał {"); LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Jasność"); LSTR MSG_CUSTOM_LEDS = _UxGT("Własne światła"); LSTR MSG_INTENSITY_R = _UxGT("Czerwony"); @@ -330,7 +330,7 @@ namespace Language_pl { LSTR MSG_STOP_PRINT = _UxGT("Stop"); LSTR MSG_PRINTING_OBJECT = _UxGT("Drukowanie obiektu"); LSTR MSG_CANCEL_OBJECT = _UxGT("Anunuj obiekt"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Anunuj obiekt ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Anunuj obiekt {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Odzyskiwanie po awarii"); LSTR MSG_MEDIA_MENU = _UxGT("Karta SD"); LSTR MSG_NO_MEDIA = _UxGT("Brak karty"); @@ -474,7 +474,7 @@ namespace Language_pl { LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Usuń, kliknij"); LSTR MSG_MIX = _UxGT("Miks"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponent ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponent {"); LSTR MSG_MIXER = _UxGT("Mikser"); LSTR MSG_FULL_GRADIENT = _UxGT("Pełny gradient"); LSTR MSG_TOGGLE_MIX = _UxGT("Przełacz miks"); @@ -482,7 +482,6 @@ namespace Language_pl { LSTR MSG_GAMES = _UxGT("Gry"); - LSTR MSG_EDIT_PASSWORD = _UxGT("Zmień hasło"); LSTR MSG_LOGIN_REQUIRED = _UxGT("Wymagane zalogowanie"); LSTR MSG_PASSWORD_SETTINGS = _UxGT("Ustawienia hasła"); diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index 0672f2556084..06fe069ee553 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -40,7 +40,7 @@ namespace Language_pt { LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" pronta."); LSTR MSG_MEDIA_INSERTED = _UxGT("Cartão inserido"); LSTR MSG_MEDIA_REMOVED = _UxGT("Cartão removido"); - LSTR MSG_MAIN = _UxGT("Menu principal"); + LSTR MSG_MAIN_MENU = _UxGT("Menu principal"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Desactivar motores"); LSTR MSG_AUTO_HOME = _UxGT("Ir para origem"); LSTR MSG_AUTO_HOME_X = _UxGT("Ir para origem X"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index d52728d10726..b3e9a8f5bb06 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -48,7 +48,7 @@ namespace Language_pt_br { LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB falhou"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Fins de curso"); LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Fins curso"); - LSTR MSG_MAIN = _UxGT("Menu principal"); + LSTR MSG_MAIN_MENU = _UxGT("Menu principal"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Config. Avançada"); LSTR MSG_CONFIGURATION = _UxGT("Configuração"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Início automático"); @@ -293,7 +293,7 @@ namespace Language_pt_br { LSTR MSG_STOP_PRINT = _UxGT("Parar impressão"); LSTR MSG_PRINTING_OBJECT = _UxGT("Imprimindo objeto"); LSTR MSG_CANCEL_OBJECT = _UxGT("Cancelar Objeto"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Objeto ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Objeto {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Recuperar Impressão"); LSTR MSG_MEDIA_MENU = _UxGT("Imprimir do SD"); LSTR MSG_NO_MEDIA = _UxGT("Sem cartão SD"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index 4eefc11cb9c4..3d537f006a14 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -49,7 +49,7 @@ namespace Language_ro { LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Eroare:Subcall Overflow"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); - LSTR MSG_MAIN = _UxGT("Principal"); + LSTR MSG_MAIN_MENU = _UxGT("Principal"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Setari Avansate"); LSTR MSG_CONFIGURATION = _UxGT("Configurare"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostart"); @@ -348,7 +348,7 @@ namespace Language_ro { LSTR MSG_STOP_PRINT = _UxGT("Stop Print"); LSTR MSG_PRINTING_OBJECT = _UxGT("Printing Object"); LSTR MSG_CANCEL_OBJECT = _UxGT("Cancel Object"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancel Object ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancel Object {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Outage Recovery"); LSTR MSG_MEDIA_MENU = _UxGT("Print from Media"); LSTR MSG_NO_MEDIA = _UxGT("No Media"); @@ -532,7 +532,7 @@ namespace Language_ro { LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Remove, click"); LSTR MSG_MIX = _UxGT("Mix"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("Component ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Component {"); LSTR MSG_MIXER = _UxGT("Mixer"); LSTR MSG_GRADIENT = _UxGT("Gradient"); LSTR MSG_FULL_GRADIENT = _UxGT("Full Gradient"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 03380af15e84..1272ea582e0b 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -58,7 +58,7 @@ namespace Language_ru { #endif LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Прогр. эндстопы"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Эндстопы"); // Max length 8 characters - LSTR MSG_MAIN = _UxGT("Основное меню"); + LSTR MSG_MAIN_MENU = _UxGT("Основное меню"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Другие настройки"); LSTR MSG_CONFIGURATION = _UxGT("Конфигурация"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Автостарт"); @@ -312,7 +312,7 @@ namespace Language_ru { LSTR MSG_SET_LEDS_VIOLET = _UxGT("Фиолетовый"); LSTR MSG_SET_LEDS_WHITE = _UxGT("Белый"); LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Свет по умолчанию"); - LSTR MSG_LED_CHANNEL_N = _UxGT("Канал ="); + LSTR MSG_LED_CHANNEL_N = _UxGT("Канал {"); LSTR MSG_LEDS2 = _UxGT("Свет #2"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_NEO2_PRESETS = _UxGT("Свет #2 предустановки"); @@ -487,7 +487,7 @@ namespace Language_ru { LSTR MSG_STOP_PRINT = _UxGT("Остановить печать"); LSTR MSG_PRINTING_OBJECT = _UxGT("Печать объекта"); LSTR MSG_CANCEL_OBJECT = _UxGT("Завершить объект"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Завершить объект ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Завершить объект {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Восстановение сбоя"); LSTR MSG_MEDIA_MENU = _UxGT("Печать с SD карты"); LSTR MSG_NO_MEDIA = _UxGT("Нет SD карты"); @@ -736,7 +736,7 @@ namespace Language_ru { #else LSTR MSG_MIX = _UxGT("Смешив."); #endif - LSTR MSG_MIX_COMPONENT_N = _UxGT("Компонент ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Компонент {"); LSTR MSG_MIXER = _UxGT("Смеситель"); LSTR MSG_GRADIENT = _UxGT("Градиент"); LSTR MSG_FULL_GRADIENT = _UxGT("Полный градиент"); @@ -766,10 +766,10 @@ namespace Language_ru { LSTR MSG_END_Z = _UxGT(" Конец Z"); LSTR MSG_GAMES = _UxGT("Игры"); - LSTR MSG_BRICKOUT = _UxGT("Кирпичи"); - LSTR MSG_INVADERS = _UxGT("Вторжение"); - LSTR MSG_SNAKE = _UxGT("Змейка"); - LSTR MSG_MAZE = _UxGT("Лабиринт"); + LSTR MSG_BRICKOUT = _UxGT("Brickout"); + LSTR MSG_INVADERS = _UxGT("Invaders"); + LSTR MSG_SNAKE = _UxGT("Sn4k3"); + LSTR MSG_MAZE = _UxGT("Maze"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_BAD_PAGE = _UxGT("Плохой индекс страницы"); @@ -826,7 +826,7 @@ namespace Language_ru { LSTR MSG_TMC_DRIVERS = _UxGT("Драйвера TMC"); LSTR MSG_TMC_CURRENT = _UxGT("Ток двигателей"); LSTR MSG_TMC_HYBRID_THRS = _UxGT("Гибридный режим"); - LSTR MSG_TMC_HOMING_THRS = _UxGT("Режим без эндстопов"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Чувствительность"); LSTR MSG_TMC_STEPPING_MODE = _UxGT("Режим драйвера"); LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("Тихий режим вкл"); @@ -864,7 +864,7 @@ namespace Language_ru { LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Калибровка успешна"); LSTR MSG_CALIBRATION_FAILED = _UxGT("Ошибка калибровки"); - LSTR MSG_DRIVER_BACKWARD = _UxGT(" драйвер назад"); + LSTR MSG_DRIVER_BACKWARD = _UxGT(" драйвер наоборот"); LSTR MSG_SD_CARD = _UxGT("SD Карта"); LSTR MSG_USB_DISK = _UxGT("USB Диск"); @@ -872,4 +872,5 @@ namespace Language_ru { LSTR MSG_SHORT_DAY = _UxGT("д"); // One character only LSTR MSG_SHORT_HOUR = _UxGT("ч"); // One character only LSTR MSG_SHORT_MINUTE = _UxGT("м"); // One character only + LSTR MSG_LINEAR_ADVANCE = _UxGT("Linear Advance"); } diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 024d02b71345..6899acc39863 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -34,7 +34,7 @@ * Substitutions are applied for the following characters when used in menu items titles: * * $ displays an inserted string - * = displays '0'....'10' for indexes 0 - 10 + * { displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) * @ displays an axis name such as XYZUVW, or E for an extruder @@ -65,7 +65,7 @@ namespace Language_sk { LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Preteč. podprogramu"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstopy"); // max 8 znakov LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft. endstopy"); - LSTR MSG_MAIN = _UxGT("Hlavná ponuka"); + LSTR MSG_MAIN_MENU = _UxGT("Hlavná ponuka"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Pokročilé nastav."); LSTR MSG_TOOLBAR_SETUP = _UxGT("Panel nástrojov"); LSTR MSG_OPTION_DISABLED = _UxGT("Možnosť vypnutá"); @@ -294,7 +294,7 @@ namespace Language_sk { LSTR MSG_SET_LEDS_VIOLET = _UxGT("Fialová"); LSTR MSG_SET_LEDS_WHITE = _UxGT("Biela"); LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Obnoviť nastavenie"); - LSTR MSG_LED_CHANNEL_N = _UxGT("Kanál ="); + LSTR MSG_LED_CHANNEL_N = _UxGT("Kanál {"); LSTR MSG_LEDS2 = _UxGT("Svetlo #2"); LSTR MSG_NEO2_PRESETS = _UxGT("Predvolby svetla #2"); LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Jas"); @@ -500,7 +500,7 @@ namespace Language_sk { LSTR MSG_HOST_START_PRINT = _UxGT("Spustiť z hosta"); LSTR MSG_PRINTING_OBJECT = _UxGT("Tlačím objekt"); LSTR MSG_CANCEL_OBJECT = _UxGT("Zrušiť objekt"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Zrušiť objekt ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Zrušiť objekt {"); LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Pokračovať v úlohe"); LSTR MSG_MEDIA_MENU = _UxGT("Vytlačiť z karty"); LSTR MSG_TURN_OFF = _UxGT("Vypnite tlačiareň"); @@ -509,7 +509,7 @@ namespace Language_sk { LSTR MSG_HOST_START_PRINT = _UxGT("Spustiť z hosta"); LSTR MSG_PRINTING_OBJECT = _UxGT("Tlačím obj."); LSTR MSG_CANCEL_OBJECT = _UxGT("Zrušiť obj."); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Zrušiť obj. ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Zrušiť obj. {"); LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Pokrač. v úlohe"); LSTR MSG_MEDIA_MENU = _UxGT("Tlač z karty"); LSTR MSG_TURN_OFF = _UxGT("Vypnit. teraz"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index e66de33c221e..e2d08c5c2409 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -51,7 +51,7 @@ namespace Language_sv { LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Underanrop överskriden"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Slutstop"); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Mjuk slutstopp"); - LSTR MSG_MAIN = _UxGT("Huvud"); + LSTR MSG_MAIN_MENU = _UxGT("Huvud"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Advancerade inställningar"); LSTR MSG_CONFIGURATION = _UxGT("Konfiguration"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostarta Filer"); @@ -233,7 +233,7 @@ namespace Language_sv { LSTR MSG_SET_LEDS_VIOLET = _UxGT("Violet"); LSTR MSG_SET_LEDS_WHITE = _UxGT("Vitt"); LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Standard"); - LSTR MSG_LED_CHANNEL_N = _UxGT("Kanal ="); + LSTR MSG_LED_CHANNEL_N = _UxGT("Kanal {"); LSTR MSG_LEDS2 = _UxGT("Ljus #2"); LSTR MSG_NEO2_PRESETS = _UxGT("Ljus #2 Förinställd"); LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Ljusstyrka"); @@ -381,7 +381,7 @@ namespace Language_sv { LSTR MSG_END_LOOPS = _UxGT("Slut Upprepningsloop"); LSTR MSG_PRINTING_OBJECT = _UxGT("Skriver Objekt"); LSTR MSG_CANCEL_OBJECT = _UxGT("Avbryt Objekt"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Avbryt Objekt ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Avbryt Objekt {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Ström Avbrott"); LSTR MSG_MEDIA_MENU = _UxGT("Skriv fråm Media"); LSTR MSG_NO_MEDIA = _UxGT("Inget Media"); @@ -569,7 +569,7 @@ namespace Language_sv { LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Ta bort, Klicka"); LSTR MSG_MIX = _UxGT("Mixa"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponent ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponent {"); LSTR MSG_MIXER = _UxGT("Mixer"); LSTR MSG_GRADIENT = _UxGT("Gradient"); LSTR MSG_FULL_GRADIENT = _UxGT("Full Gradient"); diff --git a/Marlin/src/lcd/language/language_test.h b/Marlin/src/lcd/language/language_test.h index 20b5a7e686ab..f517a8775992 100644 --- a/Marlin/src/lcd/language/language_test.h +++ b/Marlin/src/lcd/language/language_test.h @@ -44,22 +44,18 @@ // Kanji (an other Japanese symbol set) uses far more than two codepages. So currently I don't see a chance to map the Unicodes. Its not // impossible to have a close to direct mapping but will need giant conversion tables and fonts (we don't want to have in a embedded system). - // Select the better font for full graphic displays. //#define DISPLAY_CHARSET_ISO10646_1 //#define DISPLAY_CHARSET_ISO10646_5 //#define DISPLAY_CHARSET_ISO10646_GREEK //#define DISPLAY_CHARSET_ISO10646_KANA - - // next 5 lines select variants in this file only #define DISPLAYTEST //#define WEST //#define CYRIL //#define KANA - // TESTSTRINGS #define STRG_ASCII_2 _UxGT(" !\"#$%&'()*+,-./") @@ -133,7 +129,7 @@ namespace Language_test { LSTR MSG_PREPARE = _UxGT("UTF8"); LSTR MSG_CONTROL = _UxGT("ASCII"); - LSTR MSG_MAIN = _UxGT(".."); + LSTR MSG_MAIN_MENU = _UxGT(".."); LSTR MSG_DISABLE_STEPPERS = STRG_C2_8; LSTR MSG_AUTO_HOME = STRG_C2_9; LSTR MSG_SET_HOME_OFFSETS = STRG_C2_a; @@ -143,7 +139,7 @@ namespace Language_test { LSTR MSG_SWITCH_PS_OFF = STRG_C3_a; LSTR MSG_MOVE_AXIS = STRG_C3_b; - LSTR MSG_MAIN = STRG_OKTAL_2; + LSTR MSG_MAIN_MENU = STRG_OKTAL_2; LSTR MSG_TEMPERATURE = STRG_OKTAL_3; LSTR MSG_MOTION = STRG_OKTAL_4; LSTR MSG_FILAMENT = STRG_OKTAL_5; @@ -170,7 +166,7 @@ namespace Language_test { LSTR MSG_PREPARE = _UxGT("UTF8"); LSTR MSG_CONTROL = _UxGT("ASCII"); - LSTR MSG_MAIN = _UxGT(".."); + LSTR MSG_MAIN_MENU = _UxGT(".."); LSTR MSG_DISABLE_STEPPERS = STRG_D0_8; LSTR MSG_AUTO_HOME = STRG_D0_9; LSTR MSG_SET_HOME_OFFSETS = STRG_D0_a; @@ -180,7 +176,7 @@ namespace Language_test { LSTR MSG_SWITCH_PS_OFF = STRG_D1_a; LSTR MSG_MOVE_AXIS = STRG_D1_b; - LSTR MSG_MAIN = STRG_OKTAL_2; + LSTR MSG_MAIN_MENU = STRG_OKTAL_2; LSTR MSG_TEMPERATURE = STRG_OKTAL_3; LSTR MSG_MOTION = STRG_OKTAL_4; LSTR MSG_FILAMENT = STRG_OKTAL_5; @@ -206,7 +202,7 @@ namespace Language_test { LSTR MSG_PREPARE = _UxGT("UTF8"); LSTR MSG_CONTROL = _UxGT("ASCII"); - LSTR MSG_MAIN = _UxGT(".."); + LSTR MSG_MAIN_MENU = _UxGT(".."); LSTR MSG_DISABLE_STEPPERS = STRG_E382_8; LSTR MSG_AUTO_HOME = STRG_E382_9; LSTR MSG_SET_HOME_OFFSETS = STRG_E382_a; @@ -216,7 +212,7 @@ namespace Language_test { LSTR MSG_SWITCH_PS_OFF = STRG_E383_a; LSTR MSG_MOVE_AXIS = STRG_E383_b; - LSTR MSG_MAIN = STRG_OKTAL_2; + LSTR MSG_MAIN_MENU = STRG_OKTAL_2; LSTR MSG_TEMPERATURE = STRG_OKTAL_3; LSTR MSG_MOTION = STRG_OKTAL_4; LSTR MSG_FILAMENT = STRG_OKTAL_5; diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index ca6a38142caa..5fc78758d4f1 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -55,7 +55,7 @@ namespace Language_tr { LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Yazılımsal Endstops"); - LSTR MSG_MAIN = _UxGT("Ana"); + LSTR MSG_MAIN_MENU = _UxGT("Ana"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Gelişmiş Ayarlar"); LSTR MSG_TOOLBAR_SETUP = _UxGT("Araç Çubuğu Kurulumu"); LSTR MSG_OPTION_DISABLED = _UxGT("Seçenek Devre Dışı"); @@ -280,7 +280,7 @@ namespace Language_tr { LSTR MSG_SET_LEDS_VIOLET = _UxGT("Menekşe"); LSTR MSG_SET_LEDS_WHITE = _UxGT("Beyaz"); LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Varsayılan"); - LSTR MSG_LED_CHANNEL_N = _UxGT("Kanal ="); + LSTR MSG_LED_CHANNEL_N = _UxGT("Kanal {"); LSTR MSG_LEDS2 = _UxGT("Işıklar #2"); LSTR MSG_NEO2_PRESETS = _UxGT("Işık #2 Ön Ayarları"); LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Parlaklık"); @@ -479,7 +479,7 @@ namespace Language_tr { LSTR MSG_HOST_START_PRINT = _UxGT("Host Baskıyı başlat"); LSTR MSG_PRINTING_OBJECT = _UxGT("Yazdırma Nesnesi"); LSTR MSG_CANCEL_OBJECT = _UxGT("Nesneyi İptal Et"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Nesneyi İptal Et ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Nesneyi İptal Et {"); LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Yazdırmaya Devam Et"); LSTR MSG_MEDIA_MENU = _UxGT("SD Karttan Yazdır"); LSTR MSG_TURN_OFF = _UxGT("Yazıcıyı kapat"); @@ -488,7 +488,7 @@ namespace Language_tr { LSTR MSG_HOST_START_PRINT = _UxGT("Host Başlatma"); LSTR MSG_PRINTING_OBJECT = _UxGT("Nesneyi Yazdır"); LSTR MSG_CANCEL_OBJECT = _UxGT("Nesneyi İptal Et"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Nesneyi İptal Et ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Nesneyi İptal Et {"); LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("İşe Devam Et"); LSTR MSG_MEDIA_MENU = MEDIA_TYPE_EN _UxGT(" Yazdır"); LSTR MSG_TURN_OFF = _UxGT("Şimdi kapat"); @@ -720,7 +720,7 @@ namespace Language_tr { LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Kaldır, tıkla"); LSTR MSG_MIX = _UxGT("Karışım"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("Bileşen ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Bileşen {"); LSTR MSG_MIXER = _UxGT("Karıştırıcı"); LSTR MSG_GRADIENT = _UxGT("Gradyan"); LSTR MSG_FULL_GRADIENT = _UxGT("Tam Gradyan"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index e678cd872e48..2db94dba86d8 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -60,7 +60,7 @@ namespace Language_uk { LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Прогр.кінцевики"); #endif LSTR MSG_LCD_ENDSTOPS = _UxGT("Кінцевик"); // Max length 8 characters - LSTR MSG_MAIN = _UxGT("Основне меню"); + LSTR MSG_MAIN_MENU = _UxGT("Основне меню"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Інші налаштування"); LSTR MSG_CONFIGURATION = _UxGT("Конфігурація"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Автостарт"); @@ -313,7 +313,7 @@ namespace Language_uk { LSTR MSG_SET_LEDS_VIOLET = _UxGT("Фіолетовий"); LSTR MSG_SET_LEDS_WHITE = _UxGT("Білий"); LSTR MSG_SET_LEDS_DEFAULT = _UxGT("За умовчанням"); - LSTR MSG_LED_CHANNEL_N = _UxGT("Канал ="); + LSTR MSG_LED_CHANNEL_N = _UxGT("Канал {"); LSTR MSG_LEDS2 = _UxGT("Світло #2"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 LSTR MSG_NEO2_PRESETS = _UxGT("Передустановка світла #2"); @@ -507,7 +507,7 @@ namespace Language_uk { LSTR MSG_END_LOOPS = _UxGT("End Repeat Loops"); // needs translation LSTR MSG_PRINTING_OBJECT = _UxGT("Друк об'єкта"); LSTR MSG_CANCEL_OBJECT = _UxGT("Завершити об'єкт"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Завершити об'єкт ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Завершити об'єкт {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Віднов. після збою"); LSTR MSG_MEDIA_MENU = _UxGT("Друкувати з SD"); LSTR MSG_NO_MEDIA = _UxGT("SD-картки немає"); @@ -780,7 +780,7 @@ namespace Language_uk { #else LSTR MSG_MIX = _UxGT("Змішув."); #endif - LSTR MSG_MIX_COMPONENT_N = _UxGT("Компонент ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("Компонент {"); LSTR MSG_MIXER = _UxGT("Змішувач"); LSTR MSG_GRADIENT = _UxGT("Градієнт"); LSTR MSG_FULL_GRADIENT = _UxGT("Повний градієнт"); @@ -833,7 +833,6 @@ namespace Language_uk { LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Не забудь зберегти!"); LSTR MSG_PASSWORD_REMOVED = _UxGT("Пароль видалений"); - // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 3b83349207e6..223186e6f093 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -44,7 +44,7 @@ namespace Language_vi { LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB khởi thất bại"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Công tắc"); // Endstops - công tắc hành trình LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Công tắc mềm"); // soft Endstops - LSTR MSG_MAIN = _UxGT("Chính"); // Main + LSTR MSG_MAIN_MENU = _UxGT("Chính"); // Main LSTR MSG_ADVANCED_SETTINGS = _UxGT("Thiết lập cấp cao"); // Advanced Settings LSTR MSG_CONFIGURATION = _UxGT("Cấu hình"); // Configuration LSTR MSG_RUN_AUTO_FILES = _UxGT("Khởi chạy tự động"); // Autostart diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 9dbb61e70b07..e87ac44d3bce 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -48,7 +48,7 @@ namespace Language_zh_CN { LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("子响应溢出"); LSTR MSG_LCD_ENDSTOPS = _UxGT("挡块"); // "Endstops" // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("软挡块"); - LSTR MSG_MAIN = _UxGT("主菜单"); // "Main" + LSTR MSG_MAIN_MENU = _UxGT("主菜单"); // "Main" LSTR MSG_ADVANCED_SETTINGS = _UxGT("高级设置"); LSTR MSG_CONFIGURATION = _UxGT("配置"); LSTR MSG_RUN_AUTO_FILES = _UxGT("自动开始"); // "Autostart" @@ -348,7 +348,7 @@ namespace Language_zh_CN { LSTR MSG_STOP_PRINT = _UxGT("停止打印"); // "Stop print" LSTR MSG_PRINTING_OBJECT = _UxGT("打印物体"); LSTR MSG_CANCEL_OBJECT = _UxGT("取消物体"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("取消物体 ="); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("取消物体 {"); LSTR MSG_OUTAGE_RECOVERY = _UxGT("中断恢复"); LSTR MSG_MEDIA_MENU = _UxGT("从存储卡上打印"); // "Print from SD" LSTR MSG_NO_MEDIA = _UxGT("无存储卡"); // "No SD card" @@ -532,7 +532,7 @@ namespace Language_zh_CN { LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("移出, 按下"); LSTR MSG_MIX = _UxGT("混合"); - LSTR MSG_MIX_COMPONENT_N = _UxGT("器件 ="); + LSTR MSG_MIX_COMPONENT_N = _UxGT("器件 {"); LSTR MSG_MIXER = _UxGT("混合器"); LSTR MSG_GRADIENT = _UxGT("梯度"); LSTR MSG_FULL_GRADIENT = _UxGT("全梯度"); diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 49e57d6220fd..222d27f77ea0 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -46,7 +46,7 @@ namespace Language_zh_TW { LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB啟動失敗"); // "USB start failed" LSTR MSG_LCD_ENDSTOPS = _UxGT("擋塊"); // "Endstops" // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("軟體擋塊"); // "Soft Endstops" - LSTR MSG_MAIN = _UxGT("主選單"); // "Main" + LSTR MSG_MAIN_MENU = _UxGT("主選單"); // "Main" LSTR MSG_ADVANCED_SETTINGS = _UxGT("進階設置"); // "Advanced Settings" LSTR MSG_CONFIGURATION = _UxGT("設置"); //Configuration LSTR MSG_RUN_AUTO_FILES = _UxGT("自動開始"); // "Autostart" @@ -235,10 +235,10 @@ namespace Language_zh_TW { LSTR MSG_BED = " " LCD_STR_THERMOMETER _UxGT(" 熱床"); // "Bed" LSTR MSG_CHAMBER = _UxGT("Enclosure"); LSTR MSG_FAN_SPEED = _UxGT("風扇速率"); // "Fan speed" - LSTR MSG_FAN_SPEED_N = _UxGT("風扇速率 ="); - LSTR MSG_STORED_FAN_N = _UxGT("Stored Fan ="); + LSTR MSG_FAN_SPEED_N = _UxGT("風扇速率 {"); + LSTR MSG_STORED_FAN_N = _UxGT("Stored Fan {"); LSTR MSG_EXTRA_FAN_SPEED = _UxGT("額外風扇速率"); // "Extra fan speed" - LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("額外風扇速率 ="); + LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("額外風扇速率 {"); LSTR MSG_FLOW = _UxGT("擠出速率"); LSTR MSG_FLOW_N = _UxGT("擠出速率 ~"); // "Flow" LSTR MSG_CONTROL = _UxGT("控制"); // "Control" @@ -322,7 +322,7 @@ namespace Language_zh_TW { LSTR MSG_STOP_PRINT = _UxGT("停止列印"); // "Stop print" LSTR MSG_PRINTING_OBJECT = _UxGT("列印物件"); // "Printing Object" LSTR MSG_CANCEL_OBJECT = _UxGT("中止物件"); // "Cancel Object" - LSTR MSG_CANCEL_OBJECT_N = _UxGT("中止物件 ="); // "Cancel Object =" + LSTR MSG_CANCEL_OBJECT_N = _UxGT("中止物件 {"); // "Cancel Object =" LSTR MSG_OUTAGE_RECOVERY = _UxGT("中斷恢復"); // "Outage Recovery" LSTR MSG_MEDIA_MENU = _UxGT("從記憶卡上列印"); // "Print from SD" LSTR MSG_NO_MEDIA = _UxGT("無記憶卡"); // "No SD card" diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index 650824e553bc..162f01a12cbd 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -37,7 +37,7 @@ * Print a string with optional substitutions: * * $ displays the clipped string given by fstr or cstr - * = displays '0'....'10' for indexes 0 - 10 + * { displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) * @ displays an axis name such as XYZUVW, or E for an extruder @@ -50,11 +50,11 @@ lcd_uint_t lcd_put_u8str_P(PGM_P const ptpl, const int8_t ind, const char *cstr/ lchar_t wc; p = get_utf8_value_cb(p, read_byte_rom, wc); if (!wc) break; - if (wc == '=' || wc == '~' || wc == '*') { + if (wc == '{' || wc == '~' || wc == '*') { if (ind >= 0) { if (wc == '*') { lcd_put_u8str(F("E")); n--; } if (n) { - int8_t inum = ind + ((wc == '=') ? 0 : LCD_FIRST_TOOL); + int8_t inum = ind + ((wc == '{') ? 0 : LCD_FIRST_TOOL); if (inum >= 10) { lcd_put_lchar('0' + (inum / 10)); n--; inum %= 10; diff --git a/Marlin/src/lcd/lcdprint.h b/Marlin/src/lcd/lcdprint.h index bcf85cb69396..f4343c22661c 100644 --- a/Marlin/src/lcd/lcdprint.h +++ b/Marlin/src/lcd/lcdprint.h @@ -30,7 +30,7 @@ */ #pragma once -#include "fontutils.h" +#include "utf8.h" #include "../inc/MarlinConfig.h" @@ -208,11 +208,11 @@ inline int lcd_put_u8str(const lcd_uint_t col, const lcd_uint_t row, FSTR_P cons /** * @brief Draw a string with optional substitution * @details Print a string with optional substitutions: - * $ displays the clipped string given by fstr or cstr - * = displays '0'....'10' for indexes 0 - 10 - * ~ displays '1'....'11' for indexes 0 - 10 - * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) - * @ displays an axis name such as XYZUVW, or E for an extruder + * $ : the clipped string given by fstr or cstr + * { : '0'....'10' for indexes 0 - 10 + * ~ : '1'....'11' for indexes 0 - 10 + * * : 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) + * @ : an axis name such as XYZUVW, or E for an extruder * * @param ptpl A ROM string (template) * @param ind An index value to use for = ~ * substitution diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 604e9bb0ca7a..b8ef8e1ed88b 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -24,7 +24,7 @@ #include "../MarlinCore.h" // for printingIsPaused -#if LED_POWEROFF_TIMEOUT > 0 || BOTH(HAS_WIRED_LCD, PRINTER_EVENT_LEDS) +#if LED_POWEROFF_TIMEOUT > 0 || ALL(HAS_WIRED_LCD, PRINTER_EVENT_LEDS) #include "../feature/leds/leds.h" #endif @@ -32,7 +32,7 @@ #include "../feature/host_actions.h" #endif -#if BOTH(BROWSE_MEDIA_ON_INSERT, PASSWORD_ON_SD_PRINT_MENU) +#if ALL(BROWSE_MEDIA_ON_INSERT, PASSWORD_ON_SD_PRINT_MENU) #include "../feature/password/password.h" #endif @@ -42,7 +42,7 @@ MarlinUI ui; #if HAS_DISPLAY #include "../gcode/queue.h" - #include "fontutils.h" + #include "utf8.h" #endif #if ENABLED(DWIN_CREALITY_LCD) @@ -68,7 +68,7 @@ MarlinUI ui; constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #if HAS_STATUS_MESSAGE - #if ENABLED(STATUS_MESSAGE_SCROLLING) && EITHER(HAS_WIRED_LCD, DWIN_LCD_PROUI) + #if ENABLED(STATUS_MESSAGE_SCROLLING) && ANY(HAS_WIRED_LCD, DWIN_LCD_PROUI) uint8_t MarlinUI::status_scroll_offset; // = 0 #endif char MarlinUI::status_message[MAX_MESSAGE_LENGTH + 1]; @@ -154,7 +154,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; } #endif -#if EITHER(HAS_MARLINUI_MENU, EXTENSIBLE_UI) +#if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI) bool MarlinUI::lcd_clicked; #endif @@ -213,6 +213,10 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; void MarlinUI::init() { + #if HAS_U8GLIB_I2C_OLED && PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM) + Wire.begin(uint8_t(I2C_SDA_PIN), uint8_t(I2C_SCL_PIN)); + #endif + init_lcd(); #if HAS_DIGITAL_BUTTONS @@ -265,14 +269,10 @@ void MarlinUI::init() { #endif // HAS_SHIFT_ENCODER - #if BOTH(HAS_ENCODER_ACTION, HAS_SLOW_BUTTONS) + #if ALL(HAS_ENCODER_ACTION, HAS_SLOW_BUTTONS) slow_buttons = 0; #endif - #if HAS_U8GLIB_I2C_OLED && PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM) - Wire.begin(int(I2C_SDA_PIN), int(I2C_SCL_PIN)); - #endif - update_buttons(); TERN_(HAS_ENCODER_ACTION, encoderDiff = 0); @@ -334,7 +334,7 @@ void MarlinUI::init() { uint8_t MarlinUI::lcd_status_update_delay = 1; // First update one loop delayed - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #if ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) millis_t MarlinUI::next_filament_display; // = 0 #endif @@ -348,7 +348,7 @@ void MarlinUI::init() { bool MarlinUI::did_first_redraw; #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA #if MARLINUI_SCROLL_NAME uint8_t MarlinUI::filename_scroll_pos, MarlinUI::filename_scroll_max; @@ -397,16 +397,16 @@ void MarlinUI::init() { } #endif - #if EITHER(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) + #if ANY(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) int8_t MarlinUI::encoderDirection = ENCODERBASE; #endif #if HAS_TOUCH_BUTTONS uint8_t MarlinUI::touch_buttons; - uint8_t MarlinUI::repeat_delay; + uint16_t MarlinUI::repeat_delay; #endif - #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) + #if ANY(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) bool MarlinUI::external_control; // = false @@ -419,7 +419,7 @@ void MarlinUI::init() { #if !HAS_GRAPHICAL_TFT - void _wrap_string(uint8_t &col, uint8_t &row, const char * const string, read_byte_cb_t cb_read_byte, bool wordwrap/*=false*/) { + void _wrap_string(uint8_t &col, uint8_t &row, const char * const string, read_byte_cb_t cb_read_byte, const bool wordwrap/*=false*/) { SETCURSOR(col, row); if (!string) return; @@ -439,8 +439,9 @@ void MarlinUI::init() { p = get_utf8_value_cb(p, cb_read_byte, wc); const bool eol = !wc; // zero ends the string // End or a break between phrases? - if (eol || wc == ' ' || wc == '-' || wc == '+' || wc == '.') { - if (!c && wc == ' ') { if (wrd) wrd++; continue; } // collapse extra spaces + if (eol || wc == ' ' || wc == '-' || wc == '+' || wc == '.' || wc == '\n') { + const bool newline_after = wc == '\n'; + if (!c && (wc == ' ' || newline_after)) { if (wrd) wrd++; continue; } // collapse extra spaces // Past the right and the word is not too long? if (col + c > LCD_WIDTH && col >= (LCD_WIDTH) / 4) _newline(); // should it wrap? c += !eol; // +1 so the space will be printed @@ -451,6 +452,7 @@ void MarlinUI::init() { lcd_put_lchar(wc); // character to the LCD } if (eol) break; // all done! + if (newline_after) _newline(); wrd = nullptr; // set up for next word } else c++; // count word characters @@ -467,30 +469,26 @@ void MarlinUI::init() { } } - void MarlinUI::draw_select_screen_prompt(FSTR_P const pref, const char * const string/*=nullptr*/, FSTR_P const suff/*=nullptr*/) { - const uint8_t plen = utf8_strlen(pref), slen = suff ? utf8_strlen(suff) : 0; + void MarlinUI::draw_select_screen_prompt(FSTR_P const fpre, const char * const string/*=nullptr*/, FSTR_P const fsuf/*=nullptr*/) { + const uint8_t plen = utf8_strlen_P(FTOP(fpre)), slen = fsuf ? utf8_strlen_P(FTOP(fsuf)) : 0; uint8_t col = 0, row = 0; if (!string && plen + slen <= LCD_WIDTH) { col = (LCD_WIDTH - plen - slen) / 2; row = LCD_HEIGHT > 3 ? 1 : 0; } if (LCD_HEIGHT >= 8) row = LCD_HEIGHT / 2 - 2; - wrap_string_P(col, row, FTOP(pref), true); + wrap_string_P(col, row, FTOP(fpre), true); if (string) { if (col) { col = 0; row++; } // Move to the start of the next line wrap_string(col, row, string); } - if (suff) wrap_string_P(col, row, FTOP(suff)); + if (fsuf) wrap_string_P(col, row, FTOP(fsuf)); } #endif // !HAS_GRAPHICAL_TFT #endif // HAS_MARLINUI_MENU - //////////////////////////////////////////// - ///////////// Keypad Handling ////////////// - //////////////////////////////////////////// - #if IS_RRW_KEYPAD && HAS_ENCODER_ACTION volatile uint8_t MarlinUI::keypad_buttons; @@ -501,7 +499,7 @@ void MarlinUI::init() { ui.manual_move.menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; ui.encoderPosition = dir; switch (axis) { - case X_AXIS: + TERN_(HAS_X_AXIS, case X_AXIS:) TERN_(HAS_Y_AXIS, case Y_AXIS:) TERN_(HAS_Z_AXIS, case Z_AXIS:) lcd_move_axis(axis); @@ -569,7 +567,7 @@ void MarlinUI::init() { #endif if (homed) { - #if EITHER(DELTA, Z_HOME_TO_MAX) + #if ANY(DELTA, Z_HOME_TO_MAX) if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); #endif if (RRK(EN_KEYPAD_F3)) _reprapworld_keypad_move(Z_AXIS, -1); @@ -665,7 +663,7 @@ void MarlinUI::init() { #if HAS_MARLINUI_MENU if (use_click()) { - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #if ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) pause_filament_display(); #endif goto_screen(menu_main); @@ -697,7 +695,7 @@ void MarlinUI::init() { if (old_frm != new_frm) { feedrate_percentage = new_frm; encoderPosition = 0; - #if BOTH(HAS_SOUND, BEEP_ON_FEEDRATE_CHANGE) + #if ALL(HAS_SOUND, BEEP_ON_FEEDRATE_CHANGE) static millis_t next_beep; #ifndef GOT_MS const millis_t ms = millis(); @@ -771,10 +769,6 @@ void MarlinUI::init() { #endif } - //////////////////////////////////////////// - /////////////// Manual Move //////////////// - //////////////////////////////////////////// - #if HAS_MARLINUI_MENU ManualMove MarlinUI::manual_move{}; @@ -856,7 +850,7 @@ void MarlinUI::init() { TERN_(MULTI_E_MANUAL, axis == E_AXIS ? e_index :) active_extruder ); - //SERIAL_ECHOLNPGM("Add planner.move with Axis ", AS_CHAR(AXIS_CHAR(axis)), " at FR ", fr_mm_s); + //SERIAL_ECHOLNPGM("Add planner.move with Axis ", C(AXIS_CHAR(axis)), " at FR ", fr_mm_s); axis = NO_AXIS_ENUM; @@ -873,7 +867,7 @@ void MarlinUI::init() { TERN_(MULTI_E_MANUAL, if (move_axis == E_AXIS) e_index = eindex); start_time = millis() + (menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves axis = move_axis; - //SERIAL_ECHOLNPGM("Post Move with Axis ", AS_CHAR(AXIS_CHAR(axis)), " soon."); + //SERIAL_ECHOLNPGM("Post Move with Axis ", C(AXIS_CHAR(axis)), " soon."); } #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -881,8 +875,8 @@ void MarlinUI::init() { void MarlinUI::external_encoder() { if (external_control && encoderDiff) { bedlevel.encoder_diff += encoderDiff; // Encoder for UBL G29 mesh editing - encoderDiff = 0; // Hide encoder events from the screen handler - refresh(LCDVIEW_REDRAW_NOW); // ...but keep the refresh. + encoderDiff = 0; // Hide encoder events from the screen handler + refresh(LCDVIEW_REDRAW_NOW); // ...but keep the refresh. } } @@ -1041,7 +1035,7 @@ void MarlinUI::init() { if (encoderPastThreshold || lcd_clicked) { if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) { - #if BOTH(HAS_MARLINUI_MENU, ENCODER_RATE_MULTIPLIER) + #if ALL(HAS_MARLINUI_MENU, ENCODER_RATE_MULTIPLIER) int32_t encoderMultiplier = 1; @@ -1107,7 +1101,7 @@ void MarlinUI::init() { refresh(LCDVIEW_REDRAW_NOW); } - #if BOTH(HAS_MARLINUI_MENU, SCROLL_LONG_FILENAMES) + #if ALL(HAS_MARLINUI_MENU, SCROLL_LONG_FILENAMES) // If scrolling of long file names is enabled and we are in the sd card menu, // cause a refresh to occur until all the text has scrolled into view. if (currentScreen == menu_media && !lcd_status_update_delay--) { @@ -1278,7 +1272,7 @@ void MarlinUI::init() { thermalManager.current_ADCKey_raw = HAL_ADC_RANGE; thermalManager.ADCKey_count = 0; if (currentkpADCValue < adc_other_button) - LOOP_L_N(i, ADC_KEY_NUM) { + for (uint8_t i = 0; i < ADC_KEY_NUM; ++i) { const raw_adc_t lo = pgm_read_word(&stADCKeyTable[i].ADCKeyValueMin), hi = pgm_read_word(&stADCKeyTable[i].ADCKeyValueMax); if (WITHIN(currentkpADCValue, lo, hi)) return pgm_read_byte(&stADCKeyTable[i].ADCKeyNo); @@ -1342,7 +1336,7 @@ void MarlinUI::init() { #endif // UP || DOWN || LEFT || RIGHT buttons = (newbutton | TERN0(HAS_SLOW_BUTTONS, slow_buttons) - #if BOTH(HAS_TOUCH_BUTTONS, HAS_ENCODER_ACTION) + #if ALL(HAS_TOUCH_BUTTONS, HAS_ENCODER_ACTION) | (touch_buttons & TERN(HAS_ENCODER_WHEEL, ~(EN_A | EN_B), 0xFF)) #endif ); @@ -1369,7 +1363,7 @@ void MarlinUI::init() { uint8_t val = 0; WRITE(SHIFT_LD_PIN, LOW); WRITE(SHIFT_LD_PIN, HIGH); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { val >>= 1; if (READ(SHIFT_OUT_PIN)) SBI(val, 7); WRITE(SHIFT_CLK_PIN, HIGH); @@ -1402,7 +1396,7 @@ void MarlinUI::init() { case 3: ENCODER_SPIN(2, 1); break; case 1: ENCODER_SPIN(3, 0); break; } - #if BOTH(HAS_MARLINUI_MENU, AUTO_BED_LEVELING_UBL) + #if ALL(HAS_MARLINUI_MENU, AUTO_BED_LEVELING_UBL) external_encoder(); #endif lastEncoderBits = enc; @@ -1424,10 +1418,6 @@ void MarlinUI::init() { #if HAS_STATUS_MESSAGE - //////////////////////////////////////////// - ////////////// Status Message ////////////// - //////////////////////////////////////////// - #if ENABLED(EXTENSIBLE_UI) #include "extui/ui_api.h" #endif @@ -1464,7 +1454,6 @@ void MarlinUI::init() { /** * Reset the status message */ - void MarlinUI::reset_status(const bool no_welcome) { #if SERVICE_INTERVAL_1 > 0 static PGMSTR(service1, "> " SERVICE_NAME_1 "!"); @@ -1479,7 +1468,7 @@ void MarlinUI::init() { FSTR_P msg; if (printingIsPaused()) msg = GET_TEXT_F(MSG_PRINT_PAUSED); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA else if (IS_SD_PRINTING()) return set_status(card.longest_filename(), true); #endif @@ -1576,7 +1565,7 @@ void MarlinUI::init() { #if HAS_WIRED_LCD - #if BASIC_PROGRESS_BAR || BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #if BASIC_PROGRESS_BAR || ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) const millis_t ms = millis(); #endif @@ -1587,13 +1576,13 @@ void MarlinUI::init() { #endif #endif - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #if ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) pause_filament_display(ms); // Show status message for 5s #endif #endif - #if ENABLED(STATUS_MESSAGE_SCROLLING) && EITHER(HAS_WIRED_LCD, DWIN_LCD_PROUI) + #if ENABLED(STATUS_MESSAGE_SCROLLING) && ANY(HAS_WIRED_LCD, DWIN_LCD_PROUI) status_scroll_offset = 0; #endif @@ -1640,12 +1629,12 @@ void MarlinUI::init() { #if HAS_DISPLAY - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA extern bool wait_for_user, wait_for_heatup; #endif void MarlinUI::abort_print() { - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA wait_for_heatup = wait_for_user = false; card.abortFilePrintSoon(); #endif @@ -1659,7 +1648,7 @@ void MarlinUI::init() { TERN_(DWIN_LCD_PROUI, HMI_flag.abort_flag = true); } - #if BOTH(HAS_MARLINUI_MENU, PSU_CONTROL) + #if ALL(HAS_MARLINUI_MENU, PSU_CONTROL) void MarlinUI::poweroff() { queue.inject(F("M81" TERN_(POWER_OFF_WAIT_FOR_COOLDOWN, "S"))); @@ -1668,11 +1657,13 @@ void MarlinUI::init() { #endif - void MarlinUI::flow_fault() { - LCD_ALERTMESSAGE(MSG_FLOWMETER_FAULT); - BUZZ(1000, 440); - TERN_(HAS_MARLINUI_MENU, return_to_status()); - } + #if ENABLED(FLOWMETER_SAFETY) + void MarlinUI::flow_fault() { + LCD_ALERTMESSAGE(MSG_FLOWMETER_FAULT); + BUZZ(1000, 440); + TERN_(HAS_MARLINUI_MENU, return_to_status()); + } + #endif void MarlinUI::pause_print() { #if HAS_MARLINUI_MENU @@ -1688,7 +1679,7 @@ void MarlinUI::init() { #if ENABLED(PARK_HEAD_ON_PAUSE) pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT); // Show message immediately to let user know about pause in progress queue.inject(F("M25 P\nM24")); - #elif ENABLED(SDSUPPORT) + #elif HAS_MEDIA queue.inject(F("M25")); #elif defined(ACTION_ON_PAUSE) hostui.pause(); @@ -1698,7 +1689,7 @@ void MarlinUI::init() { void MarlinUI::resume_print() { reset_status(); TERN_(PARK_HEAD_ON_PAUSE, wait_for_heatup = wait_for_user = false); - TERN_(SDSUPPORT, if (IS_SD_PAUSED()) queue.inject_P(M24_STR)); + TERN_(HAS_MEDIA, if (IS_SD_PAUSED()) queue.inject_P(M24_STR)); #ifdef ACTION_ON_RESUME hostui.resume(); #endif @@ -1707,13 +1698,13 @@ void MarlinUI::init() { #if HAS_TOUCH_BUTTONS - // - // Screen Click - // - On menu screens move directly to the touched item - // - On menu screens, right side (last 3 cols) acts like a scroll - half up => prev page, half down = next page - // - On select screens (and others) touch the Right Half for +, Left Half for - - // - On edit screens, touch Up Half for -, Bottom Half to + - // + /** + * Screen Click + * - On menu screens move directly to the touched item + * - On menu screens, right side (last 3 cols) acts like a scroll - half up => prev page, half down = next page + * - On select screens (and others) touch the Left Half for ←, Right Half for → + * - On edit screens, touch Top Half for ↑, Bottom Half for ↓ + */ void MarlinUI::screen_click(const uint8_t row, const uint8_t col, const uint8_t, const uint8_t) { const millis_t now = millis(); if (PENDING(now, next_button_update_ms)) return; @@ -1743,7 +1734,7 @@ void MarlinUI::init() { MarlinUI::progress_t MarlinUI::_get_progress() { return ( TERN0(SET_PROGRESS_PERCENT, (progress_override & PROGRESS_MASK)) - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA ?: TERN(HAS_PRINT_PROGRESS_PERMYRIAD, card.permyriadDone(), card.percentDone()) #endif ); @@ -1770,7 +1761,7 @@ void MarlinUI::init() { #endif // HAS_PRINT_PROGRESS -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #if ENABLED(EXTENSIBLE_UI) #include "extui/ui_api.h" @@ -1823,7 +1814,7 @@ void MarlinUI::init() { #endif } -#endif // SDSUPPORT +#endif // HAS_MEDIA #if HAS_MARLINUI_MENU void MarlinUI::reset_settings() { @@ -1834,7 +1825,7 @@ void MarlinUI::init() { #endif } - #if EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + #if ANY(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) void MarlinUI::zoffset_overlay(const_float_t zvalue) { // Determine whether the user is raising or lowering the nozzle. static int8_t dir; @@ -1849,7 +1840,7 @@ void MarlinUI::init() { #endif -#if BOTH(EXTENSIBLE_UI, ADVANCED_PAUSE_FEATURE) +#if ALL(EXTENSIBLE_UI, ADVANCED_PAUSE_FEATURE) void MarlinUI::pause_show_message( const PauseMessage message, diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index e33eda05911c..3d58c7f9c77c 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -88,7 +88,7 @@ typedef bool (*statusResetFunc_t)(); #endif // HAS_WIRED_LCD -#if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) +#if ANY(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) #define LCD_WITH_BLINK 1 #define LCD_UPDATE_INTERVAL TERN(HAS_TOUCH_BUTTONS, 50, 100) #endif @@ -246,13 +246,13 @@ class MarlinUI { // LCD implementations static void clear_lcd(); - #if BOTH(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) + #if ALL(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) static void check_touch_calibration() { if (touch_calibration.need_calibration()) currentScreen = touch_calibration_screen; } #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA #define MEDIA_MENU_GATEWAY TERN(PASSWORD_ON_SD_PRINT_MENU, password.media_gatekeeper, menu_media) static void media_changed(const uint8_t old_stat, const uint8_t stat); #endif @@ -297,23 +297,24 @@ class MarlinUI { } #endif + #if HAS_PRINT_PROGRESS_PERMYRIAD + typedef uint16_t progress_t; + #define PROGRESS_SCALE 100U + #define PROGRESS_MASK 0x7FFF + #else + typedef uint8_t progress_t; + #define PROGRESS_SCALE 1U + #define PROGRESS_MASK 0x7F + #endif + #if HAS_PRINT_PROGRESS - #if HAS_PRINT_PROGRESS_PERMYRIAD - typedef uint16_t progress_t; - #define PROGRESS_SCALE 100U - #define PROGRESS_MASK 0x7FFF - #else - typedef uint8_t progress_t; - #define PROGRESS_SCALE 1U - #define PROGRESS_MASK 0x7F - #endif #if ENABLED(SET_PROGRESS_PERCENT) static progress_t progress_override; static void set_progress(const progress_t p) { progress_override = _MIN(p, 100U * (PROGRESS_SCALE)); } static void set_progress_done() { progress_override = (PROGRESS_MASK + 1U) + 100U * (PROGRESS_SCALE); } static void progress_reset() { if (progress_override & (PROGRESS_MASK + 1U)) set_progress(0); } #endif - #if EITHER(SHOW_REMAINING_TIME, SET_PROGRESS_MANUALLY) + #if ANY(SHOW_REMAINING_TIME, SET_PROGRESS_MANUALLY) static uint32_t _calculated_remaining_time() { const duration_t elapsed = print_job_timer.duration(); const progress_t progress = _get_progress(); @@ -359,7 +360,7 @@ class MarlinUI { #if HAS_STATUS_MESSAGE - #if EITHER(HAS_WIRED_LCD, DWIN_LCD_PROUI) + #if ANY(HAS_WIRED_LCD, DWIN_LCD_PROUI) #if ENABLED(STATUS_MESSAGE_SCROLLING) #define MAX_MESSAGE_LENGTH _MAX(LONG_FILENAME_LENGTH, MAX_LANG_CHARSIZE * 2 * (LCD_WIDTH)) #else @@ -410,7 +411,7 @@ class MarlinUI { static void resume_print(); static void flow_fault(); - #if BOTH(HAS_MARLINUI_MENU, PSU_CONTROL) + #if ALL(HAS_MARLINUI_MENU, PSU_CONTROL) static void poweroff(); #endif @@ -469,7 +470,7 @@ class MarlinUI { FORCE_INLINE static void refresh_contrast() { set_contrast(contrast); } #endif - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #if ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) static millis_t next_filament_display; static void pause_filament_display(const millis_t ms=millis()) { next_filament_display = ms + 5000UL; } #endif @@ -508,7 +509,7 @@ class MarlinUI { static bool did_first_redraw; #endif - #if EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + #if ANY(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) static void zoffset_overlay(const int8_t dir); static void zoffset_overlay(const_float_t zvalue); #endif @@ -531,8 +532,8 @@ class MarlinUI { static void completion_feedback(const bool=true) {} #endif - #if ENABLED(SDSUPPORT) - #if BOTH(SCROLL_LONG_FILENAMES, HAS_MARLINUI_MENU) + #if HAS_MEDIA + #if ALL(SCROLL_LONG_FILENAMES, HAS_MARLINUI_MENU) #define MARLINUI_SCROLL_NAME 1 #endif #if MARLINUI_SCROLL_NAME @@ -561,7 +562,7 @@ class MarlinUI { #if HAS_TOUCH_BUTTONS static uint8_t touch_buttons; - static uint8_t repeat_delay; + static uint16_t repeat_delay; #else static constexpr uint8_t touch_buttons = 0; #endif @@ -630,7 +631,7 @@ class MarlinUI { static float ubl_mesh_value(); #endif - static void draw_select_screen_prompt(FSTR_P const pref, const char * const string=nullptr, FSTR_P const suff=nullptr); + static void draw_select_screen_prompt(FSTR_P const fpre, const char * const string=nullptr, FSTR_P const fsuf=nullptr); #else @@ -644,7 +645,7 @@ class MarlinUI { #endif - #if EITHER(HAS_MARLINUI_MENU, EXTENSIBLE_UI) + #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI) static bool lcd_clicked; static bool use_click() { const bool click = lcd_clicked; @@ -682,7 +683,7 @@ class MarlinUI { // // Special handling if a move is underway // - #if ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION, PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) || (ENABLED(LCD_BED_LEVELING) && EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)) + #if ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION, PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) || (ENABLED(LCD_BED_LEVELING) && ANY(PROBE_MANUALLY, MESH_BED_LEVELING)) #define LCD_HAS_WAIT_FOR_MOVE 1 static bool wait_for_move; #else @@ -692,7 +693,7 @@ class MarlinUI { // // Block interaction while under external control // - #if HAS_MARLINUI_MENU && EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) + #if HAS_MARLINUI_MENU && ANY(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) static bool external_control; FORCE_INLINE static void capture() { external_control = true; } FORCE_INLINE static void release() { external_control = false; } @@ -725,7 +726,7 @@ class MarlinUI { * printer unusable in practice. */ static bool hw_button_pressed() { - LOOP_L_N(s, ENCODER_SAMPLES) { + for (uint8_t s = 0; s < ENCODER_SAMPLES; ++s) { if (!BUTTON_CLICK()) return false; safe_delay(1); } @@ -735,7 +736,7 @@ class MarlinUI { static bool hw_button_pressed() { return BUTTON_CLICK(); } #endif - #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) + #if ANY(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) static void wait_for_release(); #endif @@ -743,14 +744,14 @@ class MarlinUI { #define ENCODERBASE (TERN(REVERSE_ENCODER_DIRECTION, -1, +1)) - #if EITHER(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) + #if ANY(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) static int8_t encoderDirection; #else static constexpr int8_t encoderDirection = ENCODERBASE; #endif FORCE_INLINE static void encoder_direction_normal() { - #if EITHER(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) + #if ANY(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) encoderDirection = ENCODERBASE; #endif } diff --git a/Marlin/src/lcd/menu/game/brickout.cpp b/Marlin/src/lcd/menu/game/brickout.cpp index fc4d19b1d98d..078cbbcceee2 100644 --- a/Marlin/src/lcd/menu/game/brickout.cpp +++ b/Marlin/src/lcd/menu/game/brickout.cpp @@ -44,7 +44,7 @@ brickout_data_t &bdat = marlin_game_data.brickout; inline void reset_bricks(const uint16_t v) { bdat.brick_count = (BRICK_COLS) * (BRICK_ROWS); - LOOP_L_N(i, BRICK_ROWS) bdat.bricks[i] = v; + for (uint8_t i = 0; i < BRICK_ROWS; ++i) bdat.bricks[i] = v; } void reset_ball() { @@ -138,13 +138,13 @@ void BrickoutGame::game_screen() { // Draw bricks if (PAGE_CONTAINS(BRICK_TOP, BRICK_BOT)) { - LOOP_L_N(y, BRICK_ROWS) { + for (uint8_t y = 0; y < BRICK_ROWS; ++y) { const uint8_t yy = y * BRICK_H + BRICK_TOP; if (PAGE_CONTAINS(yy, yy + BRICK_H - 1)) { - LOOP_L_N(x, BRICK_COLS) { + for (uint8_t x = 0; x < BRICK_COLS; ++x) { if (TEST(bdat.bricks[y], x)) { const uint8_t xx = x * BRICK_W; - LOOP_L_N(v, BRICK_H - 1) + for (uint8_t v = 0; v < BRICK_H - 1; ++v) if (PAGE_CONTAINS(yy + v, yy + v)) u8g.drawHLine(xx, yy + v, BRICK_W - 1); } diff --git a/Marlin/src/lcd/menu/game/invaders.cpp b/Marlin/src/lcd/menu/game/invaders.cpp index 56e4c224dd14..588523854f94 100644 --- a/Marlin/src/lcd/menu/game/invaders.cpp +++ b/Marlin/src/lcd/menu/game/invaders.cpp @@ -166,34 +166,33 @@ inline void update_invader_data() { uint8_t inv_mask = 0; // Get a list of all active invaders uint8_t sc = 0; - LOOP_L_N(y, INVADER_ROWS) { + for (uint8_t y = 0; y < INVADER_ROWS; ++y) { uint8_t m = idat.bugs[y]; if (m) idat.botmost = y + 1; inv_mask |= m; - LOOP_L_N(x, INVADER_COLS) + for (uint8_t x = 0; x < INVADER_COLS; ++x) if (TEST(m, x)) idat.shooters[sc++] = (y << 4) | x; } idat.leftmost = 0; - LOOP_L_N(i, INVADER_COLS) { if (TEST(inv_mask, i)) break; idat.leftmost -= INVADER_COL_W; } + for (uint8_t i = 0; i < INVADER_COLS; ++i) { if (TEST(inv_mask, i)) break; idat.leftmost -= INVADER_COL_W; } idat.rightmost = LCD_PIXEL_WIDTH - (INVADERS_WIDE); for (uint8_t i = INVADER_COLS; i--;) { if (TEST(inv_mask, i)) break; idat.rightmost += INVADER_COL_W; } if (idat.count == 2) idat.dir = idat.dir > 0 ? INVADER_VEL + 1 : -(INVADER_VEL + 1); } inline void reset_bullets() { - LOOP_L_N(i, COUNT(idat.bullet)) idat.bullet[i].v = 0; + for (uint8_t i = 0; i < COUNT(idat.bullet); ++i) idat.bullet[i].v = 0; } inline void reset_invaders() { idat.pos.x = 0; idat.pos.y = INVADER_TOP; idat.dir = INVADER_VEL; idat.count = (INVADER_COLS) * (INVADER_ROWS); - LOOP_L_N(i, INVADER_ROWS) idat.bugs[i] = _BV(INVADER_COLS) - 1; + for (uint8_t i = 0; i < INVADER_ROWS; ++i) idat.bugs[i] = _BV(INVADER_COLS) - 1; update_invader_data(); reset_bullets(); } - inline void spawn_ufo() { idat.ufov = random(0, 2) ? 1 : -1; idat.ufox = idat.ufov > 0 ? -(UFO_W) : LCD_PIXEL_WIDTH - 1; @@ -274,7 +273,7 @@ void InvadersGame::game_screen() { // Find a free bullet laser_t *b = nullptr; - LOOP_L_N(i, COUNT(idat.bullet)) if (!idat.bullet[i].v) { b = &idat.bullet[i]; break; } + for (uint8_t i = 0; i < COUNT(idat.bullet); ++i) if (!idat.bullet[i].v) { b = &idat.bullet[i]; break; } if (b) { // Pick a random shooter and update the bullet //SERIAL_ECHOLNPGM("free bullet found"); @@ -322,7 +321,7 @@ void InvadersGame::game_screen() { } // laser in invader zone // Handle alien bullets - LOOP_L_N(s, COUNT(idat.bullet)) { + for (uint8_t s = 0; s < COUNT(idat.bullet); ++s) { laser_t *b = &idat.bullet[s]; if (b->v) { // Update alien bullet position @@ -371,11 +370,11 @@ void InvadersGame::game_screen() { // Draw invaders if (PAGE_CONTAINS(idat.pos.y, idat.pos.y + idat.botmost * (INVADER_ROW_H) - 2 - 1)) { int8_t yy = idat.pos.y; - LOOP_L_N(y, INVADER_ROWS) { + for (uint8_t y = 0; y < INVADER_ROWS; ++y) { const uint8_t type = inv_type[y]; if (PAGE_CONTAINS(yy, yy + INVADER_H - 1)) { int8_t xx = idat.pos.x; - LOOP_L_N(x, INVADER_COLS) { + for (uint8_t x = 0; x < INVADER_COLS; ++x) { if (TEST(idat.bugs[y], x)) u8g.drawBitmapP(xx, yy, 2, INVADER_H, invader[type][idat.game_blink]); xx += INVADER_COL_W; @@ -398,7 +397,7 @@ void InvadersGame::game_screen() { u8g.drawVLine(idat.laser.x, idat.laser.y, LASER_H); // Draw invader bullets - LOOP_L_N (i, COUNT(idat.bullet)) { + for (uint8_t i = 0; i < COUNT(idat.bullet); ++i) { if (idat.bullet[i].v && PAGE_CONTAINS(idat.bullet[i].y - (SHOT_H - 1), idat.bullet[i].y)) u8g.drawVLine(idat.bullet[i].x, idat.bullet[i].y - (SHOT_H - 1), SHOT_H); } diff --git a/Marlin/src/lcd/menu/game/invaders.h b/Marlin/src/lcd/menu/game/invaders.h index c99e6c16ae76..a3ae6ffaedc2 100644 --- a/Marlin/src/lcd/menu/game/invaders.h +++ b/Marlin/src/lcd/menu/game/invaders.h @@ -53,8 +53,8 @@ typedef struct { uint8_t bugs[INVADER_ROWS], shooters[(INVADER_ROWS) * (INVADER_COLS)]; int8_t ufox, ufov; bool game_blink; - int8_t laser_col() { return ((laser.x - pos.x) / (INVADER_COL_W)); }; - int8_t laser_row() { return ((laser.y - pos.y + 2) / (INVADER_ROW_H)); }; + int8_t laser_col() { return ((laser.x - pos.x) / (INVADER_COL_W)); } + int8_t laser_row() { return ((laser.y - pos.y + 2) / (INVADER_ROW_H)); } } invaders_data_t; class InvadersGame : MarlinGame { public: static void enter_game(), game_screen(); }; diff --git a/Marlin/src/lcd/menu/game/maze.cpp b/Marlin/src/lcd/menu/game/maze.cpp index 85f752ee7de5..0c77f69e1ed4 100644 --- a/Marlin/src/lcd/menu/game/maze.cpp +++ b/Marlin/src/lcd/menu/game/maze.cpp @@ -83,7 +83,7 @@ void MazeGame::game_screen() { if (PAGE_UNDER(HEADER_H)) lcd_put_int(0, HEADER_H - 1, score); // Draw the maze - // LOOP_L_N(n, head_ind) { + // for (uint8_t n = 0; n < head_ind; ++n) { // const pos_t &p = maze_walls[n], &q = maze_walls[n + 1]; // if (p.x == q.x) { // const int8_t y1 = GAMEY(_MIN(p.y, q.y)), y2 = GAMEY(_MAX(p.y, q.y)); diff --git a/Marlin/src/lcd/menu/game/snake.cpp b/Marlin/src/lcd/menu/game/snake.cpp index c88893a6e6c7..2a78c089cfbe 100644 --- a/Marlin/src/lcd/menu/game/snake.cpp +++ b/Marlin/src/lcd/menu/game/snake.cpp @@ -84,14 +84,14 @@ void shorten_tail() { } if (shift) { sdat.head_ind--; - LOOP_LE_N(i, sdat.head_ind) + for (uint8_t i = 0; i <= sdat.head_ind; ++i) sdat.snake_tail[i] = sdat.snake_tail[i + 1]; } } // The food is on a line inline bool food_on_line() { - LOOP_L_N(n, sdat.head_ind) { + for (uint8_t n = 0; n < sdat.head_ind; ++n) { pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x == q.x) { if ((sdat.foodx == p.x - 1 || sdat.foodx == p.x) && WITHIN(sdat.foody, _MIN(p.y, q.y), _MAX(p.y, q.y))) @@ -151,7 +151,7 @@ bool snake_overlap() { // VERTICAL head segment? if (h1.x == h2.x) { // Loop from oldest to segment two away from head - LOOP_L_N(n, sdat.head_ind - 2) { + for (uint8_t n = 0; n < sdat.head_ind - 2; ++n) { // Segment p to q const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x != q.x) { @@ -163,7 +163,7 @@ bool snake_overlap() { } else { // Loop from oldest to segment two away from head - LOOP_L_N(n, sdat.head_ind - 2) { + for (uint8_t n = 0; n < sdat.head_ind - 2; ++n) { // Segment p to q const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.y != q.y) { @@ -240,7 +240,7 @@ void SnakeGame::game_screen() { #if SNAKE_WH < 2 // At this scale just draw a line - LOOP_L_N(n, sdat.head_ind) { + for (uint8_t n = 0; n < sdat.head_ind; ++n) { const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x == q.x) { const int8_t y1 = GAMEY(_MIN(p.y, q.y)), y2 = GAMEY(_MAX(p.y, q.y)); @@ -256,7 +256,7 @@ void SnakeGame::game_screen() { #elif SNAKE_WH == 2 // At this scale draw two lines - LOOP_L_N(n, sdat.head_ind) { + for (uint8_t n = 0; n < sdat.head_ind; ++n) { const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x == q.x) { const int8_t y1 = GAMEY(_MIN(p.y, q.y)), y2 = GAMEY(_MAX(p.y, q.y)); @@ -275,7 +275,7 @@ void SnakeGame::game_screen() { #else // Draw a series of boxes - LOOP_L_N(n, sdat.head_ind) { + for (uint8_t n = 0; n < sdat.head_ind; ++n) { const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x == q.x) { const int8_t y1 = _MIN(p.y, q.y), y2 = _MAX(p.y, q.y); diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 21546b0c8b8c..80fba484f48e 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -48,7 +48,7 @@ //////////////////////////////////////////// #if HAS_LEVELING && ANY(LCD_BED_TRAMMING, PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) - bool leveling_was_active; // = false + bool menu_leveling_was_active; // = false #endif #if ANY(PROBE_MANUALLY, MESH_BED_LEVELING, X_AXIS_TWIST_COMPENSATION) uint8_t manual_probe_index; // = 0 @@ -138,7 +138,7 @@ void MenuEditItemBase::goto_edit_screen( void * const ev, // Edit value pointer const int32_t minv, // Encoder minimum const int32_t maxv, // Encoder maximum - const uint16_t ep, // Initial encoder value + const uint32_t ep, // Initial encoder value const screenFunc_t cs, // MenuItem_type::draw_edit_screen => MenuEditItemBase::edit() const screenFunc_t cb, // Callback after edit const bool le // Flag to call cb() during editing @@ -176,7 +176,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co TERN_(SET_PROGRESS_PERCENT, progress_reset()); - #if BOTH(DOUBLECLICK_FOR_Z_BABYSTEPPING, BABYSTEPPING) + #if ALL(DOUBLECLICK_FOR_Z_BABYSTEPPING, BABYSTEPPING) static millis_t doubleclick_expire_ms = 0; // Going to menu_main from status screen? Remember first click time. // Going back to status screen within a very short time? Go to Z babystepping. @@ -352,13 +352,13 @@ bool MarlinUI::update_selection() { void MenuItem_confirm::select_screen( FSTR_P const yes, FSTR_P const no, selectFunc_t yesFunc, selectFunc_t noFunc, - FSTR_P const pref, const char * const string/*=nullptr*/, FSTR_P const suff/*=nullptr*/ + FSTR_P const fpre, const char * const string/*=nullptr*/, FSTR_P const fsuf/*=nullptr*/ ) { ui.defer_status_screen(); const bool ui_selection = !yes ? false : !no || ui.update_selection(), got_click = ui.use_click(); if (got_click || ui.should_draw()) { - draw_select_screen(yes, no, ui_selection, pref, string, suff); + draw_select_screen(yes, no, ui_selection, fpre, string, fsuf); if (got_click) { selectFunc_t callFunc = ui_selection ? yesFunc : noFunc; if (callFunc) callFunc(); else ui.goto_previous_screen(); diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index befffe5f72d2..7654d60aa207 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -64,25 +64,25 @@ class MenuItemBase { // Implementation-specific: // Draw an item either selected (pre_char) or not (space) with post_char // Menus may set up itemIndex, itemStringC/F and pass them to string-building or string-emitting functions - static void _draw(const bool sel, const uint8_t row, FSTR_P const fstr, const char pre_char, const char post_char); + static void _draw(const bool sel, const uint8_t row, FSTR_P const ftpl, const char pre_char, const char post_char); // Draw an item either selected ('>') or not (space) with post_char - FORCE_INLINE static void _draw(const bool sel, const uint8_t row, FSTR_P const fstr, const char post_char) { - _draw(sel, row, fstr, '>', post_char); + FORCE_INLINE static void _draw(const bool sel, const uint8_t row, FSTR_P const ftpl, const char post_char) { + _draw(sel, row, ftpl, '>', post_char); } }; // STATIC_ITEM(LABEL,...) class MenuItem_static : public MenuItemBase { public: - static void draw(const uint8_t row, FSTR_P const fstr, const uint8_t style=SS_DEFAULT, const char * const vstr=nullptr); + static void draw(const uint8_t row, FSTR_P const ftpl, const uint8_t style=SS_DEFAULT, const char * const vstr=nullptr); }; // BACK_ITEM(LABEL) class MenuItem_back : public MenuItemBase { public: - FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const fstr) { - _draw(sel, row, fstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0]); + FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const ftpl) { + _draw(sel, row, ftpl, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0]); } // Back Item action goes back one step in history FORCE_INLINE static void action(FSTR_P const=nullptr) { ui.go_back(); } @@ -101,31 +101,31 @@ class MenuItem_confirm : public MenuItemBase { FSTR_P const yes, // Right option label FSTR_P const no, // Left option label const bool yesno, // Is "yes" selected? - FSTR_P const pref, // Prompt prefix + FSTR_P const fpre, // Prompt prefix const char * const string, // Prompt runtime string - FSTR_P const suff // Prompt suffix + FSTR_P const fsuf // Prompt suffix ); static void select_screen( FSTR_P const yes, FSTR_P const no, selectFunc_t yesFunc, selectFunc_t noFunc, - FSTR_P const pref, const char * const string=nullptr, FSTR_P const suff=nullptr + FSTR_P const fpre, const char * const string=nullptr, FSTR_P const fsuf=nullptr ); static void select_screen( FSTR_P const yes, FSTR_P const no, selectFunc_t yesFunc, selectFunc_t noFunc, - FSTR_P const pref, FSTR_P const fstr, FSTR_P const suff=nullptr + FSTR_P const fpre, FSTR_P const fstr, FSTR_P const fsuf=nullptr ) { #ifdef __AVR__ char str[strlen_P(FTOP(fstr)) + 1]; strcpy_P(str, FTOP(fstr)); - select_screen(yes, no, yesFunc, noFunc, pref, str, suff); + select_screen(yes, no, yesFunc, noFunc, fpre, str, fsuf); #else - select_screen(yes, no, yesFunc, noFunc, pref, FTOP(fstr), suff); + select_screen(yes, no, yesFunc, noFunc, fpre, FTOP(fstr), fsuf); #endif } // Shortcut for prompt with "NO"/ "YES" labels - FORCE_INLINE static void confirm_screen(selectFunc_t yesFunc, selectFunc_t noFunc, FSTR_P const pref, const char * const string=nullptr, FSTR_P const suff=nullptr) { - select_screen(GET_TEXT_F(MSG_YES), GET_TEXT_F(MSG_NO), yesFunc, noFunc, pref, string, suff); + FORCE_INLINE static void confirm_screen(selectFunc_t yesFunc, selectFunc_t noFunc, FSTR_P const fpre, const char * const string=nullptr, FSTR_P const fsuf=nullptr) { + select_screen(GET_TEXT_F(MSG_YES), GET_TEXT_F(MSG_NO), yesFunc, noFunc, fpre, string, fsuf); } }; @@ -145,6 +145,7 @@ typedef union { uint32_t uint32; celsius_t celsius; } chimera_t; + extern chimera_t editable; // Base class for Menu Edit Items @@ -167,7 +168,7 @@ class MenuEditItemBase : public MenuItemBase { void * const ev, // Edit value pointer const int32_t minv, // Encoder minimum const int32_t maxv, // Encoder maximum - const uint16_t ep, // Initial encoder value + const uint32_t ep, // Initial encoder value const screenFunc_t cs, // MenuItem_type::draw_edit_screen => MenuEditItemBase::edit() const screenFunc_t cb, // Callback after edit const bool le // Flag to call cb() during editing @@ -190,7 +191,7 @@ class MenuEditItemBase : public MenuItemBase { static void draw_edit_screen(const char * const value) { draw_edit_screen(editLabel, value); } }; -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA class CardReader; class MenuItem_sdbase { public: @@ -206,7 +207,7 @@ class MenuEditItemBase : public MenuItemBase { void menu_main(); void menu_move(); -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA void menu_media(); #endif @@ -264,7 +265,7 @@ 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(LCD_BED_TRAMMING, PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) - extern bool leveling_was_active; + extern bool menu_leveling_was_active; #endif #if ANY(PROBE_MANUALLY, MESH_BED_LEVELING, X_AXIS_TWIST_COMPENSATION) diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index f56b4f899731..a37a6d4659d1 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -268,7 +268,7 @@ void menu_backlash(); } #endif -#if BOTH(AUTOTEMP, HAS_TEMP_HOTEND) || ANY(PID_AUTOTUNE_MENU, PID_EDIT_MENU, MPC_AUTOTUNE_MENU, MPC_EDIT_MENU) +#if ALL(AUTOTEMP, HAS_TEMP_HOTEND) || ANY(PID_AUTOTUNE_MENU, PID_EDIT_MENU, MPC_AUTOTUNE_MENU, MPC_EDIT_MENU) #define SHOW_MENU_ADVANCED_TEMPERATURE 1 #endif @@ -279,7 +279,7 @@ void menu_backlash(); #if ENABLED(MPC_EDIT_MENU) #define MPC_EDIT_DEFS(N) \ - MPC_t &c = thermalManager.temp_hotend[N].constants; \ + MPC_t &c = thermalManager.temp_hotend[N].mpc; \ TERN_(MPC_INCLUDE_FAN, editable.decimal = c.ambient_xfer_coeff_fan0 + c.fan255_adjustment) #endif @@ -294,7 +294,7 @@ void menu_backlash(); // // Autotemp, Min, Max, Fact // - #if BOTH(AUTOTEMP, HAS_TEMP_HOTEND) + #if ALL(AUTOTEMP, HAS_TEMP_HOTEND) EDIT_ITEM(bool, MSG_AUTOTEMP, &planner.autotemp_enabled); EDIT_ITEM(int3, MSG_MIN, &planner.autotemp_min, 0, thermalManager.hotend_max_target(0)); EDIT_ITEM(int3, MSG_MAX, &planner.autotemp_max, 0, thermalManager.hotend_max_target(0)); @@ -310,7 +310,7 @@ void menu_backlash(); // PID-P E5, PID-I E5, PID-D E5, PID-C E5, PID Autotune E5 // - #if BOTH(PIDTEMP, PID_EDIT_MENU) + #if ALL(PIDTEMP, PID_EDIT_MENU) #define __PID_HOTEND_MENU_ITEMS(N) \ raw_Kp = thermalManager.temp_hotend[N].pid.p(); \ raw_Ki = thermalManager.temp_hotend[N].pid.i(); \ @@ -343,7 +343,7 @@ void menu_backlash(); #endif - #if ENABLED(PID_EDIT_MENU) && EITHER(PIDTEMPBED, PIDTEMPCHAMBER) + #if ENABLED(PID_EDIT_MENU) && ANY(PIDTEMPBED, PIDTEMPCHAMBER) #define _PID_EDIT_ITEMS_TMPL(N,T) \ raw_Kp = T.pid.p(); \ raw_Ki = T.pid.i(); \ @@ -380,7 +380,7 @@ void menu_backlash(); #define MPC_EDIT_ITEMS(N) \ _MPC_EDIT_ITEMS(N); \ EDIT_ITEM_FAST_N(float43, N, MSG_MPC_AMBIENT_XFER_COEFF_FAN_E, &editable.decimal, 0, 1, []{ \ - MPC_t &c = thermalManager.temp_hotend[MenuItemBase::itemIndex].constants; \ + MPC_t &c = thermalManager.temp_hotend[MenuItemBase::itemIndex].mpc; \ c.fan255_adjustment = editable.decimal - c.ambient_xfer_coeff_fan0; \ }) #else @@ -461,7 +461,7 @@ void menu_backlash(); EDIT_ITEM_FAST_N(float5, E_AXIS, MSG_VMAX_N, &planner.settings.max_feedrate_mm_s[E_AXIS_N(active_extruder)], 1, max_fr_edit_scaled.e); #endif #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(n, E_STEPPERS) + for (uint8_t n = 0; n < E_STEPPERS; ++n) EDIT_ITEM_FAST_N(float5, n, MSG_VMAX_EN, &planner.settings.max_feedrate_mm_s[E_AXIS_N(n)], 1, max_fr_edit_scaled.e); #endif @@ -476,9 +476,23 @@ void menu_backlash(); // M201 / M204 Accelerations void menu_advanced_acceleration() { - float max_accel = planner.settings.max_acceleration_mm_per_s2[A_AXIS]; - TERN_(HAS_Y_AXIS, NOLESS(max_accel, planner.settings.max_acceleration_mm_per_s2[B_AXIS])); - TERN_(HAS_Z_AXIS, NOLESS(max_accel, planner.settings.max_acceleration_mm_per_s2[C_AXIS])); + float max_accel = ( + #if NUM_AXES + _MAX(NUM_AXIS_LIST( + planner.settings.max_acceleration_mm_per_s2[A_AXIS], + planner.settings.max_acceleration_mm_per_s2[B_AXIS], + planner.settings.max_acceleration_mm_per_s2[C_AXIS], + planner.settings.max_acceleration_mm_per_s2[I_AXIS], + planner.settings.max_acceleration_mm_per_s2[J_AXIS], + planner.settings.max_acceleration_mm_per_s2[K_AXIS], + planner.settings.max_acceleration_mm_per_s2[U_AXIS], + planner.settings.max_acceleration_mm_per_s2[V_AXIS], + planner.settings.max_acceleration_mm_per_s2[W_AXIS] + )) + #else + 0 + #endif + ); // M201 settings constexpr xyze_ulong_t max_accel_edit = @@ -519,7 +533,7 @@ void menu_backlash(); #if ENABLED(DISTINCT_E_FACTORS) EDIT_ITEM_FAST(long5_25, MSG_AMAX_E, &planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)], 100, max_accel_edit_scaled.e, []{ planner.refresh_acceleration_rates(); }); - LOOP_L_N(n, E_STEPPERS) + for (uint8_t n = 0; n < E_STEPPERS; ++n) EDIT_ITEM_FAST_N(long5_25, n, MSG_AMAX_EN, &planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(n)], 100, max_accel_edit_scaled.e, []{ if (MenuItemBase::itemIndex == active_extruder) planner.refresh_acceleration_rates(); @@ -580,12 +594,6 @@ void menu_backlash(); START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); - #if HAS_JUNCTION_DEVIATION - EDIT_ITEM(float43, MSG_JUNCTION_DEVIATION, &planner.junction_deviation_mm, 0.001f, TERN(LIN_ADVANCE, 0.3f, 0.5f) - OPTARG(LIN_ADVANCE, planner.recalculate_max_e_jerk) - ); - #endif - constexpr xyze_float_t max_jerk_edit = #ifdef MAX_JERK_EDIT_VALUES MAX_JERK_EDIT_VALUES @@ -598,7 +606,7 @@ void menu_backlash(); ; LOOP_LOGICAL_AXES(a) { - if (a == C_AXIS || TERN0(HAS_EXTRUDERS, a == E_AXIS)) + if (TERN0(HAS_C_AXIS, a == C_AXIS) || TERN0(HAS_EXTRUDERS, a == E_AXIS)) EDIT_ITEM_FAST_N(float52sign, a, MSG_VN_JERK, &planner.max_jerk[a], 0.1f, max_jerk_edit[a]); else EDIT_ITEM_FAST_N(float3, a, MSG_VN_JERK, &planner.max_jerk[a], 1.0f, max_jerk_edit[a]); @@ -643,7 +651,7 @@ void menu_advanced_steps_per_mm() { EDIT_ITEM_FAST_N(float72, a, MSG_N_STEPS, &planner.settings.axis_steps_per_mm[a], 5, 9999, []{ planner.refresh_positioning(); }); #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(n, E_STEPPERS) + for (uint8_t n = 0; n < E_STEPPERS; ++n) EDIT_ITEM_FAST_N(float72, n, MSG_EN_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS_N(n)], 5, 9999, []{ const uint8_t e = MenuItemBase::itemIndex; if (e == active_extruder) diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index e71606fc12a9..a5f1f3746bf0 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, BACKLASH_GCODE) +#if ALL(HAS_MARLINUI_MENU, BACKLASH_GCODE) #include "menu_item.h" @@ -34,12 +34,12 @@ void menu_backlash() { START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); editable.uint8 = backlash.get_correction_uint8(); EDIT_ITEM_FAST(percent, MSG_BACKLASH_CORRECTION, &editable.uint8, backlash.all_off, backlash.all_on, []{ backlash.set_correction_uint8(editable.uint8); }); - #if DISABLED(CORE_BACKLASH) || EITHER(MARKFORGED_XY, MARKFORGED_YX) + #if DISABLED(CORE_BACKLASH) || ANY(MARKFORGED_XY, MARKFORGED_YX) #define _CAN_CALI AXIS_CAN_CALIBRATE #else #define _CAN_CALI(A) true @@ -50,7 +50,9 @@ void menu_backlash() { EDIT_ITEM_FAST_N(float43, _AXIS(N), MSG_BACKLASH_N, &editable.decimal, 0.0f, 9.9f, []{ backlash.set_distance_mm(_AXIS(N), editable.decimal); }); \ } while (0); - if (_CAN_CALI(A)) EDIT_BACKLASH_DISTANCE(A); + #if HAS_X_AXIS && _CAN_CALI(A) + EDIT_BACKLASH_DISTANCE(A); + #endif #if HAS_Y_AXIS && _CAN_CALI(B) EDIT_BACKLASH_DISTANCE(B); #endif diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index 9505a82dd77c..cf1997499dc6 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -43,7 +43,7 @@ #endif #endif -#if EITHER(PROBE_MANUALLY, MESH_BED_LEVELING) +#if ANY(PROBE_MANUALLY, MESH_BED_LEVELING) #include "../../module/motion.h" #include "../../gcode/queue.h" @@ -53,7 +53,7 @@ // // LCD probed points are from defaults - constexpr uint8_t total_probe_points = TERN(AUTO_BED_LEVELING_3POINT, 3, GRID_MAX_POINTS); + constexpr grid_count_t total_probe_points = TERN(AUTO_BED_LEVELING_3POINT, 3, GRID_MAX_POINTS); // // Bed leveling is done. Wait for G29 to complete. @@ -169,7 +169,7 @@ if (ui.should_draw()) { MenuItem_static::draw(1, GET_TEXT_F(MSG_LEVEL_BED_WAITING)); // Color UI needs a control to detect a touch - #if BOTH(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) + #if ALL(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) touch.add_control(CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT); #endif } @@ -249,7 +249,7 @@ void menu_bed_leveling() { #endif // Level Bed - #if EITHER(PROBE_MANUALLY, MESH_BED_LEVELING) + #if ANY(PROBE_MANUALLY, MESH_BED_LEVELING) // Manual leveling uses a guided procedure SUBMENU(MSG_LEVEL_BED, _lcd_level_bed_continue); #else @@ -293,7 +293,7 @@ void menu_bed_leveling() { #endif #if ENABLED(LCD_BED_TRAMMING) - SUBMENU(MSG_BED_TRAMMING, _lcd_level_bed_corners); + SUBMENU(MSG_BED_TRAMMING, _lcd_bed_tramming); #endif #if ENABLED(EEPROM_SETTINGS) diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_tramming.cpp similarity index 83% rename from Marlin/src/lcd/menu/menu_bed_corners.cpp rename to Marlin/src/lcd/menu/menu_bed_tramming.cpp index 0e0051e65d6c..c5d425bfcfab 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_tramming.cpp @@ -21,12 +21,12 @@ */ // -// Level Bed Corners menu +// Bed Tramming menu // #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, LCD_BED_TRAMMING) +#if ALL(HAS_MARLINUI_MENU, LCD_BED_TRAMMING) #include "menu_item.h" #include "../../module/motion.h" @@ -54,7 +54,7 @@ #endif float last_z; int good_points; - bool corner_probing_done, wait_for_probe; + bool tramming_done, wait_for_probe; #if HAS_MARLINUI_U8GLIB #include "../dogm/marlinui_DOGM.h" @@ -66,6 +66,11 @@ static_assert(BED_TRAMMING_Z_HOP >= 0, "BED_TRAMMING_Z_HOP must be >= 0. Please update your configuration."); +#define LF 1 +#define RF 2 +#define RB 3 +#define LB 4 + #ifndef BED_TRAMMING_LEVELING_ORDER #define BED_TRAMMING_LEVELING_ORDER { LF, RF, LB, RB } // Default //#define BED_TRAMMING_LEVELING_ORDER { LF, LB, RF } // 3 hard-coded points @@ -75,18 +80,14 @@ static_assert(BED_TRAMMING_Z_HOP >= 0, "BED_TRAMMING_Z_HOP must be >= 0. Please //#define BED_TRAMMING_LEVELING_ORDER { LB, RB } // 3-Point tramming - Front #endif -#define LF 1 -#define RF 2 -#define RB 3 -#define LB 4 constexpr int lco[] = BED_TRAMMING_LEVELING_ORDER; -constexpr bool level_corners_3_points = COUNT(lco) == 2; -static_assert(level_corners_3_points || COUNT(lco) == 4, "BED_TRAMMING_LEVELING_ORDER must have exactly 2 or 4 corners."); +constexpr bool tramming_3_points = COUNT(lco) == 2; +static_assert(tramming_3_points || COUNT(lco) == 4, "BED_TRAMMING_LEVELING_ORDER must have exactly 2 or 4 corners."); constexpr int lcodiff = ABS(lco[0] - lco[1]); static_assert(COUNT(lco) == 4 || lcodiff == 1 || lcodiff == 3, "The first two BED_TRAMMING_LEVELING_ORDER corners must be on the same edge."); -constexpr int nr_edge_points = level_corners_3_points ? 3 : 4; +constexpr int nr_edge_points = tramming_3_points ? 3 : 4; constexpr int available_points = nr_edge_points + ENABLED(BED_TRAMMING_INCLUDE_CENTER); constexpr int center_index = TERN(BED_TRAMMING_INCLUDE_CENTER, available_points - 1, -1); constexpr float inset_lfrb[4] = BED_TRAMMING_INSET_LFRB; @@ -98,9 +99,9 @@ static int8_t bed_corner; /** * Select next corner coordinates */ -static void _lcd_level_bed_corners_get_next_position() { +static void _lcd_bed_tramming_get_next_position() { - if (level_corners_3_points) { + if (tramming_3_points) { if (bed_corner >= available_points) bed_corner = 0; // Above max position -> move back to first corner switch (bed_corner) { case 0 ... 1: @@ -141,9 +142,9 @@ static void _lcd_level_bed_corners_get_next_position() { else { current_position = lf; // Left front switch (lco[bed_corner]) { - case RF: current_position.x = rb.x; break; // Right front - case RB: current_position = rb; break; // Right rear - case LB: current_position.y = rb.y; break; // Left rear + case RF: current_position.x = rb.x; break; // Right Front + case RB: current_position = rb; break; // Right Back + case LB: current_position.y = rb.y; break; // Left Back } } } @@ -198,7 +199,7 @@ static void _lcd_level_bed_corners_get_next_position() { if (!ui.should_draw()) return; MenuItem_confirm::select_screen( GET_TEXT_F(MSG_BUTTON_DONE), GET_TEXT_F(MSG_BUTTON_SKIP) - , []{ corner_probing_done = true; wait_for_probe = false; } + , []{ tramming_done = true; wait_for_probe = false; } , []{ wait_for_probe = false; } , GET_TEXT_F(MSG_BED_TRAMMING_RAISE) ); @@ -207,23 +208,25 @@ static void _lcd_level_bed_corners_get_next_position() { void _lcd_draw_level_prompt() { if (!ui.should_draw()) return; MenuItem_confirm::select_screen( - GET_TEXT_F(TERN(HAS_LEVELING, MSG_BUTTON_LEVEL, MSG_BUTTON_DONE)), - TERN(HAS_LEVELING, GET_TEXT_F(MSG_BUTTON_BACK), nullptr) + GET_TEXT_F(TERN(HAS_LEVELING, MSG_BUTTON_LEVEL, MSG_BUTTON_DONE)) + , TERN(HAS_LEVELING, GET_TEXT_F(MSG_BUTTON_BACK), nullptr) , []{ queue.inject(TERN(HAS_LEVELING, F("G29N"), FPSTR(G28_STR))); ui.return_to_status(); } , TERN(HAS_LEVELING, ui.goto_previous_screen_no_defer, []{}) , GET_TEXT_F(MSG_BED_TRAMMING_IN_RANGE) ); } - bool _lcd_level_bed_corners_probe(bool verify=false) { - if (verify) do_blocking_move_to_z(current_position.z + BED_TRAMMING_Z_HOP); // do clearance if needed + bool _lcd_bed_tramming_probe(bool verify=false) { + if (verify) line_to_z(BED_TRAMMING_Z_HOP); // do clearance if needed 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 - BED_TRAMMING_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, 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) > BED_TRAMMING_PROBE_TOLERANCE) { last_z = current_position.z; // Above tolerance. Set a new Z for subsequent corners. @@ -231,13 +234,13 @@ static void _lcd_level_bed_corners_get_next_position() { } return true; // probe triggered } - do_blocking_move_to_z(last_z); // go back to tolerance middle point before raise + line_to_z(last_z); // go back to tolerance middle point before raise return false; // probe not triggered } - bool _lcd_level_bed_corners_raise() { + bool _lcd_bed_tramming_raise() { bool probe_triggered = false; - corner_probing_done = false; + tramming_done = false; wait_for_probe = true; ui.goto_screen(_lcd_draw_raise); // show raise screen ui.set_selection(true); @@ -264,25 +267,25 @@ static void _lcd_level_bed_corners_get_next_position() { ui.refresh(LCDVIEW_REDRAW_NOW); _lcd_draw_probing(); // update screen with # of good points - do_blocking_move_to_z(current_position.z + BED_TRAMMING_Z_HOP + TERN0(BLTOUCH, bltouch.z_extra_clearance())); // clearance + line_to_z(current_position.z + BED_TRAMMING_Z_HOP + TERN0(BLTOUCH, bltouch.z_extra_clearance())); // clearance - _lcd_level_bed_corners_get_next_position(); // Select next corner coordinates + _lcd_bed_tramming_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, 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(BED_TRAMMING_VERIFY_RAISED) // Verify - while (!_lcd_level_bed_corners_probe(true)) { // Loop while corner verified - if (!_lcd_level_bed_corners_raise()) { // Prompt user to raise bed if needed - if (corner_probing_done) return; // Done was selected + if (!_lcd_bed_tramming_probe()) { // Probe down to tolerance + if (_lcd_bed_tramming_raise()) { // Prompt user to raise bed if needed + #if ENABLED(BED_TRAMMING_VERIFY_RAISED) // Verify + while (!_lcd_bed_tramming_probe(true)) { // Loop while corner verified + if (!_lcd_bed_tramming_raise()) { // Prompt user to raise bed if needed + if (tramming_done) return; // Done was selected break; // Skip was selected } } #endif } - else if (corner_probing_done) // Done was selected + else if (tramming_done) // Done was selected return; } @@ -293,9 +296,9 @@ static void _lcd_level_bed_corners_get_next_position() { #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 + BED_TRAMMING_Z_HOP); + // In HIGH SPEED MODE do stow and clearance at the very end bltouch.stow(); + do_z_clearance(BED_TRAMMING_Z_HOP); } #endif @@ -309,7 +312,7 @@ static void _lcd_level_bed_corners_get_next_position() { line_to_z(BED_TRAMMING_Z_HOP); // Select next corner coordinates - _lcd_level_bed_corners_get_next_position(); + _lcd_bed_tramming_get_next_position(); line_to_current_position(manual_feedrate_mm_s.x); line_to_z(BED_TRAMMING_HEIGHT); @@ -318,15 +321,19 @@ static void _lcd_level_bed_corners_get_next_position() { #endif // !BED_TRAMMING_USE_PROBE -static void _lcd_level_bed_corners_homing() { +void _lcd_bed_tramming_homing() { _lcd_draw_homing(); if (!all_axes_homed()) return; + #if ENABLED(BED_TRAMMING_USE_PROBE) + _lcd_test_corners(); - if (corner_probing_done) ui.goto_previous_screen_no_defer(); - TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); + if (tramming_done) ui.goto_previous_screen_no_defer(); + TERN_(HAS_LEVELING, set_bed_leveling_enabled(menu_leveling_was_active)); endstops.enable_z_probe(false); - #else + + #else // !BED_TRAMMING_USE_PROBE + bed_corner = 0; ui.goto_screen([]{ MenuItem_confirm::select_screen( @@ -334,7 +341,7 @@ static void _lcd_level_bed_corners_homing() { , _lcd_goto_next_corner , []{ line_to_z(BED_TRAMMING_Z_HOP); // Raise Z off the bed when done - TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); + TERN_(HAS_LEVELING, set_bed_leveling_enabled(menu_leveling_was_active)); ui.goto_previous_screen_no_defer(); } , GET_TEXT_F(TERN(BED_TRAMMING_INCLUDE_CENTER, MSG_LEVEL_BED_NEXT_POINT, MSG_NEXT_CORNER)) @@ -343,10 +350,11 @@ static void _lcd_level_bed_corners_homing() { }); ui.set_selection(true); _lcd_goto_next_corner(); - #endif + + #endif // !BED_TRAMMING_USE_PROBE } -void _lcd_level_bed_corners() { +void _lcd_bed_tramming() { ui.defer_status_screen(); if (!all_axes_trusted()) { set_all_unhomed(); @@ -355,11 +363,11 @@ void _lcd_level_bed_corners() { // Disable leveling so the planner won't mess with us #if HAS_LEVELING - leveling_was_active = planner.leveling_active; + menu_leveling_was_active = planner.leveling_active; set_bed_leveling_enabled(false); #endif - ui.goto_screen(_lcd_level_bed_corners_homing); + ui.goto_screen(_lcd_bed_tramming_homing); } #endif // HAS_MARLINUI_MENU && LCD_BED_TRAMMING diff --git a/Marlin/src/lcd/menu/menu_cancelobject.cpp b/Marlin/src/lcd/menu/menu_cancelobject.cpp index b2d36bf8c30d..bcbd90ee3a60 100644 --- a/Marlin/src/lcd/menu/menu_cancelobject.cpp +++ b/Marlin/src/lcd/menu/menu_cancelobject.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, CANCEL_OBJECTS) +#if ALL(HAS_MARLINUI_MENU, CANCEL_OBJECTS) #include "menu_item.h" #include "menu_addon.h" @@ -56,7 +56,7 @@ void menu_cancelobject() { const int8_t ao = cancelable.active_object; START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); // Draw cancelable items in a loop for (int8_t i = -1; i < cancelable.object_count; i++) { diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index e50cd69f6302..a743f3ed22c7 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -60,7 +60,7 @@ #define HAS_DEBUG_MENU ENABLED(LCD_PROGRESS_BAR_TEST) void menu_advanced_settings(); -#if EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) +#if ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) void menu_delta_calibrate(); #endif @@ -181,10 +181,10 @@ void menu_advanced_settings(); #if ENABLED(DUAL_X_CARRIAGE) EDIT_ITEM_FAST_N(float42_52, X_AXIS, MSG_HOTEND_OFFSET_A, &hotend_offset[1].x, float(X2_HOME_POS - 25), float(X2_HOME_POS + 25), _recalc_offsets); #else - EDIT_ITEM_FAST_N(float42_52, X_AXIS, MSG_HOTEND_OFFSET_A, &hotend_offset[1].x, -99.0, 99.0, _recalc_offsets); + EDIT_ITEM_FAST_N(float42_52, X_AXIS, MSG_HOTEND_OFFSET_A, &hotend_offset[1].x, -99.0f, 99.0f, _recalc_offsets); #endif - EDIT_ITEM_FAST_N(float42_52, Y_AXIS, MSG_HOTEND_OFFSET_A, &hotend_offset[1].y, -99.0, 99.0, _recalc_offsets); - EDIT_ITEM_FAST_N(float42_52, Z_AXIS, MSG_HOTEND_OFFSET_A, &hotend_offset[1].z, Z_PROBE_LOW_POINT, 10.0, _recalc_offsets); + EDIT_ITEM_FAST_N(float42_52, Y_AXIS, MSG_HOTEND_OFFSET_A, &hotend_offset[1].y, -99.0f, 99.0f, _recalc_offsets); + EDIT_ITEM_FAST_N(float42_52, Z_AXIS, MSG_HOTEND_OFFSET_A, &hotend_offset[1].z, -10.0f, 10.0f, _recalc_offsets); #if ENABLED(EEPROM_SETTINGS) ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); #endif @@ -360,7 +360,7 @@ void menu_advanced_settings(); void custom_menus_configuration() { START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); #define HAS_CUSTOM_ITEM_CONF(N) (defined(CONFIG_MENU_ITEM_##N##_DESC) && defined(CONFIG_MENU_ITEM_##N##_GCODE)) @@ -472,7 +472,7 @@ void menu_configuration() { const bool busy = printer_busy(); START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); // // Debug Menu when certain options are enabled @@ -507,7 +507,7 @@ void menu_configuration() { #endif if (!busy) { - #if EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) + #if ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) SUBMENU(MSG_DELTA_CALIBRATE, menu_delta_calibrate); #endif @@ -572,7 +572,7 @@ void menu_configuration() { // Preheat configurations #if HAS_PREHEAT && DISABLED(SLIM_LCD_MENUS) - LOOP_L_N(m, PREHEAT_COUNT) + for (uint8_t m = 0; m < PREHEAT_COUNT; ++m) SUBMENU_N_f(m, ui.get_preheat_label(m), MSG_PREHEAT_M_SETTINGS, _menu_configuration_preheat_settings); #endif diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index 04bb81569159..14a7c86c9c65 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_MARLINUI_MENU && EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) +#if HAS_MARLINUI_MENU && ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) #include "menu_item.h" #include "../../module/delta.h" @@ -132,7 +132,7 @@ void menu_delta_calibrate() { #endif START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); #if ENABLED(DELTA_AUTO_CALIBRATION) GCODES_ITEM(MSG_DELTA_AUTO_CALIBRATE, F("G33")); diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 122f0c405099..46ebf85ba4b8 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, ADVANCED_PAUSE_FEATURE) +#if ALL(HAS_MARLINUI_MENU, ADVANCED_PAUSE_FEATURE) #include "menu_item.h" #include "../../module/temperature.h" @@ -96,7 +96,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { if (LCD_HEIGHT >= 4) STATIC_ITEM_F(change_filament_header(mode), SS_DEFAULT|SS_INVERT); BACK_ITEM(MSG_BACK); #if HAS_PREHEAT - LOOP_L_N(m, PREHEAT_COUNT) + for (uint8_t m = 0; m < PREHEAT_COUNT; ++m) ACTION_ITEM_N_f(m, ui.get_preheat_label(m), MSG_PREHEAT_M, _change_filament_with_preset); #endif EDIT_ITEM_FAST_N(int3, extruder, MSG_PREHEAT_CUSTOM, &thermalManager.temp_hotend[extruder].target, @@ -130,7 +130,7 @@ void menu_change_filament() { #endif START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); // Change filament #if E_STEPPERS == 1 @@ -141,7 +141,7 @@ void menu_change_filament() { GCODES_ITEM_F(fmsg, F("M600 B0")); #else FSTR_P const fmsg = GET_TEXT_F(MSG_FILAMENTCHANGE_E); - LOOP_L_N(s, E_STEPPERS) { + for (uint8_t s = 0; s < E_STEPPERS; ++s) { if (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_F(s, fmsg, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, MenuItemBase::itemIndex); }); else { @@ -166,7 +166,7 @@ void menu_change_filament() { GCODES_ITEM_F(msg_load, F("M701")); #else FSTR_P const msg_load = GET_TEXT_F(MSG_FILAMENTLOAD_E); - LOOP_L_N(s, E_STEPPERS) { + for (uint8_t s = 0; s < E_STEPPERS; ++s) { if (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_F(s, msg_load, []{ _menu_temp_filament_op(PAUSE_MODE_LOAD_FILAMENT, MenuItemBase::itemIndex); }); else { @@ -194,7 +194,7 @@ void menu_change_filament() { GCODES_ITEM(MSG_FILAMENTUNLOAD_ALL, F("M702")); #endif FSTR_P const msg_unload = GET_TEXT_F(MSG_FILAMENTUNLOAD_E); - LOOP_L_N(s, E_STEPPERS) { + for (uint8_t s = 0; s < E_STEPPERS; ++s) { if (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_F(s, msg_unload, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, MenuItemBase::itemIndex); }); else { @@ -250,6 +250,12 @@ static FSTR_P pause_header() { }while(0) void menu_pause_option() { + #if HAS_FILAMENT_SENSOR + const bool still_out = runout.filament_ran_out; + #else + constexpr bool still_out = false; + #endif + START_MENU(); #if LCD_HEIGHT > 2 STATIC_ITEM(MSG_FILAMENT_CHANGE_OPTION_HEADER); @@ -257,11 +263,8 @@ void menu_pause_option() { ACTION_ITEM(MSG_FILAMENT_CHANGE_OPTION_PURGE, []{ pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; }); #if HAS_FILAMENT_SENSOR - const bool still_out = runout.filament_ran_out; if (still_out) EDIT_ITEM(bool, MSG_RUNOUT_SENSOR, &runout.enabled, runout.reset); - #else - constexpr bool still_out = false; #endif if (!still_out) diff --git a/Marlin/src/lcd/menu/menu_game.cpp b/Marlin/src/lcd/menu/menu_game.cpp index fa56d7eee266..750c3c7e8210 100644 --- a/Marlin/src/lcd/menu/menu_game.cpp +++ b/Marlin/src/lcd/menu/menu_game.cpp @@ -29,7 +29,7 @@ void menu_game() { START_MENU(); - BACK_ITEM(TERN(LCD_INFO_MENU, MSG_INFO_MENU, MSG_MAIN)); + BACK_ITEM(TERN(LCD_INFO_MENU, MSG_INFO_MENU, MSG_MAIN_MENU)); #if ENABLED(MARLIN_BRICKOUT) SUBMENU(MSG_BRICKOUT, brickout.enter_game); #endif diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index 101861074d95..bc0c15f3170b 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, LCD_INFO_MENU) +#if ALL(HAS_MARLINUI_MENU, LCD_INFO_MENU) #include "menu_item.h" @@ -276,7 +276,7 @@ void menu_info_board() { // void menu_info() { START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); #if ENABLED(LCD_PRINTER_INFO_IS_BOOTSCREEN) SUBMENU(MSG_INFO_PRINTER_MENU, TERN(SHOW_CUSTOM_BOOTSCREEN, menu_show_custom_bootscreen, menu_show_marlin_bootscreen)); #else diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index 2a6a568062b3..a98f87a3623c 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -242,6 +242,9 @@ class MenuItem_bool : public MenuEditItemBase { #define START_SCREEN() SCREEN_OR_MENU_LOOP(false) #define START_MENU() SCREEN_OR_MENU_LOOP(true) #define NEXT_ITEM() (++_thisItemNr) +#define MY_LINE() (_menuLineNr == _thisItemNr) +#define HIGHLIGHTED() (encoderLine == _thisItemNr) +#define CLICKED() (HIGHLIGHTED() && ui.use_click()) #define SKIP_ITEM() NEXT_ITEM() #define END_SCREEN() } screen_items = _thisItemNr #define END_MENU() END_SCREEN(); UNUSED(_skipStatic) @@ -274,19 +277,19 @@ class MenuItem_bool : public MenuEditItemBase { #define _MENU_INNER_F(TYPE, USE_MULTIPLIER, FLABEL, V...) do { \ FSTR_P const flabel = FLABEL; \ - if (encoderLine == _thisItemNr && ui.use_click()) { \ + if (CLICKED()) { \ _MENU_ITEM_MULTIPLIER_CHECK(USE_MULTIPLIER); \ MenuItem_##TYPE::action(flabel, ##V); \ if (ui.screen_changed) return; \ } \ if (ui.should_draw()) \ MenuItem_##TYPE::draw \ - (encoderLine == _thisItemNr, _lcdLineNr, flabel, ##V); \ + (HIGHLIGHTED(), _lcdLineNr, flabel, ##V); \ }while(0) // Item with optional data #define _MENU_ITEM_F(TYPE, V...) do { \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ _MENU_INNER_F(TYPE, ##V); \ } \ @@ -295,7 +298,7 @@ class MenuItem_bool : public MenuEditItemBase { // Item with index value, C-string, and optional data #define _MENU_ITEM_N_S_F(TYPE, N, S, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ MenuItemBase::init(N, S); \ _MENU_INNER_F(TYPE, ##V); \ @@ -305,7 +308,7 @@ class MenuItem_bool : public MenuEditItemBase { // Item with index value and F-string #define _MENU_ITEM_N_f_F(TYPE, N, f, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ MenuItemBase::init(N, f); \ _MENU_INNER_F(TYPE, ##V); \ @@ -315,7 +318,7 @@ class MenuItem_bool : public MenuEditItemBase { // Item with index value #define _MENU_ITEM_N_F(TYPE, N, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ MenuItemBase::init(N); \ _MENU_INNER_F(TYPE, ##V); \ @@ -325,7 +328,7 @@ class MenuItem_bool : public MenuEditItemBase { // Items with a unique string #define _MENU_ITEM_S_F(TYPE, S, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ MenuItemBase::init(0, S); \ _MENU_INNER_F(TYPE, ##V); \ @@ -335,7 +338,7 @@ class MenuItem_bool : public MenuEditItemBase { // Items with a unique F-string #define _MENU_ITEM_f_F(TYPE, f, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ MenuItemBase::init(0, f); \ _MENU_INNER_F(TYPE, ##V); \ @@ -356,32 +359,42 @@ class MenuItem_bool : public MenuEditItemBase { } while(0) #define STATIC_ITEM_F(FLABEL, V...) do{ \ - if (_menuLineNr == _thisItemNr) \ + if (MY_LINE()) \ STATIC_ITEM_INNER_F(FLABEL, ##V); \ NEXT_ITEM(); \ } while(0) #define STATIC_ITEM_N_F(N, FLABEL, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ MenuItemBase::init(N); \ STATIC_ITEM_INNER_F(FLABEL, ##V); \ } \ NEXT_ITEM(); \ }while(0) -// PSTRING_ITEM is like STATIC_ITEM but it takes -// two PSTRs with the style as the last parameter. +// PSTRING_ITEM is like STATIC_ITEM +// but also takes a PSTR and style. + +#define PSTRING_ITEM_F_P(FLABEL, PVAL, STYL) do{ \ + constexpr int m = 20; \ + char msg[m + 1]; \ + if (_menuLineNr == _thisItemNr) { \ + msg[0] = ':'; msg[1] = ' '; \ + strncpy_P(msg + 2, PVAL, m - 2); \ + if (msg[m - 1] & 0x80) msg[m - 1] = '\0'; \ + } \ + STATIC_ITEM_F(FLABEL, STYL, msg); \ +}while(0) -#define PSTRING_ITEM_F(FLABEL, PVAL, STYL) do{ \ - constexpr int m = 20; \ - char msg[m+1]; \ - msg[0] = ':'; msg[1] = ' '; \ - strncpy_P(msg+2, PSTR(PVAL), m-2); \ - if (msg[m-1] & 0x80) msg[m-1] = '\0'; \ - STATIC_ITEM_F(FLABEL, STYL, msg); \ +#define PSTRING_ITEM_N_F_P(N, V...) do{ \ + if (_menuLineNr == _thisItemNr) \ + MenuItemBase::init(N); \ + PSTRING_ITEM_F_P(V); \ }while(0) -#define PSTRING_ITEM(LABEL, V...) PSTRING_ITEM_F(GET_TEXT_F(LABEL), ##V) +#define PSTRING_ITEM_N_P(N, LABEL, V...) PSTRING_ITEM_N_F_P(N, GET_TEXT_F(LABEL), ##V) +#define PSTRING_ITEM_P(LABEL, V...) PSTRING_ITEM_F_P(GET_TEXT_F(LABEL), ##V) +#define PSTRING_ITEM(LABEL, S, V...) PSTRING_ITEM_P(LABEL, PSTR(S), ##V) #define STATIC_ITEM(LABEL, V...) STATIC_ITEM_F(GET_TEXT_F(LABEL), ##V) #define STATIC_ITEM_N(N, LABEL, V...) STATIC_ITEM_N_F(N, GET_TEXT_F(LABEL), ##V) @@ -490,18 +503,18 @@ class MenuItem_bool : public MenuEditItemBase { #define EDIT_ITEM_FAST_f(TYPE, f, LABEL, V...) EDIT_ITEM_FAST_f_F(TYPE, f, GET_TEXT_F(LABEL), ##V) #define _CONFIRM_ITEM_INNER_F(FLABEL, V...) do { \ - if (encoderLine == _thisItemNr && ui.use_click()) { \ + if (CLICKED()) { \ ui.push_current_screen(); \ ui.goto_screen([]{MenuItem_confirm::select_screen(V);}); \ return; \ } \ if (ui.should_draw()) MenuItem_confirm::draw \ - (encoderLine == _thisItemNr, _lcdLineNr, FLABEL, ##V); \ + (HIGHLIGHTED(), _lcdLineNr, FLABEL, ##V); \ }while(0) // Indexed items set a global index value and optional data #define _CONFIRM_ITEM_F(FLABEL, V...) do { \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ _CONFIRM_ITEM_INNER_F(FLABEL, ##V); \ } \ @@ -510,7 +523,7 @@ class MenuItem_bool : public MenuEditItemBase { // Indexed items set a global index value #define _CONFIRM_ITEM_N_S_F(N, S, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ MenuItemBase::init(N, S); \ _CONFIRM_ITEM_INNER_F(TYPE, ##V); \ @@ -538,7 +551,7 @@ class MenuItem_bool : public MenuEditItemBase { #define YESNO_ITEM_N(N,LABEL, V...) YESNO_ITEM_N_F(N, GET_TEXT_F(LABEL), ##V) #if ENABLED(LCD_BED_TRAMMING) - void _lcd_level_bed_corners(); + void _lcd_bed_tramming(); #endif #if HAS_FAN @@ -571,10 +584,10 @@ class MenuItem_bool : public MenuEditItemBase { }while(0) #if FAN_COUNT > 1 - #define FAN_EDIT_ITEMS(F) _FAN_EDIT_ITEMS(F,FAN_SPEED_N) + #define FAN_EDIT_ITEMS(F) _FAN_EDIT_ITEMS(F, FAN_SPEED_N) #endif - #define SNFAN(N) (ENABLED(SINGLENOZZLE_STANDBY_FAN) && !HAS_FAN##N && EXTRUDERS > N) + #define SNFAN(N) (ENABLED(SINGLENOZZLE_STANDBY_FAN) && !HAS_FAN##N && (N) < EXTRUDERS) #if SNFAN(1) || SNFAN(2) || SNFAN(3) || SNFAN(4) || SNFAN(5) || SNFAN(6) || SNFAN(7) #define DEFINE_SINGLENOZZLE_ITEM() \ diff --git a/Marlin/src/lcd/menu/menu_job_recovery.cpp b/Marlin/src/lcd/menu/menu_job_recovery.cpp index 6329c5839786..b2276aeb0cdd 100644 --- a/Marlin/src/lcd/menu/menu_job_recovery.cpp +++ b/Marlin/src/lcd/menu/menu_job_recovery.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, POWER_LOSS_RECOVERY) +#if ALL(HAS_MARLINUI_MENU, POWER_LOSS_RECOVERY) #include "menu_item.h" #include "../../gcode/queue.h" diff --git a/Marlin/src/lcd/menu/menu_language.cpp b/Marlin/src/lcd/menu/menu_language.cpp index 2ea4359c6bb7..c92b86095013 100644 --- a/Marlin/src/lcd/menu/menu_language.cpp +++ b/Marlin/src/lcd/menu/menu_language.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfig.h" -#if HAS_MULTI_LANGUAGE +#if HAS_MENU_MULTI_LANGUAGE #include "menu_item.h" #include "../../MarlinCore.h" @@ -39,7 +39,7 @@ static void set_lcd_language(const uint8_t inlang) { void menu_language() { START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); MENU_ITEM_F(function, FPSTR(GET_LANGUAGE_NAME(1)), []{ set_lcd_language(0); }); MENU_ITEM_F(function, FPSTR(GET_LANGUAGE_NAME(2)), []{ set_lcd_language(1); }); @@ -56,4 +56,4 @@ void menu_language() { END_MENU(); } -#endif // HAS_MULTI_LANGUAGE +#endif // HAS_MENU_MULTI_LANGUAGE diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index 867e4dafa940..c7390b98cb20 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_MARLINUI_MENU && EITHER(LED_CONTROL_MENU, CASE_LIGHT_MENU) +#if HAS_MARLINUI_MENU && ANY(LED_CONTROL_MENU, CASE_LIGHT_MENU) #include "menu_item.h" @@ -126,7 +126,7 @@ void menu_led() { START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); #if ENABLED(LED_CONTROL_MENU) if (TERN1(PSU_CONTROL, powerManager.psu_on)) { diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 81b36d2b01a9..c244438cd0bd 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -43,10 +43,10 @@ #include "game/game.h" #endif -#if EITHER(SDSUPPORT, HOST_PROMPT_SUPPORT) || defined(ACTION_ON_CANCEL) +#if ANY(HAS_MEDIA, HOST_PROMPT_SUPPORT) || defined(ACTION_ON_CANCEL) #define MACHINE_CAN_STOP 1 #endif -#if ANY(SDSUPPORT, HOST_PROMPT_SUPPORT, PARK_HEAD_ON_PAUSE) || defined(ACTION_ON_PAUSE) +#if ANY(HAS_MEDIA, HOST_PROMPT_SUPPORT, PARK_HEAD_ON_PAUSE) || defined(ACTION_ON_PAUSE) #define MACHINE_CAN_PAUSE 1 #endif @@ -88,7 +88,7 @@ void menu_configuration(); void menu_info(); #endif -#if EITHER(LED_CONTROL_MENU, CASE_LIGHT_MENU) +#if ANY(LED_CONTROL_MENU, CASE_LIGHT_MENU) void menu_led(); #endif @@ -114,7 +114,7 @@ void menu_configuration(); void custom_menus_main() { START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); #define HAS_CUSTOM_ITEM_MAIN(N) (defined(MAIN_MENU_ITEM_##N##_DESC) && defined(MAIN_MENU_ITEM_##N##_GCODE)) @@ -234,7 +234,7 @@ void menu_configuration(); void menu_main() { const bool busy = printingIsActive() - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA , card_detected = card.isMounted() , card_open = card_detected && card.isFileOpen() #endif @@ -243,7 +243,7 @@ void menu_main() { START_MENU(); BACK_ITEM(MSG_INFO_SCREEN); - #if ENABLED(SDSUPPORT) && !defined(MEDIA_MENU_AT_TOP) && !HAS_ENCODER_WHEEL + #if HAS_MEDIA && !defined(MEDIA_MENU_AT_TOP) && !HAS_ENCODER_WHEEL #define MEDIA_MENU_AT_TOP #endif @@ -273,7 +273,7 @@ void menu_main() { #endif } else { - #if BOTH(SDSUPPORT, MEDIA_MENU_AT_TOP) + #if ALL(HAS_MEDIA, MEDIA_MENU_AT_TOP) // BEGIN MEDIA MENU #if ENABLED(MENU_ADDAUTOSTART) ACTION_ITEM(MSG_RUN_AUTO_FILES, card.autofile_begin); // Run Auto Files @@ -292,7 +292,7 @@ void menu_main() { #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); + ui.refresh(LCDVIEW_CLEAR_CALL_REDRAW); #endif }); #endif @@ -303,9 +303,11 @@ void menu_main() { #if HAS_SD_DETECT ACTION_ITEM(MSG_NO_MEDIA, nullptr); // "No Media" #else - GCODES_ITEM(MSG_ATTACH_MEDIA, F("M21" TERN_(MULTI_VOLUME, "S"))); // M21 Attach Media #if ENABLED(MULTI_VOLUME) - GCODES_ITEM(MSG_ATTACH_USB_MEDIA, F("M21U")); // M21 Attach USB Media + GCODES_ITEM(MSG_ATTACH_SD_MEDIA, F("M21S")); // M21S Attach SD Card + GCODES_ITEM(MSG_ATTACH_USB_MEDIA, F("M21U")); // M21U Attach USB Media + #else + GCODES_ITEM(MSG_ATTACH_MEDIA, F("M21")); // M21 Attach Media #endif #endif } @@ -326,7 +328,7 @@ void menu_main() { SUBMENU(MSG_MOTION, menu_motion); } - #if BOTH(ADVANCED_PAUSE_FEATURE, DISABLE_ENCODER) + #if ENABLED(ADVANCED_PAUSE_FEATURE) && (!HAS_ENCODER_WHEEL || ENABLED(DISABLE_ENCODER)) FILAMENT_CHANGE_ITEM(); #endif @@ -366,7 +368,7 @@ void menu_main() { SUBMENU(MSG_INFO_MENU, menu_info); #endif - #if EITHER(LED_CONTROL_MENU, CASE_LIGHT_MENU) + #if ANY(LED_CONTROL_MENU, CASE_LIGHT_MENU) SUBMENU(MSG_LEDS, menu_led); #endif @@ -388,7 +390,7 @@ void menu_main() { GCODES_ITEM(MSG_SWITCH_PS_ON, F("M80")); #endif - #if ENABLED(SDSUPPORT) && DISABLED(MEDIA_MENU_AT_TOP) + #if HAS_MEDIA && DISABLED(MEDIA_MENU_AT_TOP) // BEGIN MEDIA MENU #if ENABLED(MENU_ADDAUTOSTART) ACTION_ITEM(MSG_RUN_AUTO_FILES, card.autofile_begin); // Run Auto Files @@ -407,7 +409,7 @@ void menu_main() { #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); + ui.refresh(LCDVIEW_CLEAR_CALL_REDRAW); #endif }); #endif @@ -418,10 +420,12 @@ void menu_main() { #if HAS_SD_DETECT ACTION_ITEM(MSG_NO_MEDIA, nullptr); // "No Media" #else - GCODES_ITEM(MSG_ATTACH_MEDIA, F("M21" TERN_(MULTI_VOLUME, "S"))); // M21 Attach Media - #if ENABLED(MULTI_VOLUME) - GCODES_ITEM(MSG_ATTACH_USB_MEDIA, F("M21U")); // M21 Attach USB Media - #endif + #if ENABLED(MULTI_VOLUME) + GCODES_ITEM(MSG_ATTACH_SD_MEDIA, F("M21S")); // M21S Attach SD Card + GCODES_ITEM(MSG_ATTACH_USB_MEDIA, F("M21U")); // M21U Attach USB Media + #else + GCODES_ITEM(MSG_ATTACH_MEDIA, F("M21")); // M21 Attach Media + #endif #endif } // END MEDIA MENU @@ -495,7 +499,7 @@ void menu_main() { }); #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) && DISABLED(DISABLE_ENCODER) + #if ENABLED(ADVANCED_PAUSE_FEATURE) && HAS_ENCODER_WHEEL && DISABLED(DISABLE_ENCODER) FILAMENT_CHANGE_ITEM(); #endif diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 20ef6e3d198f..daa396601f2d 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, SDSUPPORT) +#if ALL(HAS_MARLINUI_MENU, HAS_MEDIA) #include "menu_item.h" #include "../../sd/cardreader.h" @@ -73,14 +73,11 @@ class MenuItem_sdfile : public MenuItem_sdbase { #endif #if ENABLED(SD_MENU_CONFIRM_START) MenuItem_submenu::action(fstr, []{ - char * const longest = card.longest_filename(); - char buffer[strlen(longest) + 2]; - buffer[0] = ' '; - strcpy(buffer + 1, longest); + char * const filename = card.longest_filename(); MenuItem_confirm::select_screen( GET_TEXT_F(MSG_BUTTON_PRINT), GET_TEXT_F(MSG_BUTTON_CANCEL), sdcard_start_selected_file, nullptr, - GET_TEXT_F(MSG_START_PRINT), buffer, F("?") + GET_TEXT_F(MSG_START_PRINT), filename, F("?") ); }); #else @@ -109,17 +106,17 @@ void menu_media_filelist() { ui.encoder_direction_menus(); #if HAS_MARLINUI_U8GLIB - static uint16_t fileCnt; - if (ui.first_page) fileCnt = card.get_num_Files(); + static int16_t fileCnt; + if (ui.first_page) fileCnt = card.get_num_items(); #else - const uint16_t fileCnt = card.get_num_Files(); + const int16_t fileCnt = card.get_num_items(); #endif START_MENU(); #if ENABLED(MULTI_VOLUME) ACTION_ITEM(MSG_BACK, []{ ui.goto_screen(menu_media); }); #else - BACK_ITEM_F(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT_F(MSG_MAIN) : GET_TEXT_F(MSG_BACK)); + BACK_ITEM_F(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT_F(MSG_MAIN_MENU) : GET_TEXT_F(MSG_BACK)); #endif if (card.flag.workDirIsRoot) { #if !HAS_SD_DETECT @@ -129,16 +126,18 @@ void menu_media_filelist() { else if (card.isMounted()) ACTION_ITEM_F(F(LCD_STR_FOLDER " .."), lcd_sd_updir); - if (ui.should_draw()) for (uint16_t i = 0; i < fileCnt; i++) { - if (_menuLineNr == _thisItemNr) { - card.getfilename_sorted(SD_ORDER(i, fileCnt)); - if (card.flag.filenameIsDir) - MENU_ITEM(sdfolder, MSG_MEDIA_MENU, card); - else - MENU_ITEM(sdfile, MSG_MEDIA_MENU, card); + if (ui.should_draw()) { + for (int16_t i = 0; i < fileCnt; i++) { + if (_menuLineNr != _thisItemNr) + SKIP_ITEM(); + else { + card.selectFileByIndexSorted(i); + if (card.flag.filenameIsDir) + MENU_ITEM(sdfolder, MSG_MEDIA_MENU, card); + else + MENU_ITEM(sdfile, MSG_MEDIA_MENU, card); + } } - else - SKIP_ITEM(); } END_MENU(); } @@ -146,7 +145,7 @@ void menu_media_filelist() { #if ENABLED(MULTI_VOLUME) void menu_media_select() { START_MENU(); - BACK_ITEM_F(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT_F(MSG_MAIN) : GET_TEXT_F(MSG_BACK)); + BACK_ITEM_F(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT_F(MSG_MAIN_MENU) : GET_TEXT_F(MSG_BACK)); #if ENABLED(VOLUME_SD_ONBOARD) ACTION_ITEM(MSG_SD_CARD, []{ card.changeMedia(&card.media_driver_sdcard); card.mount(); ui.goto_screen(menu_media_filelist); }); #endif @@ -161,4 +160,4 @@ void menu_media() { TERN(MULTI_VOLUME, menu_media_select, menu_media_filelist)(); } -#endif // HAS_MARLINUI_MENU && SDSUPPORT +#endif // HAS_MARLINUI_MENU && HAS_MEDIA diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp index f787d47d0f4d..21c18c820989 100644 --- a/Marlin/src/lcd/menu/menu_mixer.cpp +++ b/Marlin/src/lcd/menu/menu_mixer.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, MIXING_EXTRUDER) +#if ALL(HAS_MARLINUI_MENU, MIXING_EXTRUDER) #include "menu_item.h" #include "menu_addon.h" @@ -170,7 +170,7 @@ void lcd_mixer_mix_edit() { #if CHANNEL_MIX_EDITING - LOOP_S_LE_N(n, 1, MIXING_STEPPERS) + for (uint8_t n = 1; n <= MIXING_STEPPERS; ++n) EDIT_ITEM_FAST_N(float42_52, n, MSG_MIX_COMPONENT_N, &mixer.collector[n-1], 0, 10); ACTION_ITEM(MSG_CYCLE_MIX, _lcd_mixer_cycle_mix); @@ -225,7 +225,7 @@ void lcd_mixer_mix_edit() { void menu_mixer() { START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); v_index = mixer.get_current_vtool(); EDIT_ITEM(uint8, MSG_ACTIVE_VTOOL, &v_index, 0, MIXING_VIRTUAL_TOOLS - 1, _lcd_mixer_select_vtool, ENABLED(HAS_DUAL_MIXING)); diff --git a/Marlin/src/lcd/menu/menu_mmu2.cpp b/Marlin/src/lcd/menu/menu_mmu2.cpp index a2412b0f6ae8..347a585de130 100644 --- a/Marlin/src/lcd/menu/menu_mmu2.cpp +++ b/Marlin/src/lcd/menu/menu_mmu2.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if BOTH(HAS_MARLINUI_MENU, MMU2_MENUS) +#if ALL(HAS_MARLINUI_MENU, MMU2_MENUS) #include "../../MarlinCore.h" #include "../../feature/mmu/mmu2.h" @@ -104,7 +104,7 @@ void action_mmu2_reset() { void menu_mmu2() { START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); SUBMENU(MSG_MMU2_LOAD_FILAMENT, menu_mmu2_load_filament); SUBMENU(MSG_MMU2_LOAD_TO_NOZZLE, menu_mmu2_load_to_nozzle); SUBMENU(MSG_MMU2_EJECT_FILAMENT, menu_mmu2_eject_filament); diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 81068ae30b53..5c16a56f6914 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -118,7 +118,7 @@ void lcd_move_axis(const AxisEnum axis) { #endif // E_MANUAL -#if EITHER(PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) +#if ANY(PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) void _goto_manual_move_z(const_float_t scale) { ui.manual_move.menu_scale = scale; @@ -206,7 +206,7 @@ void menu_move() { START_MENU(); BACK_ITEM(MSG_MOTION); - #if BOTH(HAS_SOFTWARE_ENDSTOPS, SOFT_ENDSTOPS_MENU_ITEM) + #if ALL(HAS_SOFTWARE_ENDSTOPS, SOFT_ENDSTOPS_MENU_ITEM) EDIT_ITEM(bool, MSG_LCD_SOFT_ENDSTOPS, &soft_endstop._enabled); #endif @@ -264,7 +264,7 @@ void menu_move() { #define SUBMENU_MOVE_E(N) SUBMENU_N(N, MSG_MOVE_EN, []{ _menu_move_distance(E_AXIS, []{ lcd_move_e(N); }, N); }); - #if EITHER(SWITCHING_EXTRUDER, SWITCHING_NOZZLE) + #if ANY(SWITCHING_EXTRUDER, SWITCHING_NOZZLE) // ...and the non-switching #if E_MANUAL == 7 || E_MANUAL == 5 || E_MANUAL == 3 @@ -316,7 +316,7 @@ void menu_motion() { // // ^ Main // - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); // // Move Axis @@ -346,7 +346,7 @@ void menu_motion() { // // Auto Z-Align // - #if EITHER(Z_STEPPER_AUTO_ALIGN, MECHANICAL_GANTRY_CALIBRATION) + #if ANY(Z_STEPPER_AUTO_ALIGN, MECHANICAL_GANTRY_CALIBRATION) GCODES_ITEM(MSG_AUTO_Z_ALIGN, F("G34")); #endif @@ -403,7 +403,7 @@ void menu_motion() { #endif #if ENABLED(LCD_BED_TRAMMING) && DISABLED(LCD_BED_LEVELING) - SUBMENU(MSG_BED_TRAMMING, _lcd_level_bed_corners); + SUBMENU(MSG_BED_TRAMMING, _lcd_bed_tramming); #endif #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) diff --git a/Marlin/src/lcd/menu/menu_password.cpp b/Marlin/src/lcd/menu/menu_password.cpp index 50e3df3dfec9..361a331cabf0 100644 --- a/Marlin/src/lcd/menu/menu_password.cpp +++ b/Marlin/src/lcd/menu/menu_password.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, PASSWORD_FEATURE) +#if ALL(HAS_MARLINUI_MENU, PASSWORD_FEATURE) #include "../../feature/password/password.h" @@ -108,7 +108,7 @@ void Password::authentication_done() { // A single digit was completed void Password::digit_entered() { uint32_t multiplier = CAT(1e, PASSWORD_LENGTH); // 1e5 = 100000 - LOOP_LE_N(i, digit_no) multiplier /= 10; + for (uint8_t i = 0; i <= digit_no; ++i) multiplier /= 10; value_entry += editable.uint8 * multiplier; string[digit_no++] = '0' + editable.uint8; diff --git a/Marlin/src/lcd/menu/menu_power_monitor.cpp b/Marlin/src/lcd/menu/menu_power_monitor.cpp index 3cd9909e5cf7..3d718c108a77 100644 --- a/Marlin/src/lcd/menu/menu_power_monitor.cpp +++ b/Marlin/src/lcd/menu/menu_power_monitor.cpp @@ -33,7 +33,7 @@ void menu_power_monitor() { START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); #if ENABLED(POWER_MONITOR_CURRENT) { diff --git a/Marlin/src/lcd/menu/menu_probe_offset.cpp b/Marlin/src/lcd/menu/menu_probe_offset.cpp index c7cbebaade82..34172de4581a 100644 --- a/Marlin/src/lcd/menu/menu_probe_offset.cpp +++ b/Marlin/src/lcd/menu/menu_probe_offset.cpp @@ -51,7 +51,7 @@ inline void z_clearance_move() { void set_offset_and_go_back(const_float_t z) { probe.offset.z = z; SET_SOFT_ENDSTOP_LOOSE(false); - TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); + TERN_(HAS_LEVELING, set_bed_leveling_enabled(menu_leveling_was_active)); ui.goto_previous_screen_no_defer(); } @@ -119,7 +119,7 @@ void prepare_for_probe_offset_wizard() { // Move Nozzle to Probing/Homing Position ui.wait_for_move = true; current_position += probe.offset_xy; - line_to_current_position(MMM_TO_MMS(XY_PROBE_FEEDRATE)); + line_to_current_position(XY_PROBE_FEEDRATE_MM_S); ui.synchronize(GET_TEXT_F(MSG_PROBE_WIZARD_MOVING)); ui.wait_for_move = false; @@ -143,7 +143,7 @@ void goto_probe_offset_wizard() { // Store Bed-Leveling-State and disable #if HAS_LEVELING - leveling_was_active = planner.leveling_active; + menu_leveling_was_active = planner.leveling_active; set_bed_leveling_enabled(false); #endif diff --git a/Marlin/src/lcd/menu/menu_spindle_laser.cpp b/Marlin/src/lcd/menu/menu_spindle_laser.cpp index de16316987e6..e053361fb07e 100644 --- a/Marlin/src/lcd/menu/menu_spindle_laser.cpp +++ b/Marlin/src/lcd/menu/menu_spindle_laser.cpp @@ -39,7 +39,7 @@ #endif START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); #if ENABLED(SPINDLE_LASER_USE_PWM) // Change the cutter's "current power" value without turning the cutter on or off diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 2e5b8f1e54ce..56f80b89130a 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -35,7 +35,7 @@ #include "../../module/motion.h" #endif -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "../../feature/cooler.h" #endif @@ -162,7 +162,7 @@ void menu_temperature() { #endif START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); // // Nozzle: @@ -179,7 +179,7 @@ void menu_temperature() { #endif #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) - LOOP_S_L_N(e, 1, EXTRUDERS) + for (uint8_t e = 1; e < EXTRUDERS; ++e) EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_STANDBY, &thermalManager.singlenozzle_temp[e], 0, thermalManager.hotend_max_target(0)); #endif @@ -222,7 +222,7 @@ void menu_temperature() { DEFINE_SINGLENOZZLE_ITEM(); #if HAS_FAN0 - _FAN_EDIT_ITEMS(0,FIRST_FAN_SPEED); + _FAN_EDIT_ITEMS(0, FIRST_FAN_SPEED); #endif #if HAS_FAN1 && REDUNDANT_PART_COOLING_FAN != 1 FAN_EDIT_ITEMS(1); @@ -266,7 +266,7 @@ void menu_temperature() { // // Preheat for all Materials // - LOOP_L_N(m, PREHEAT_COUNT) { + for (uint8_t m = 0; m < PREHEAT_COUNT; ++m) { editable.int8 = m; #if HAS_MULTI_HOTEND || HAS_HEATED_BED SUBMENU_f(ui.get_preheat_label(m), MSG_PREHEAT_M, menu_preheat_m); @@ -291,9 +291,9 @@ void menu_temperature() { void menu_preheat_only() { START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); - LOOP_L_N(m, PREHEAT_COUNT) { + for (uint8_t m = 0; m < PREHEAT_COUNT; ++m) { editable.int8 = m; #if HAS_MULTI_HOTEND || HAS_HEATED_BED SUBMENU_f(ui.get_preheat_label(m), MSG_PREHEAT_M, menu_preheat_m); diff --git a/Marlin/src/lcd/menu/menu_touch_screen.cpp b/Marlin/src/lcd/menu/menu_touch_screen.cpp index 130308dadffa..93380cb0e04a 100644 --- a/Marlin/src/lcd/menu/menu_touch_screen.cpp +++ b/Marlin/src/lcd/menu/menu_touch_screen.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) +#if ALL(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) #include "menu_item.h" #include "../marlinui.h" diff --git a/Marlin/src/lcd/menu/menu_tramming.cpp b/Marlin/src/lcd/menu/menu_tramming_wizard.cpp similarity index 98% rename from Marlin/src/lcd/menu/menu_tramming.cpp rename to Marlin/src/lcd/menu/menu_tramming_wizard.cpp index 1dd8a1cab6fd..c7d85282b41e 100644 --- a/Marlin/src/lcd/menu/menu_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_tramming_wizard.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, ASSISTED_TRAMMING_WIZARD) +#if ALL(HAS_MARLINUI_MENU, ASSISTED_TRAMMING_WIZARD) #include "menu_item.h" diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index a4a30882214a..f63e88653eba 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -109,7 +109,7 @@ void menu_tune() { START_MENU(); - BACK_ITEM(MSG_MAIN); + BACK_ITEM(MSG_MAIN_MENU); // // Speed: @@ -119,7 +119,7 @@ void menu_tune() { // // Manual bed leveling, Bed Z: // - #if BOTH(MESH_BED_LEVELING, LCD_BED_LEVELING) + #if ALL(MESH_BED_LEVELING, LCD_BED_LEVELING) EDIT_ITEM(float43, MSG_BED_Z, &bedlevel.z_offset, -1, 1); #endif @@ -135,7 +135,7 @@ void menu_tune() { #endif #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) - LOOP_S_L_N(e, 1, EXTRUDERS) + for (uint8_t e = 1; e < EXTRUDERS; ++e) EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_STANDBY, &thermalManager.singlenozzle_temp[e], 0, thermalManager.hotend_max_target(0)); #endif diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index d6f42faa5558..c8fd33d26df0 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, AUTO_BED_LEVELING_UBL) +#if ALL(HAS_MARLINUI_MENU, AUTO_BED_LEVELING_UBL) #include "menu_item.h" #include "../../gcode/gcode.h" diff --git a/Marlin/src/lcd/menu/menu_x_twist.cpp b/Marlin/src/lcd/menu/menu_x_twist.cpp index a069b427c6bf..56872b73ee25 100644 --- a/Marlin/src/lcd/menu/menu_x_twist.cpp +++ b/Marlin/src/lcd/menu/menu_x_twist.cpp @@ -46,7 +46,7 @@ float measured_z, z_offset; void xatc_wizard_done() { if (!ui.wait_for_move) { xatc.print_points(); - set_bed_leveling_enabled(leveling_was_active); + set_bed_leveling_enabled(menu_leveling_was_active); SET_SOFT_ENDSTOP_LOOSE(false); ui.goto_screen(menu_advanced_settings); } @@ -141,7 +141,7 @@ void xatc_wizard_goto_next_point() { xatc.set_enabled(true); 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)); + line_to_current_position(XY_PROBE_FEEDRATE_MM_S); ui.wait_for_move = false; } else @@ -150,12 +150,12 @@ void xatc_wizard_goto_next_point() { else { // Compute the z-offset by averaging the values found with this wizard z_offset = 0; - LOOP_L_N(i, XATC_MAX_POINTS) z_offset += xatc.z_offset[i]; + for (uint8_t i = 0; i < XATC_MAX_POINTS; ++i) z_offset += xatc.z_offset[i]; z_offset /= XATC_MAX_POINTS; // Subtract the average from the values found with this wizard. // This way they are indipendent from the z-offset - LOOP_L_N(i, XATC_MAX_POINTS) xatc.z_offset[i] -= z_offset; + for (uint8_t i = 0; i < XATC_MAX_POINTS; ++i) xatc.z_offset[i] -= z_offset; ui.goto_screen(xatc_wizard_update_z_offset); } @@ -170,7 +170,7 @@ void xatc_wizard_homing_done() { MenuItem_static::draw(1, GET_TEXT_F(MSG_LEVEL_BED_WAITING)); // Color UI needs a control to detect a touch - #if BOTH(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) + #if ALL(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) touch.add_control(CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT); #endif } @@ -199,7 +199,7 @@ void xatc_wizard_homing() { void xatc_wizard_continue() { // Store Bed-Leveling-State and disable #if HAS_LEVELING - leveling_was_active = planner.leveling_active; + menu_leveling_was_active = planner.leveling_active; set_bed_leveling_enabled(false); #endif diff --git a/Marlin/src/lcd/tft/canvas.cpp b/Marlin/src/lcd/tft/canvas.cpp index e8b89bad7060..c852dd96b9a4 100644 --- a/Marlin/src/lcd/tft/canvas.cpp +++ b/Marlin/src/lcd/tft/canvas.cpp @@ -41,7 +41,7 @@ void CANVAS::New(uint16_t x, uint16_t y, uint16_t width, uint16_t height) { void CANVAS::Continue() { startLine = endLine; - endLine = TFT_BUFFER_SIZE < width * (height - startLine) ? startLine + TFT_BUFFER_SIZE / width : height; + endLine = TFT_BUFFER_WORDS < width * (height - startLine) ? startLine + TFT_BUFFER_WORDS / width : height; } bool CANVAS::ToScreen() { diff --git a/Marlin/src/lcd/tft/tft.h b/Marlin/src/lcd/tft/tft.h index 6df4c22d5191..9e6092705114 100644 --- a/Marlin/src/lcd/tft/tft.h +++ b/Marlin/src/lcd/tft/tft.h @@ -53,21 +53,21 @@ #error "Unsupported display resolution!" #endif -#ifndef TFT_BUFFER_SIZE +#ifndef TFT_BUFFER_WORDS #ifdef STM32F103xB - #define TFT_BUFFER_SIZE 1024 + #define TFT_BUFFER_WORDS 1024 #elif defined(STM32F103xE) - #define TFT_BUFFER_SIZE 19200 // 320 * 60 + #define TFT_BUFFER_WORDS 19200 // 320 * 60 #elif defined(STM32F1) - #define TFT_BUFFER_SIZE 8192 + #define TFT_BUFFER_WORDS 8192 #else - #define TFT_BUFFER_SIZE 19200 // 320 * 60 + #define TFT_BUFFER_WORDS 19200 // 320 * 60 #endif #endif -#if TFT_BUFFER_SIZE > DMA_MAX_SIZE +#if TFT_BUFFER_WORDS > DMA_MAX_WORDS // DMA Count parameter is uint16_t - #error "TFT_BUFFER_SIZE can not exceed DMA_MAX_SIZE" + #error "TFT_BUFFER_WORDS can not exceed DMA_MAX_WORDS" #endif class TFT { @@ -78,7 +78,7 @@ class TFT { public: static TFT_Queue queue; - static uint16_t buffer[TFT_BUFFER_SIZE]; + static uint16_t buffer[TFT_BUFFER_WORDS]; static void init(); static void set_font(const uint8_t *Font) { string.set_font(Font); } diff --git a/Marlin/src/lcd/tft/tft_color.h b/Marlin/src/lcd/tft/tft_color.h index a8668179e579..bfc47a517fa8 100644 --- a/Marlin/src/lcd/tft/tft_color.h +++ b/Marlin/src/lcd/tft/tft_color.h @@ -30,8 +30,8 @@ #define COLOR(color) RGB(((color >> 16) & 0xFF), ((color >> 8) & 0xFF), (color & 0xFF)) #define HALF(color) RGB(RED(color) >> 1, GREEN(color) >> 1, BLUE(color) >> 1) -// 16 bit color generator: https://ee-programming-notepad.blogspot.com/2016/10/16-bit-color-generator-picker.html -// RGB565 color picker: https://trolsoft.ru/en/articles/rgb565-color-picker +// RGB565 color picker: https://embeddednotepad.com/page/rgb565-color-picker +// Hex code to color name: https://www.color-name.com/ #define COLOR_BLACK 0x0000 // #000000 #define COLOR_WHITE 0xFFFF // #FFFFFF diff --git a/Marlin/src/lcd/tft/tft_queue.cpp b/Marlin/src/lcd/tft/tft_queue.cpp index 19dd810dc7dc..2ce421cae18e 100644 --- a/Marlin/src/lcd/tft/tft_queue.cpp +++ b/Marlin/src/lcd/tft/tft_queue.cpp @@ -86,9 +86,9 @@ void TFT_Queue::fill(queueTask_t *task) { task->state = TASK_STATE_IN_PROGRESS; } - if (task_parameters->count > DMA_MAX_SIZE) { - count = DMA_MAX_SIZE; - task_parameters->count -= DMA_MAX_SIZE; + if (task_parameters->count > DMA_MAX_WORDS) { + count = DMA_MAX_WORDS; + task_parameters->count -= DMA_MAX_WORDS; } else { count = task_parameters->count; diff --git a/Marlin/src/lcd/tft/tft_string.cpp b/Marlin/src/lcd/tft/tft_string.cpp index d589b0465b7f..cd285b0d4a80 100644 --- a/Marlin/src/lcd/tft/tft_string.cpp +++ b/Marlin/src/lcd/tft/tft_string.cpp @@ -25,7 +25,7 @@ #if HAS_GRAPHICAL_TFT #include "tft_string.h" -#include "../fontutils.h" +#include "../utf8.h" #include "../marlinui.h" //#define DEBUG_TFT_FONT @@ -88,7 +88,7 @@ void TFT_String::set() { * Add a string, applying substitutions for the following characters: * * $ displays the string given by fstr or cstr - * = displays '0'....'10' for indexes 0 - 10 + * { displays '0'....'10' for indexes 0 - 10 * ~ displays '1'....'11' for indexes 0 - 10 * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) * @ displays an axis name such as XYZUVW, or E for an extruder @@ -101,9 +101,9 @@ void TFT_String::add(const char *tpl, const int8_t index, const char *cstr/*=nul if (wc > 255) wc |= 0x0080; const uint8_t ch = uint8_t(wc & 0x00FF); - if (ch == '=' || ch == '~' || ch == '*') { + if (ch == '{' || ch == '~' || ch == '*') { if (index >= 0) { - int8_t inum = index + ((ch == '=') ? 0 : LCD_FIRST_TOOL); + int8_t inum = index + ((ch == '{') ? 0 : LCD_FIRST_TOOL); if (ch == '*') add_character('E'); if (inum >= 10) { add_character('0' + (inum / 10)); inum %= 10; } add_character('0' + inum); diff --git a/Marlin/src/lcd/tft/tft_string.h b/Marlin/src/lcd/tft/tft_string.h index d43e0b0df2b4..1c3af88981b7 100644 --- a/Marlin/src/lcd/tft/tft_string.h +++ b/Marlin/src/lcd/tft/tft_string.h @@ -25,7 +25,7 @@ #include -#include "../fontutils.h" +#include "../utf8.h" extern const uint8_t ISO10646_1_5x7[]; extern const uint8_t font10x20[]; diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index 1665e9ab7700..ff2fb0e1c809 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -76,7 +76,6 @@ void Touch::add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t } void Touch::idle() { - uint16_t i; int16_t _x, _y; if (!enabled) return; @@ -121,7 +120,7 @@ void Touch::idle() { current_control = nullptr; } else { - for (i = 0; i < controls_count; i++) { + for (uint16_t i = 0; i < controls_count; i++) { if ((WITHIN(x, controls[i].x, controls[i].x + controls[i].width) && WITHIN(y, controls[i].y, controls[i].y + controls[i].height)) || (TERN(TOUCH_SCREEN_CALIBRATION, controls[i].type == CALIBRATE, false))) { touch_control_type = controls[i].type; touch(&controls[i]); @@ -273,12 +272,14 @@ bool Touch::get_point(int16_t *x, int16_t *y) { #elif ENABLED(TFT_TOUCH_DEVICE_GT911) bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? io.getPoint(y, x) : io.getPoint(x, y)); #endif + #if HAS_TOUCH_SLEEP if (is_touched) wakeUp(); else if (!isSleeping() && ELAPSED(millis(), next_sleep_ms) && ui.on_status_screen()) sleepTimeout(); #endif + return is_touched; } diff --git a/Marlin/src/lcd/tft/touch.h b/Marlin/src/lcd/tft/touch.h index eab85604f107..3d58f684ed67 100644 --- a/Marlin/src/lcd/tft/touch.h +++ b/Marlin/src/lcd/tft/touch.h @@ -108,7 +108,7 @@ class Touch { 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); + static void hold(touch_control_t *control, millis_t delay=0); public: static void init(); @@ -130,7 +130,7 @@ class Touch { static void sleepTimeout(); static void wakeUp(); #endif - static void add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t width, uint16_t height, intptr_t data = 0); + static void add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t width, uint16_t height, intptr_t data=0); }; extern Touch touch; diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index 08d6b51fdbba..6bc2da41b01b 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -36,7 +36,7 @@ #include "../../module/planner.h" #include "../../module/motion.h" -#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) +#if DISABLED(LCD_PROGRESS_BAR) && ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) #include "../../feature/filwidth.h" #include "../../gcode/parser.h" #endif @@ -326,7 +326,7 @@ void MarlinUI::draw_status_screen() { #if ENABLED(TOUCH_SCREEN) add_control(900, y, menu_main, imgSettings); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA const bool cm = card.isMounted(), pa = printingIsActive(); add_control(12, y, menu_media, imgSD, cm && !pa, COLOR_CONTROL_ENABLED, cm && pa ? COLOR_BUSY : COLOR_CONTROL_DISABLED); #endif @@ -605,7 +605,7 @@ MotionAxisState motionAxisState; static void quick_feedback() { #if HAS_CHIRP ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_MARLINUI_MENU, HAS_BEEPER) + #if ALL(HAS_MARLINUI_MENU, HAS_BEEPER) for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } #elif HAS_MARLINUI_MENU delay(10); @@ -795,7 +795,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } } #endif -#if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) +#if ALL(HAS_BED_PROBE, TOUCH_SCREEN) static void z_select() { motionAxisState.z_selection *= -1; quick_feedback(); @@ -890,7 +890,7 @@ void MarlinUI::move_axis_screen() { motionAxisState.zTypePos.x = x; motionAxisState.zTypePos.y = y; drawCurZSelection(); - #if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) + #if ALL(HAS_BED_PROBE, TOUCH_SCREEN) if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); #endif diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index 9014d4ed1216..08c28fef8b9a 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -36,7 +36,7 @@ #include "../../module/planner.h" #include "../../module/motion.h" -#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) +#if DISABLED(LCD_PROGRESS_BAR) && ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) #include "../../feature/filwidth.h" #include "../../gcode/parser.h" #endif @@ -343,7 +343,7 @@ void MarlinUI::draw_status_screen() { #if ENABLED(TOUCH_SCREEN) add_control(256, 130, menu_main, imgSettings); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA const bool cm = card.isMounted(), pa = printingIsActive(); add_control(0, 130, menu_media, imgSD, cm && !pa, COLOR_CONTROL_ENABLED, cm && pa ? COLOR_BUSY : COLOR_CONTROL_DISABLED); #endif @@ -581,7 +581,7 @@ MotionAxisState motionAxisState; static void quick_feedback() { #if HAS_CHIRP ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_MARLINUI_MENU, HAS_BEEPER) + #if ALL(HAS_MARLINUI_MENU, HAS_BEEPER) for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } #elif HAS_MARLINUI_MENU delay(10); @@ -775,7 +775,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } } #endif -#if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) +#if ALL(HAS_BED_PROBE, TOUCH_SCREEN) static void z_select() { motionAxisState.z_selection *= -1; quick_feedback(); @@ -870,7 +870,7 @@ void MarlinUI::move_axis_screen() { motionAxisState.zTypePos.x = x; motionAxisState.zTypePos.y = y; drawCurZSelection(); - #if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) + #if ALL(HAS_BED_PROBE, TOUCH_SCREEN) if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); #endif diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index 22c3a3fc19c1..23251b9ec496 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -36,7 +36,7 @@ #include "../../module/planner.h" #include "../../module/motion.h" -#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) +#if DISABLED(LCD_PROGRESS_BAR) && ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) #include "../../feature/filwidth.h" #include "../../gcode/parser.h" #endif @@ -320,7 +320,7 @@ void MarlinUI::draw_status_screen() { #if ENABLED(TOUCH_SCREEN) add_control(404, y, menu_main, imgSettings); - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA const bool cm = card.isMounted(), pa = printingIsActive(); add_control(12, y, menu_media, imgSD, cm && !pa, COLOR_CONTROL_ENABLED, cm && pa ? COLOR_BUSY : COLOR_CONTROL_DISABLED); #endif @@ -586,7 +586,7 @@ MotionAxisState motionAxisState; static void quick_feedback() { #if HAS_CHIRP ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_MARLINUI_MENU, HAS_BEEPER) + #if ALL(HAS_MARLINUI_MENU, HAS_BEEPER) for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } #elif HAS_MARLINUI_MENU delay(10); @@ -776,7 +776,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); } } #endif -#if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) +#if ALL(HAS_BED_PROBE, TOUCH_SCREEN) static void z_select() { motionAxisState.z_selection *= -1; quick_feedback(); @@ -871,7 +871,7 @@ void MarlinUI::move_axis_screen() { motionAxisState.zTypePos.x = x; motionAxisState.zTypePos.y = y; drawCurZSelection(); - #if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) + #if ALL(HAS_BED_PROBE, TOUCH_SCREEN) if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); #endif diff --git a/Marlin/src/lcd/tft/ui_common.cpp b/Marlin/src/lcd/tft/ui_common.cpp index 55e433b5e4fa..fec28a165669 100644 --- a/Marlin/src/lcd/tft/ui_common.cpp +++ b/Marlin/src/lcd/tft/ui_common.cpp @@ -171,7 +171,7 @@ void MenuItem_static::draw(const uint8_t row, FSTR_P const fstr, const uint8_t s tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_YELLOW, tft_string); } -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA void MenuItem_sdbase::draw(const bool sel, const uint8_t row, FSTR_P const, CardReader &theCard, const bool isDir) { menu_item(row, sel); diff --git a/Marlin/src/lcd/tft_io/ili9328.h b/Marlin/src/lcd/tft_io/ili9328.h index b50517adfea5..591a4ec2edf0 100644 --- a/Marlin/src/lcd/tft_io/ili9328.h +++ b/Marlin/src/lcd/tft_io/ili9328.h @@ -39,7 +39,7 @@ #define ILI9328_ETMOD_ID0 0x0010 // 0 - Horizontal Decrement / 1 - Horizontal Increment #define ILI9328_ETMOD_AM 0x0008 // 0 - Horizontal / 1 - Vertical -// MKS Robin TFT v1.1 - 320x240 ; Cable on the left side +// MKS Robin TFT v1.1 - 320x240 ; FPC cable on the left side #if TFT_ROTATION == TFT_ROTATE_180 #define ILI9328_DRVCTL_DATA 0x0000 @@ -65,7 +65,6 @@ #define ILI9328_ETMOD_DATA (ILI9328_ETMOD_ORIENTATION) | (ILI9328_ETMOD_COLOR) - #define ILI9328_RDDID 0x00 // ID code - 0x9328 #define ILI9328_DRVCTL 0x01 // Driver Output Control #define ILI9328_LCDCTL 0x02 // LCD Driving Wave Control @@ -128,7 +127,6 @@ #define ILI9328_RDOTP 0xA2 // OTP VCM Status and Enable #define ILI9328_OTPPKEY 0xA5 // OTP Programming ID Key - static const uint16_t ili9328_init[] = { DATASIZE_16BIT, ESC_REG(ILI9328_DRVCTL), ILI9328_DRVCTL_DATA, diff --git a/Marlin/src/lcd/tft_io/ili9341.h b/Marlin/src/lcd/tft_io/ili9341.h index dda326df6d5b..e48db82838ca 100644 --- a/Marlin/src/lcd/tft_io/ili9341.h +++ b/Marlin/src/lcd/tft_io/ili9341.h @@ -52,7 +52,7 @@ #define ILI9341_NOP 0x00 // No Operation #define ILI9341_SWRESET 0x01 // Software Reset -#define ILI9341_RDDIDIF 0x04 // Read display identification information +#define ILI9341_RDDIDIF 0x04 // Read Display Identification Information #define ILI9341_RDDST 0x09 // Read Display Status #define ILI9341_RDDPM 0x0A // Read Display Power Mode #define ILI9341_RDDMADCTL 0x0B // Read Display MADCTL @@ -136,7 +136,6 @@ #define ILI9341_IFCTL 0xF6 // Interface Control #define ILI9341_PUMPRCTL 0xF7 // Pump ratio control - static const uint16_t ili9341_init[] = { DATASIZE_8BIT, ESC_REG(ILI9341_SWRESET), ESC_DELAY(100), diff --git a/Marlin/src/lcd/tft_io/ili9488.h b/Marlin/src/lcd/tft_io/ili9488.h index e71c0d16d775..aedbaa1358e7 100644 --- a/Marlin/src/lcd/tft_io/ili9488.h +++ b/Marlin/src/lcd/tft_io/ili9488.h @@ -25,13 +25,13 @@ #include "../../inc/MarlinConfig.h" -#define ILI9488_MADCTL_MY 0x80 // Row Address Order -#define ILI9488_MADCTL_MX 0x40 // Column Address Order -#define ILI9488_MADCTL_MV 0x20 // Row/Column Exchange -#define ILI9488_MADCTL_ML 0x10 // Vertical Refresh Order -#define ILI9488_MADCTL_BGR 0x08 // RGB-BGR ORDER -#define ILI9488_MADCTL_RGB 0x00 -#define ILI9488_MADCTL_MH 0x04 // Horizontal Refresh Order +#define ILI9488_MADCTL_MY 0x80 // Row Address Order +#define ILI9488_MADCTL_MX 0x40 // Column Address Order +#define ILI9488_MADCTL_MV 0x20 // Row/Column Exchange +#define ILI9488_MADCTL_ML 0x10 // Vertical Refresh Order +#define ILI9488_MADCTL_BGR 0x08 // RGB-BGR ORDER +#define ILI9488_MADCTL_RGB 0x00 +#define ILI9488_MADCTL_MH 0x04 // Horizontal Refresh Order #define ILI9488_ORIENTATION_UP ILI9488_MADCTL_MY // 320x480 ; Cable on the upper side #define ILI9488_ORIENTATION_RIGHT ILI9488_MADCTL_MV // 480x320 ; Cable on the right side diff --git a/Marlin/src/lcd/tft_io/r65105.h b/Marlin/src/lcd/tft_io/r65105.h index 8be2afe4423c..70443a0e045b 100644 --- a/Marlin/src/lcd/tft_io/r65105.h +++ b/Marlin/src/lcd/tft_io/r65105.h @@ -41,7 +41,7 @@ #define R61505_DRVCTRL_GS 0x8000 // Gate Scan direction -// MKS Robin TFT v1.1 - 320x240 ; Cable on the left side +// MKS Robin TFT v1.1 - 320x240 ; FPC cable on the left side #if TFT_ROTATION == TFT_ROTATE_180 #define R61505_DRVCTL_DATA 0x0000 @@ -67,7 +67,6 @@ #define R61505_ETMOD_DATA (R61505_ETMOD_ORIENTATION) | (R61505_ETMOD_COLOR) - #define R61505_RDDID 0x00 // ID code - 0x1505 #define R61505_DRVCTL 0x01 // Driver Output Control #define R61505_LCDCTL 0x02 // LCD Driving Wave Control @@ -129,7 +128,6 @@ #define R61505_OSC_CTRL 0xA4 // Oscillation Control - static const uint16_t r61505_init[] = { DATASIZE_16BIT, ESC_REG(R61505_DRVCTL), R61505_DRVCTL_DATA, diff --git a/Marlin/src/lcd/tft_io/tft_io.h b/Marlin/src/lcd/tft_io/tft_io.h index d6f178a020c1..32f2de9265e2 100644 --- a/Marlin/src/lcd/tft_io/tft_io.h +++ b/Marlin/src/lcd/tft_io/tft_io.h @@ -33,69 +33,17 @@ #error "TFT IO only supports SPI, FSMC or LTDC interface." #endif -#ifndef DMA_MAX_SIZE - #error "MAX_DMA_SIZE is not configured for this platform." +#ifndef DMA_MAX_WORDS + #error "DMA_MAX_WORDS is not configured for this platform." #endif -#define TFT_EXCHANGE_XY _BV32(1) -#define TFT_INVERT_X _BV32(2) -#define TFT_INVERT_Y _BV32(3) - -#define TFT_NO_ROTATION (0x00) -#define TFT_ROTATE_90 (TFT_EXCHANGE_XY | TFT_INVERT_X) -#define TFT_ROTATE_180 (TFT_INVERT_X | TFT_INVERT_Y) -#define TFT_ROTATE_270 (TFT_EXCHANGE_XY | TFT_INVERT_Y) - -#define TFT_MIRROR_X (TFT_INVERT_Y) -#define TFT_MIRROR_Y (TFT_INVERT_X) - -#define TFT_ROTATE_90_MIRROR_X (TFT_ROTATE_90 ^ TFT_INVERT_Y) -#define TFT_ROTATE_90_MIRROR_Y (TFT_ROTATE_90 ^ TFT_INVERT_X) - -#define TFT_ROTATE_180_MIRROR_X (TFT_ROTATE_180 ^ TFT_INVERT_Y) -#define TFT_ROTATE_180_MIRROR_Y (TFT_ROTATE_180 ^ TFT_INVERT_X) - -#define TFT_ROTATE_270_MIRROR_X (TFT_ROTATE_270 ^ TFT_INVERT_Y) -#define TFT_ROTATE_270_MIRROR_Y (TFT_ROTATE_270 ^ TFT_INVERT_X) - -// TFT_ROTATION is user configurable -#ifndef TFT_ROTATION - #define TFT_ROTATION TFT_NO_ROTATION -#endif - -// TFT_ORIENTATION is the "sum" of TFT_DEFAULT_ORIENTATION plus user TFT_ROTATION -#define TFT_ORIENTATION ((TFT_DEFAULT_ORIENTATION) ^ (TFT_ROTATION)) - -#define TFT_COLOR_RGB _BV32(3) -#define TFT_COLOR_BGR _BV32(4) - // Each TFT Driver is responsible for its default color mode. // #ifndef TFT_COLOR // #define TFT_COLOR TFT_COLOR_RGB // #endif -#define TOUCH_ORIENTATION_NONE 0 -#define TOUCH_LANDSCAPE 1 -#define TOUCH_PORTRAIT 2 - -#ifndef TOUCH_CALIBRATION_X - #define TOUCH_CALIBRATION_X 0 -#endif -#ifndef TOUCH_CALIBRATION_Y - #define TOUCH_CALIBRATION_Y 0 -#endif -#ifndef TOUCH_OFFSET_X - #define TOUCH_OFFSET_X 0 -#endif -#ifndef TOUCH_OFFSET_Y - #define TOUCH_OFFSET_Y 0 -#endif -#ifndef TOUCH_ORIENTATION - #define TOUCH_ORIENTATION TOUCH_LANDSCAPE -#endif - #ifndef TFT_DRIVER - #define TFT_DRIVER AUTO + #define TFT_DRIVER AUTO #endif #define ESC_REG(x) 0xFFFF, 0x00FF & (uint16_t)x diff --git a/Marlin/src/lcd/tft_io/tft_orientation.h b/Marlin/src/lcd/tft_io/tft_orientation.h new file mode 100644 index 000000000000..5315615799d2 --- /dev/null +++ b/Marlin/src/lcd/tft_io/tft_orientation.h @@ -0,0 +1,63 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 TFT_EXCHANGE_XY _BV32(1) +#define TFT_INVERT_X _BV32(2) +#define TFT_INVERT_Y _BV32(3) + +#define TFT_NO_ROTATION (0x00) +#define TFT_ROTATE_90 (TFT_EXCHANGE_XY | TFT_INVERT_X) +#define TFT_ROTATE_180 (TFT_INVERT_X | TFT_INVERT_Y) +#define TFT_ROTATE_270 (TFT_EXCHANGE_XY | TFT_INVERT_Y) + +#define TFT_MIRROR_X (TFT_INVERT_Y) +#define TFT_MIRROR_Y (TFT_INVERT_X) + +#define TFT_ROTATE_90_MIRROR_X (TFT_ROTATE_90 ^ TFT_MIRROR_X) +#define TFT_ROTATE_90_MIRROR_Y (TFT_ROTATE_90 ^ TFT_MIRROR_Y) + +#define TFT_ROTATE_180_MIRROR_X (TFT_ROTATE_180 ^ TFT_MIRROR_X) +#define TFT_ROTATE_180_MIRROR_Y (TFT_ROTATE_180 ^ TFT_MIRROR_Y) + +#define TFT_ROTATE_270_MIRROR_X (TFT_ROTATE_270 ^ TFT_MIRROR_X) +#define TFT_ROTATE_270_MIRROR_Y (TFT_ROTATE_270 ^ TFT_MIRROR_Y) + +// TFT_ROTATION is user configurable +#ifndef TFT_ROTATION + #define TFT_ROTATION TFT_NO_ROTATION +#endif + +// TFT_ORIENTATION is the "sum" of TFT_DEFAULT_ORIENTATION plus user TFT_ROTATION +#define TFT_ORIENTATION ((TFT_DEFAULT_ORIENTATION) ^ (TFT_ROTATION)) + +// Set TFT_COLOR_UI_PORTRAIT flag, if needed +#if ((TFT_ORIENTATION) & TFT_EXCHANGE_XY) == 0 + #define TFT_COLOR_UI_PORTRAIT +#endif + +#define TFT_COLOR_RGB _BV32(3) +#define TFT_COLOR_BGR _BV32(4) + +#define TOUCH_ORIENTATION_NONE 0 +#define TOUCH_LANDSCAPE 1 +#define TOUCH_PORTRAIT 2 diff --git a/Marlin/src/lcd/tft_io/touch_calibration.h b/Marlin/src/lcd/tft_io/touch_calibration.h index 030b4977db51..e903c90d99c2 100644 --- a/Marlin/src/lcd/tft_io/touch_calibration.h +++ b/Marlin/src/lcd/tft_io/touch_calibration.h @@ -27,7 +27,6 @@ #ifndef TOUCH_SCREEN_CALIBRATION_PRECISION #define TOUCH_SCREEN_CALIBRATION_PRECISION 80 #endif - #ifndef TOUCH_SCREEN_HOLD_TO_CALIBRATE_MS #define TOUCH_SCREEN_HOLD_TO_CALIBRATE_MS 2500 #endif diff --git a/Marlin/src/lcd/thermistornames.h b/Marlin/src/lcd/thermistornames.h index 54542bed4ed8..71f48775bdbe 100644 --- a/Marlin/src/lcd/thermistornames.h +++ b/Marlin/src/lcd/thermistornames.h @@ -35,15 +35,17 @@ #if THERMISTOR_ID == 1000 #define THERMISTOR_NAME "User Parameters" -// Thermcouples +// SPI RTD/Thermocouple Boards #elif THERMISTOR_ID == -5 #define THERMISTOR_NAME "MAX31865" -#elif THERMISTOR_ID == -4 - #define THERMISTOR_NAME "AD8495" #elif THERMISTOR_ID == -3 #define THERMISTOR_NAME "MAX31855" #elif THERMISTOR_ID == -2 #define THERMISTOR_NAME "MAX6675" + +// Analog Thermocouple Boards +#elif THERMISTOR_ID == -4 + #define THERMISTOR_NAME "AD8495" #elif THERMISTOR_ID == -1 #define THERMISTOR_NAME "AD595" @@ -94,44 +96,54 @@ #define THERMISTOR_NAME "E3104FXT (alt)" #elif THERMISTOR_ID == 13 #define THERMISTOR_NAME "Hisens 3950" +#elif THERMISTOR_ID == 14 + #define THERMISTOR_NAME "100k Ender-5 S1" #elif THERMISTOR_ID == 15 #define THERMISTOR_NAME "100k JGAurora A5" +#elif THERMISTOR_ID == 17 + #define THERMISTOR_NAME "100k Dagoma NTC" #elif THERMISTOR_ID == 18 #define THERMISTOR_NAME "ATC Semitec 204GT-2" -#elif THERMISTOR_ID == 20 - #define THERMISTOR_NAME "Pt100 UltiMB 5v" -#elif THERMISTOR_ID == 21 - #define THERMISTOR_NAME "Pt100 UltiMB 3.3v" -#elif THERMISTOR_ID == 201 - #define THERMISTOR_NAME "Pt100 OverLord" #elif THERMISTOR_ID == 60 #define THERMISTOR_NAME "Makers Tool" #elif THERMISTOR_ID == 70 #define THERMISTOR_NAME "Hephestos 2" #elif THERMISTOR_ID == 75 #define THERMISTOR_NAME "MGB18" -#elif THERMISTOR_ID == 99 - #define THERMISTOR_NAME "100k with 10k pull-up" -// Modified thermistors -#elif THERMISTOR_ID == 30 - #define THERMISTOR_NAME "Kis3d EN AW NTC100K/3950" +// Analog Thermistors - 1kΩ pullup #elif THERMISTOR_ID == 51 #define THERMISTOR_NAME "EPCOS 1K" #elif THERMISTOR_ID == 52 #define THERMISTOR_NAME "ATC204GT-2 1K" #elif THERMISTOR_ID == 55 #define THERMISTOR_NAME "ATC104GT-2 1K" -#elif THERMISTOR_ID == 1047 - #define THERMISTOR_NAME "PT1000 4K7" -#elif THERMISTOR_ID == 1022 - #define THERMISTOR_NAME "PT1000 2K2" -#elif THERMISTOR_ID == 1010 - #define THERMISTOR_NAME "PT1000 1K" -#elif THERMISTOR_ID == 147 - #define THERMISTOR_NAME "Pt100 4K7" + +// Analog Thermistors - 10kΩ pullup - Atypical +#elif THERMISTOR_ID == 99 + #define THERMISTOR_NAME "100k with 10k pull-up" + +// Analog RTDs (Pt100/Pt1000) #elif THERMISTOR_ID == 110 #define THERMISTOR_NAME "Pt100 1K" +#elif THERMISTOR_ID == 147 + #define THERMISTOR_NAME "Pt100 4K7" +#elif THERMISTOR_ID == 1010 + #define THERMISTOR_NAME "PT1000 1K" +#elif THERMISTOR_ID == 1022 + #define THERMISTOR_NAME "PT1000 2K2" +#elif THERMISTOR_ID == 1047 + #define THERMISTOR_NAME "PT1000 4K7" +#elif THERMISTOR_ID == 20 + #define THERMISTOR_NAME "Pt100 UltiMB 5v" +#elif THERMISTOR_ID == 21 + #define THERMISTOR_NAME "Pt100 UltiMB 3.3v" +#elif THERMISTOR_ID == 201 + #define THERMISTOR_NAME "Pt100 OverLord" + +// Modified thermistors +#elif THERMISTOR_ID == 30 + #define THERMISTOR_NAME "Kis3d EN AW NTC100K/3950" #elif THERMISTOR_ID == 666 #define THERMISTOR_NAME "Einstart S" #elif THERMISTOR_ID == 2000 diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index 032015cdd0ed..d6c891bd8a9c 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -65,7 +65,7 @@ void TouchButtons::init() { } uint8_t TouchButtons::read_buttons() { - #ifdef HAS_WIRED_LCD + #if HAS_WIRED_LCD int16_t x, y; #if ENABLED(TFT_TOUCH_DEVICE_XPT2046) @@ -93,6 +93,7 @@ uint8_t TouchButtons::read_buttons() { #elif ENABLED(TFT_TOUCH_DEVICE_GT911) const bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? touchIO.getPoint(&y, &x) : touchIO.getPoint(&x, &y)); if (!is_touched) return 0; + #endif // Touch within the button area simulates an encoder button @@ -127,6 +128,7 @@ uint8_t TouchButtons::read_buttons() { #endif next_sleep_ms = TSLP_SLEEPING; } + void TouchButtons::wakeUp() { if (isSleeping()) { #if HAS_LCD_BRIGHTNESS @@ -135,7 +137,7 @@ uint8_t TouchButtons::read_buttons() { WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif } - next_sleep_ms = millis() + SEC_TO_MS(ui.sleep_timeout_minutes * 60); + next_sleep_ms = millis() + MIN_TO_MS(ui.sleep_timeout_minutes); } #endif // HAS_TOUCH_SLEEP diff --git a/Marlin/src/lcd/fontutils.cpp b/Marlin/src/lcd/utf8.cpp similarity index 91% rename from Marlin/src/lcd/fontutils.cpp rename to Marlin/src/lcd/utf8.cpp index 46329fd4be62..716b6d73c6b1 100644 --- a/Marlin/src/lcd/fontutils.cpp +++ b/Marlin/src/lcd/utf8.cpp @@ -21,8 +21,8 @@ */ /** - * @file fontutils.cpp - * @brief help functions for font and char + * @file utf8.cpp + * @brief Helper functions for UTF-8 strings * @author Yunhui Fu (yhfudev@gmail.com) * @version 1.0 * @date 2016-08-19 @@ -36,7 +36,7 @@ #include "../MarlinCore.h" #endif -#include "fontutils.h" +#include "utf8.h" uint8_t read_byte_ram(const uint8_t *str) { return *str; } uint8_t read_byte_rom(const uint8_t *str) { return pgm_read_byte(str); } @@ -90,13 +90,15 @@ int pf_bsearch_r(void *userdata, size_t num_data, pf_bsearch_cb_comp_t cb_comp, return -1; } -/* Returns true if passed byte is first byte of UTF-8 char sequence */ +// Is the passed byte the first byte of a UTF-8 char sequence? static inline bool utf8_is_start_byte_of_char(const uint8_t b) { return 0x80 != (b & 0xC0); } -/* This function gets the character at the pstart position, interpreting UTF8 multibyte sequences - and returns the pointer to the next character */ +/** + * Get the character at pstart, interpreting UTF8 multibyte sequences. + * Return the pointer to the next character. + */ const uint8_t* get_utf8_value_cb(const uint8_t *pstart, read_byte_cb_t cb_read_byte, lchar_t &pval) { uint32_t val = 0; const uint8_t *p = pstart; @@ -173,13 +175,8 @@ static inline uint8_t utf8_strlen_cb(const char *pstart, read_byte_cb_t cb_read_ return cnt; } -uint8_t utf8_strlen(const char *pstart) { - return utf8_strlen_cb(pstart, read_byte_ram); -} - -uint8_t utf8_strlen_P(PGM_P pstart) { - return utf8_strlen_cb(pstart, read_byte_rom); -} +uint8_t utf8_strlen(const char *pstart) { return utf8_strlen_cb(pstart, read_byte_ram); } +uint8_t utf8_strlen_P(PGM_P pstart) { return utf8_strlen_cb(pstart, read_byte_rom); } static inline uint8_t utf8_byte_pos_by_char_num_cb(const char *pstart, read_byte_cb_t cb_read_byte, const uint8_t charnum) { uint8_t *p = (uint8_t *)pstart; diff --git a/Marlin/src/lcd/fontutils.h b/Marlin/src/lcd/utf8.h similarity index 97% rename from Marlin/src/lcd/fontutils.h rename to Marlin/src/lcd/utf8.h index 69edf1a0c839..603181857174 100644 --- a/Marlin/src/lcd/fontutils.h +++ b/Marlin/src/lcd/utf8.h @@ -21,8 +21,8 @@ */ /** - * @file fontutils.h - * @brief help functions for font and char + * @file utf8.h + * @brief Helper functions for UTF-8 strings * @author Yunhui Fu (yhfudev@gmail.com) * @version 1.0 * @date 2016-08-19 diff --git a/Marlin/src/libs/BL24CXX.cpp b/Marlin/src/libs/BL24CXX.cpp index 4b5a23e4c550..adfdc1387cf2 100644 --- a/Marlin/src/libs/BL24CXX.cpp +++ b/Marlin/src/libs/BL24CXX.cpp @@ -141,7 +141,7 @@ void IIC::nAck() { void IIC::send_byte(uint8_t txd) { SDA_OUT(); IIC_SCL_0(); // Pull down the clock to start data transmission - LOOP_L_N(t, 8) { + for (uint8_t t = 0; t < 8; ++t) { // IIC_SDA = (txd & 0x80) >> 7; if (txd & 0x80) IIC_SDA_1(); else IIC_SDA_0(); txd <<= 1; @@ -157,7 +157,7 @@ void IIC::send_byte(uint8_t txd) { uint8_t IIC::read_byte(unsigned char ack_chr) { unsigned char receive = 0; SDA_IN(); // SDA is set as input - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { IIC_SCL_0(); delay_us(2); IIC_SCL_1(); @@ -228,7 +228,7 @@ void BL24CXX::writeOneByte(uint16_t WriteAddr, uint8_t DataToWrite) { // DataToWrite: the first address of the data array // Len: The length of the data to be written 2, 4 void BL24CXX::writeLenByte(uint16_t WriteAddr, uint32_t DataToWrite, uint8_t Len) { - LOOP_L_N(t, Len) + for (uint8_t t = 0; t < Len; ++t) writeOneByte(WriteAddr + t, (DataToWrite >> (8 * t)) & 0xFF); } @@ -239,7 +239,7 @@ void BL24CXX::writeLenByte(uint16_t WriteAddr, uint32_t DataToWrite, uint8_t Len // Len: The length of the data to be read 2,4 uint32_t BL24CXX::readLenByte(uint16_t ReadAddr, uint8_t Len) { uint32_t temp = 0; - LOOP_L_N(t, Len) { + for (uint8_t t = 0; t < Len; ++t) { temp <<= 8; temp += readOneByte(ReadAddr + Len - t - 1); } diff --git a/Marlin/src/libs/W25Qxx.cpp b/Marlin/src/libs/W25Qxx.cpp index 591d0d069318..558d604ea52d 100644 --- a/Marlin/src/libs/W25Qxx.cpp +++ b/Marlin/src/libs/W25Qxx.cpp @@ -48,10 +48,12 @@ void W25QXXFlash::init(uint8_t spiRate) { * STM32F1 has 3 SPI ports, SPI1 in APB2, SPI2/SPI3 in APB1 * so the minimum prescale of SPI1 is DIV4, SPI2/SPI3 is DIV2 */ - #if SPI_DEVICE == 1 - #define SPI_CLOCK_MAX SPI_CLOCK_DIV4 - #else - #define SPI_CLOCK_MAX SPI_CLOCK_DIV2 + #ifndef SPI_CLOCK_MAX + #if SPI_DEVICE == 1 + #define SPI_CLOCK_MAX SPI_CLOCK_DIV4 + #else + #define SPI_CLOCK_MAX SPI_CLOCK_DIV2 + #endif #endif uint8_t clock; switch (spiRate) { diff --git a/Marlin/src/libs/buzzer.h b/Marlin/src/libs/buzzer.h index cd86e7e7ecf7..f6d5b49d7397 100644 --- a/Marlin/src/libs/buzzer.h +++ b/Marlin/src/libs/buzzer.h @@ -27,7 +27,9 @@ #include "circularqueue.h" - #define TONE_QUEUE_LENGTH 4 + #ifndef TONE_QUEUE_LENGTH + #define TONE_QUEUE_LENGTH 4 + #endif /** * @brief Tone structure diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index 69a648441feb..d648924dc95c 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -67,7 +67,7 @@ struct duration_t { } /** - * @brief Formats the duration as years + * @brief Format the duration as years * @return The number of years */ inline uint8_t year() const { @@ -75,7 +75,7 @@ struct duration_t { } /** - * @brief Formats the duration as days + * @brief Format the duration as days * @return The number of days */ inline uint16_t day() const { @@ -83,7 +83,7 @@ struct duration_t { } /** - * @brief Formats the duration as hours + * @brief Format the duration as hours * @return The number of hours */ inline uint32_t hour() const { @@ -91,7 +91,7 @@ struct duration_t { } /** - * @brief Formats the duration as minutes + * @brief Format the duration as minutes * @return The number of minutes */ inline uint32_t minute() const { @@ -99,7 +99,7 @@ struct duration_t { } /** - * @brief Formats the duration as seconds + * @brief Format the duration as seconds * @return The number of seconds */ inline uint32_t second() const { @@ -112,11 +112,12 @@ struct duration_t { #endif /** - * @brief Formats the duration as a string + * @brief Format the duration as a string * @details String will be formatted using a "full" representation of duration * * @param buffer The array pointed to must be able to accommodate 22 bytes * (21 for the string, 1 more for the terminating nul) + * @param dense Whether to skip spaces in the resulting string * * Output examples: * 123456789012345678901 (strlen) @@ -142,10 +143,42 @@ struct duration_t { } /** - * @brief Formats the duration as a string + * @brief Format the duration as a compact string + * @details String will be formatted using a "full" representation of duration + * + * @param buffer The array pointed to must be able to accommodate 18 bytes + * (17 for the string, 1 more for the terminating nul) + * @param dense Whether to skip spaces in the resulting string + * + * Output examples: + * 12345678901234567 (strlen) + * 135y364d23h59m59s + * 364d23h59m59s + * 23h59m59s + * 59m59s + * 59s + */ + char* toCompactString(char * const buffer) const { + 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); + else if (h) sprintf_P(buffer, PSTR("%ih%im%is"), h, m, s); + else if (m) sprintf_P(buffer, PSTR("%im%is"), m, s); + else sprintf_P(buffer, PSTR("%is"), s); + return buffer; + } + + /** + * @brief Format the duration as a string * @details String will be formatted using a "digital" representation of duration * * @param buffer The array pointed to must be able to accommodate 10 bytes + * @return length of the formatted string (without terminating nul) * * Output examples: * 123456789 (strlen) diff --git a/Marlin/src/libs/heatshrink/heatshrink_decoder.cpp b/Marlin/src/libs/heatshrink/heatshrink_decoder.cpp index 073a7ed0b6ec..3d4d3fcd3fdb 100644 --- a/Marlin/src/libs/heatshrink/heatshrink_decoder.cpp +++ b/Marlin/src/libs/heatshrink/heatshrink_decoder.cpp @@ -142,7 +142,6 @@ HSD_sink_res heatshrink_decoder_sink(heatshrink_decoder *hsd, return HSDR_SINK_OK; } - /***************** * Decompression * *****************/ diff --git a/Marlin/src/libs/hex_print.cpp b/Marlin/src/libs/hex_print.cpp index 1958084abb2d..b9edc38c7778 100644 --- a/Marlin/src/libs/hex_print.cpp +++ b/Marlin/src/libs/hex_print.cpp @@ -20,7 +20,7 @@ * */ -#include "../inc/MarlinConfigPre.h" +#include "../inc/MarlinConfig.h" #if NEED_HEX_PRINT @@ -41,28 +41,26 @@ char* hex_byte(const uint8_t b) { return &_hex[byte_start + 4]; } -inline void _hex_word(const uint16_t w) { +inline void __hex_word(const uint16_t w) { _hex[byte_start + 2] = hex_nybble(w >> 12); _hex[byte_start + 3] = hex_nybble(w >> 8); _hex[byte_start + 4] = hex_nybble(w >> 4); _hex[byte_start + 5] = hex_nybble(w); } -char* hex_word(const uint16_t w) { - _hex_word(w); +char* _hex_word(const uint16_t w) { + __hex_word(w); return &_hex[byte_start + 2]; } -#ifdef CPU_32_BIT - char* hex_long(const uintptr_t l) { - _hex[2] = hex_nybble(l >> 28); - _hex[3] = hex_nybble(l >> 24); - _hex[4] = hex_nybble(l >> 20); - _hex[5] = hex_nybble(l >> 16); - _hex_word((uint16_t)(l & 0xFFFF)); - return &_hex[2]; - } -#endif +char* _hex_long(const uintptr_t l) { + _hex[2] = hex_nybble(l >> 28); + _hex[3] = hex_nybble(l >> 24); + _hex[4] = hex_nybble(l >> 20); + _hex[5] = hex_nybble(l >> 16); + __hex_word((uint16_t)(l & 0xFFFF)); + return &_hex[2]; +} char* hex_address(const void * const w) { #ifdef CPU_32_BIT @@ -78,11 +76,11 @@ void print_hex_byte(const uint8_t b) { SERIAL_ECHO(hex_byte(b)); } void print_hex_word(const uint16_t w) { SERIAL_ECHO(hex_word(w)); } void print_hex_address(const void * const w) { SERIAL_ECHO(hex_address(w)); } -void print_hex_long(const uint32_t w, const char delimiter) { +void print_hex_long(const uint32_t w, const char delimiter/*='\0'*/) { SERIAL_ECHOPGM("0x"); for (int B = 24; B >= 8; B -= 8) { print_hex_byte(w >> B); - SERIAL_CHAR(delimiter); + if (delimiter) SERIAL_CHAR(delimiter); } print_hex_byte(w); } diff --git a/Marlin/src/libs/hex_print.h b/Marlin/src/libs/hex_print.h index 0baae15bd36f..4a5cac2b6c1c 100644 --- a/Marlin/src/libs/hex_print.h +++ b/Marlin/src/libs/hex_print.h @@ -31,11 +31,15 @@ constexpr char hex_nybble(const uint8_t n) { return (n & 0xF) + ((n & 0xF) < 10 ? '0' : 'A' - 10); } char* hex_byte(const uint8_t b); -char* hex_word(const uint16_t w); +char* _hex_word(const uint16_t w); char* hex_address(const void * const w); +char* _hex_long(const uintptr_t l); + +template char* hex_word(T w) { return _hex_word((uint16_t)w); } +template char* hex_long(T w) { return _hex_long((uint32_t)w); } void print_hex_nybble(const uint8_t n); void print_hex_byte(const uint8_t b); void print_hex_word(const uint16_t w); void print_hex_address(const void * const w); -void print_hex_long(const uint32_t w, const char delimiter); +void print_hex_long(const uint32_t w, const char delimiter='\0'); diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index 575e74a81472..5430864af604 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -22,7 +22,7 @@ #include "../inc/MarlinConfig.h" -#if EITHER(NOZZLE_CLEAN_FEATURE, NOZZLE_PARK_FEATURE) +#if ANY(NOZZLE_CLEAN_FEATURE, NOZZLE_PARK_FEATURE) #include "nozzle.h" @@ -62,7 +62,7 @@ Nozzle nozzle; #endif // Start the stroke pattern - LOOP_L_N(i, strokes >> 1) { + for (uint8_t i = 0; i < strokes >> 1; ++i) { #if ENABLED(NOZZLE_CLEAN_NO_Y) do_blocking_move_to_x(end.x); do_blocking_move_to_x(start.x); @@ -102,7 +102,7 @@ Nozzle nozzle; const bool horiz = ABS(diff.x) >= ABS(diff.y); // Do a horizontal wipe? const float P = (horiz ? diff.x : diff.y) / zigs; // Period of each zig / zag const xyz_pos_t *side; - LOOP_L_N(j, strokes) { + for (uint8_t j = 0; j < strokes; ++j) { for (int8_t i = 0; i < zigs; i++) { side = (i & 1) ? &end : &start; if (horiz) @@ -138,8 +138,8 @@ Nozzle nozzle; #endif TERN(NOZZLE_CLEAN_NO_Z, do_blocking_move_to_xy, do_blocking_move_to)(start); - LOOP_L_N(s, strokes) - LOOP_L_N(i, NOZZLE_CLEAN_CIRCLE_FN) + for (uint8_t s = 0; s < strokes; ++s) + for (uint8_t i = 0; i < NOZZLE_CLEAN_CIRCLE_FN; ++i) do_blocking_move_to_xy( middle.x + sin((RADIANS(360) / NOZZLE_CLEAN_CIRCLE_FN) * i) * radius, middle.y + cos((RADIANS(360) / NOZZLE_CLEAN_CIRCLE_FN) * i) * radius @@ -161,7 +161,7 @@ Nozzle nozzle; void Nozzle::clean(const uint8_t &pattern, const uint8_t &strokes, const_float_t radius, const uint8_t &objects, const uint8_t cleans) { xyz_pos_t start[HOTENDS] = NOZZLE_CLEAN_START_POINT, end[HOTENDS] = NOZZLE_CLEAN_END_POINT, middle[HOTENDS] = NOZZLE_CLEAN_CIRCLE_MIDDLE; - const uint8_t arrPos = EITHER(SINGLENOZZLE, MIXING_EXTRUDER) ? 0 : active_extruder; + const uint8_t arrPos = ANY(SINGLENOZZLE, MIXING_EXTRUDER) ? 0 : active_extruder; #if NOZZLE_CLEAN_MIN_TEMP > 20 if (thermalManager.degTargetHotend(arrPos) < NOZZLE_CLEAN_MIN_TEMP) { diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index c28d1246d693..636e62f3bccc 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -25,16 +25,27 @@ #include "../inc/MarlinConfigPre.h" #include "../core/utility.h" -char conv[9] = { 0 }; +constexpr char DIGIT(const uint8_t n) { return '0' + n; } + +template +constexpr char DIGIMOD(const T1 n, const T2 f) { return DIGIT((n / f) % 10); } + +template +constexpr char RJDIGIT(const T1 n, const T2 f) { return (n >= (T1)f ? DIGIMOD(n, f) : ' '); } + +template +constexpr char MINUSOR(T &n, const char alt) { return (n >= 0) ? alt : (n = -n) ? '-' : '-'; } -#define DIGIT(n) ('0' + (n)) -#define DIGIMOD(n, f) DIGIT((n)/(f) % 10) -#define RJDIGIT(n, f) ((n) >= (f) ? DIGIMOD(n, f) : ' ') -#define MINUSOR(n, alt) (n >= 0 ? (alt) : (n = -n, '-')) -#define INTFLOAT(V,N) (((V) * 10 * pow(10, N) + ((V) < 0 ? -5: 5)) / 10) // pow10? -#define UINTFLOAT(V,N) INTFLOAT((V) < 0 ? -(V) : (V), N) +constexpr long INTFLOAT(const float V, const int N) { + return long((V * 10.0f * pow(10.0f, N) + (V < 0.0f ? -5.0f : 5.0f)) / 10.0f); +} +constexpr long UINTFLOAT(const float V, const int N) { + return INTFLOAT(V < 0.0f ? -V : V, N); +} + +char conv[9] = { 0 }; -// Format uint8_t (0-100) as rj string with 123% / _12% / __1% format +// Format uint8_t (0-100) as rj string with __3% / _23% / 123% format const char* pcttostrpctrj(const uint8_t i) { conv[4] = RJDIGIT(i, 100); conv[5] = RJDIGIT(i, 10); @@ -48,7 +59,7 @@ const char* ui8tostr4pctrj(const uint8_t i) { return pcttostrpctrj(ui8_to_percent(i)); } -// Convert unsigned 8bit int to string 123 format +// Convert unsigned 8bit int to string with __3 / _23 / 123 format const char* ui8tostr3rj(const uint8_t i) { conv[5] = RJDIGIT(i, 100); conv[6] = RJDIGIT(i, 10); @@ -63,7 +74,7 @@ const char* ui8tostr2(const uint8_t i) { return &conv[6]; } -// Convert signed 8bit int to rj string with 123 or -12 format +// Convert signed 8bit int to rj string with __3 / _23 / 123 / -_3 / -23 format const char* i8tostr3rj(const int8_t x) { int xx = x; conv[5] = MINUSOR(xx, RJDIGIT(xx, 100)); @@ -211,7 +222,7 @@ const char* ftostr41ns(const_float_t f) { return &conv[3]; } -// Convert signed float to fixed-length string with 12.34 / _2.34 / -2.34 or -23.45 / 123.45 format +// Convert float to fixed-length string with 12.34 / _2.34 / -2.34 or -23.45 / 123.45 format const char* ftostr42_52(const_float_t f) { if (f <= -10 || f >= 100) return ftostr52(f); // -23.45 / 123.45 long i = INTFLOAT(f, 2); @@ -223,7 +234,7 @@ const char* ftostr42_52(const_float_t f) { return &conv[3]; } -// Convert signed float to fixed-length string with 023.45 / -23.45 format +// Convert float to fixed-length string with 023.45 / -23.45 format const char* ftostr52(const_float_t f) { long i = INTFLOAT(f, 2); conv[2] = MINUSOR(i, DIGIMOD(i, 10000)); @@ -235,7 +246,7 @@ const char* ftostr52(const_float_t f) { return &conv[2]; } -// Convert signed float to fixed-length string with 12.345 / _2.345 / -2.345 or -23.45 / 123.45 format +// Convert float to fixed-length string with 12.345 / _2.345 / -2.345 or -23.45 / 123.45 format const char* ftostr53_63(const_float_t f) { if (f <= -10 || f >= 100) return ftostr63(f); // -23.456 / 123.456 long i = INTFLOAT(f, 3); @@ -248,7 +259,7 @@ const char* ftostr53_63(const_float_t f) { return &conv[2]; } -// Convert signed float to fixed-length string with 023.456 / -23.456 format +// Convert float to fixed-length string with 023.456 / -23.456 format const char* ftostr63(const_float_t f) { long i = INTFLOAT(f, 3); conv[1] = MINUSOR(i, DIGIMOD(i, 100000)); @@ -407,17 +418,17 @@ const char* ftostr52sp(const_float_t f) { conv[3] = RJDIGIT(i, 1000); conv[4] = DIGIMOD(i, 100); - if ((dig = i % 10)) { // second digit after decimal point? + if ((dig = i % 10)) { // Second digit after decimal point? conv[5] = '.'; conv[6] = DIGIMOD(i, 10); conv[7] = DIGIT(dig); } else { - if ((dig = (i / 10) % 10)) { // first digit after decimal point? + if ((dig = (i / 10) % 10)) { // First digit after decimal point? conv[5] = '.'; conv[6] = DIGIT(dig); } - else // nothing after decimal point + else // Nothing after decimal point conv[5] = conv[6] = ' '; conv[7] = ' '; } diff --git a/Marlin/src/libs/numtostr.h b/Marlin/src/libs/numtostr.h index 84027b44cde5..d4959b513ac9 100644 --- a/Marlin/src/libs/numtostr.h +++ b/Marlin/src/libs/numtostr.h @@ -40,7 +40,7 @@ const char* ui8tostr3rj(const uint8_t i); const char* i8tostr3rj(const int8_t x); #if HAS_PRINT_PROGRESS_PERMYRIAD - // Convert 16-bit unsigned permyriad value to percent: 100 / 23 / 23.4 / 3.45 + // Convert 16-bit unsigned permyriad value to percent: _100 / __23 / 23.4 / 3.45 const char* permyriadtostr4(const uint16_t xx); #endif @@ -56,7 +56,7 @@ const char* ui16tostr3rj(const uint16_t x); // Convert int16_t to string with 123 format const char* i16tostr3rj(const int16_t x); -// Convert unsigned int to lj string with 123 format +// Convert signed int to lj string with 123 format const char* i16tostr3left(const int16_t xx); // Convert signed int to rj string with _123, -123, _-12, or __-1 format @@ -86,10 +86,10 @@ const char* ftostr53_63(const_float_t x); // Convert signed float to fixed-length string with 023.456 / -23.456 format const char* ftostr63(const_float_t x); -// Convert float to fixed-length string with +12.3 / -12.3 format +// Convert signed float to fixed-length string with +12.3 / -12.3 format const char* ftostr31sign(const_float_t x); -// Convert float to fixed-length string with +123.4 / -123.4 format +// Convert signed float to fixed-length string with +123.4 / -123.4 format const char* ftostr41sign(const_float_t x); // Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format @@ -101,7 +101,7 @@ const char* ftostr54sign(const_float_t x, char plus=' '); // Convert unsigned float to rj string with 12345 format const char* ftostr5rj(const_float_t x); -// Convert signed float to string with +1234.5 format +// Convert signed float to fixed-length string with +1234.5 format const char* ftostr51sign(const_float_t x); // Convert signed float to space-padded string with -_23.4_ format @@ -116,16 +116,16 @@ const char* ftostr53sign(const_float_t f); // Convert unsigned float to string with 12345.6 format omitting trailing zeros const char* ftostr61rj(const_float_t x); -// Convert unsigned float to string with 12345.67 format omitting trailing zeros +// Convert unsigned float to string with ____5.67, ___45.67, __345.67, _2345.67, 12345.67 format const char* ftostr72rj(const_float_t x); -// Convert float to rj string with 123 or -12 format +// Convert signed float to rj string with 123 or -12 format FORCE_INLINE const char* ftostr3rj(const_float_t x) { return i16tostr3rj(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } #if ENABLED(LCD_DECIMAL_SMALL_XY) - // Convert float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format + // Convert signed float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format const char* ftostr4sign(const_float_t fx); #else - // Convert float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format + // Convert signed float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format FORCE_INLINE const char* ftostr4sign(const_float_t x) { return i16tostr4signrj(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } #endif diff --git a/Marlin/src/libs/vector_3.cpp b/Marlin/src/libs/vector_3.cpp index 02945fe6871a..a222b5cc2e7e 100644 --- a/Marlin/src/libs/vector_3.cpp +++ b/Marlin/src/libs/vector_3.cpp @@ -93,8 +93,8 @@ void matrix_3x3::apply_rotation_xyz(float &_x, float &_y, float &_z) { // Reset to identity. No rotate or translate. void matrix_3x3::set_to_identity() { - LOOP_L_N(i, 3) - LOOP_L_N(j, 3) + for (uint8_t i = 0; i < 3; ++i) + for (uint8_t j = 0; j < 3; ++j) vectors[i][j] = float(i == j); } @@ -131,16 +131,16 @@ matrix_3x3 matrix_3x3::create_look_at(const vector_3 &target) { // Get a transposed copy of the matrix matrix_3x3 matrix_3x3::transpose(const matrix_3x3 &original) { matrix_3x3 new_matrix; - LOOP_L_N(i, 3) - LOOP_L_N(j, 3) + for (uint8_t i = 0; i < 3; ++i) + for (uint8_t j = 0; j < 3; ++j) new_matrix.vectors[i][j] = original.vectors[j][i]; return new_matrix; } void matrix_3x3::debug(FSTR_P const title) { if (title) SERIAL_ECHOLNF(title); - LOOP_L_N(i, 3) { - LOOP_L_N(j, 3) { + for (uint8_t i = 0; i < 3; ++i) { + for (uint8_t j = 0; j < 3; ++j) { serial_offset(vectors[i][j], 2); SERIAL_CHAR(' '); } diff --git a/Marlin/src/libs/vector_3.h b/Marlin/src/libs/vector_3.h index 58bdb43c7b41..ab719c6a7f43 100644 --- a/Marlin/src/libs/vector_3.h +++ b/Marlin/src/libs/vector_3.h @@ -50,9 +50,9 @@ struct vector_3 { float pos[3]; }; vector_3(const_float_t _x, const_float_t _y, const_float_t _z) : x(_x), y(_y), z(_z) {} - vector_3(const xy_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); } - vector_3(const xyz_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); } - vector_3(const xyze_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); } + vector_3(const xy_float_t &in) { TERN_(HAS_X_AXIS, x = in.x); TERN_(HAS_Y_AXIS, y = in.y); } + vector_3(const xyz_float_t &in) { TERN_(HAS_X_AXIS, x = in.x); TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); } + vector_3(const xyze_float_t &in) { TERN_(HAS_X_AXIS, x = in.x); TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); } vector_3() { x = y = z = 0; } // Factory method @@ -75,8 +75,8 @@ struct vector_3 { vector_3 operator-(const vector_3 &v) { return vector_3(x - v.x, y - v.y, z - v.z); } vector_3 operator*(const float &v) { return vector_3(x * v, y * v, z * v); } - operator xy_float_t() { return xy_float_t({ x OPTARG(HAS_Y_AXIS, y) }); } - operator xyz_float_t() { return xyz_float_t({ x OPTARG(HAS_Y_AXIS, y) OPTARG(HAS_Z_AXIS, z) }); } + operator xy_float_t() { return xy_float_t({ TERN_(HAS_X_AXIS, x) OPTARG(HAS_Y_AXIS, y) }); } + operator xyz_float_t() { return xyz_float_t({ TERN_(HAS_X_AXIS, x) OPTARG(HAS_Y_AXIS, y) OPTARG(HAS_Z_AXIS, z) }); } void debug(FSTR_P const title); }; diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index ce2a6f4adad0..bc068fe43ff9 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -242,7 +242,7 @@ void home_delta() { #endif // Move all carriages together linearly until an endstop is hit. - current_position.z = DIFF_TERN(HAS_BED_PROBE, delta_height + 10, probe.offset.z); + current_position.z = DIFF_TERN(USE_PROBE_FOR_Z_HOMING, delta_height + 10, probe.offset.z); line_to_current_position(homing_feedrate(Z_AXIS)); planner.synchronize(); TERN_(HAS_DELTA_SENSORLESS_PROBING, endstops.report_states()); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index a5daf7afbdd8..0bea57bfc654 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -31,14 +31,14 @@ #include "temperature.h" #include "../lcd/marlinui.h" -#define DEBUG_OUT BOTH(USE_SENSORLESS, DEBUG_LEVELING_FEATURE) +#define DEBUG_OUT ALL(USE_SENSORLESS, DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" #if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) #include HAL_PATH(.., endstop_interrupts.h) #endif -#if BOTH(SD_ABORT_ON_ENDSTOP_HIT, SDSUPPORT) +#if ALL(SD_ABORT_ON_ENDSTOP_HIT, HAS_MEDIA) #include "printcounter.h" // for print_job_timer #endif @@ -109,7 +109,7 @@ Endstops::endstop_mask_t Endstops::live_state = 0; void Endstops::init() { - #if HAS_X_MIN + #if USE_X_MIN #if ENABLED(ENDSTOPPULLUP_XMIN) SET_INPUT_PULLUP(X_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_XMIN) @@ -119,7 +119,7 @@ void Endstops::init() { #endif #endif - #if HAS_X2_MIN + #if USE_X2_MIN #if ENABLED(ENDSTOPPULLUP_XMIN) SET_INPUT_PULLUP(X2_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_XMIN) @@ -129,7 +129,7 @@ void Endstops::init() { #endif #endif - #if HAS_Y_MIN + #if USE_Y_MIN #if ENABLED(ENDSTOPPULLUP_YMIN) SET_INPUT_PULLUP(Y_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_YMIN) @@ -139,7 +139,7 @@ void Endstops::init() { #endif #endif - #if HAS_Y2_MIN + #if USE_Y2_MIN #if ENABLED(ENDSTOPPULLUP_YMIN) SET_INPUT_PULLUP(Y2_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_YMIN) @@ -149,7 +149,7 @@ void Endstops::init() { #endif #endif - #if HAS_Z_MIN + #if USE_Z_MIN #if ENABLED(ENDSTOPPULLUP_ZMIN) SET_INPUT_PULLUP(Z_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_ZMIN) @@ -159,7 +159,7 @@ void Endstops::init() { #endif #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN #if ENABLED(ENDSTOPPULLUP_ZMIN) SET_INPUT_PULLUP(Z2_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_ZMIN) @@ -169,7 +169,7 @@ void Endstops::init() { #endif #endif - #if HAS_Z3_MIN + #if USE_Z3_MIN #if ENABLED(ENDSTOPPULLUP_ZMIN) SET_INPUT_PULLUP(Z3_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_ZMIN) @@ -179,7 +179,7 @@ void Endstops::init() { #endif #endif - #if HAS_Z4_MIN + #if USE_Z4_MIN #if ENABLED(ENDSTOPPULLUP_ZMIN) SET_INPUT_PULLUP(Z4_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_ZMIN) @@ -189,7 +189,7 @@ void Endstops::init() { #endif #endif - #if HAS_X_MAX + #if USE_X_MAX #if ENABLED(ENDSTOPPULLUP_XMAX) SET_INPUT_PULLUP(X_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_XMAX) @@ -199,7 +199,7 @@ void Endstops::init() { #endif #endif - #if HAS_X2_MAX + #if USE_X2_MAX #if ENABLED(ENDSTOPPULLUP_XMAX) SET_INPUT_PULLUP(X2_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_XMAX) @@ -209,7 +209,7 @@ void Endstops::init() { #endif #endif - #if HAS_Y_MAX + #if USE_Y_MAX #if ENABLED(ENDSTOPPULLUP_YMAX) SET_INPUT_PULLUP(Y_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_YMAX) @@ -219,7 +219,7 @@ void Endstops::init() { #endif #endif - #if HAS_Y2_MAX + #if USE_Y2_MAX #if ENABLED(ENDSTOPPULLUP_YMAX) SET_INPUT_PULLUP(Y2_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_YMAX) @@ -229,7 +229,7 @@ void Endstops::init() { #endif #endif - #if HAS_Z_MAX + #if USE_Z_MAX #if ENABLED(ENDSTOPPULLUP_ZMAX) SET_INPUT_PULLUP(Z_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_ZMAX) @@ -239,7 +239,7 @@ void Endstops::init() { #endif #endif - #if HAS_Z2_MAX + #if USE_Z2_MAX #if ENABLED(ENDSTOPPULLUP_ZMAX) SET_INPUT_PULLUP(Z2_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_ZMAX) @@ -249,7 +249,7 @@ void Endstops::init() { #endif #endif - #if HAS_Z3_MAX + #if USE_Z3_MAX #if ENABLED(ENDSTOPPULLUP_ZMAX) SET_INPUT_PULLUP(Z3_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_ZMAX) @@ -259,7 +259,7 @@ void Endstops::init() { #endif #endif - #if HAS_Z4_MAX + #if USE_Z4_MAX #if ENABLED(ENDSTOPPULLUP_ZMAX) SET_INPUT_PULLUP(Z4_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_ZMAX) @@ -269,7 +269,7 @@ void Endstops::init() { #endif #endif - #if HAS_I_MIN + #if USE_I_MIN #if ENABLED(ENDSTOPPULLUP_IMIN) SET_INPUT_PULLUP(I_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_IMIN) @@ -279,7 +279,7 @@ void Endstops::init() { #endif #endif - #if HAS_I_MAX + #if USE_I_MAX #if ENABLED(ENDSTOPPULLUP_IMAX) SET_INPUT_PULLUP(I_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_IMAX) @@ -289,7 +289,7 @@ void Endstops::init() { #endif #endif - #if HAS_J_MIN + #if USE_J_MIN #if ENABLED(ENDSTOPPULLUP_JMIN) SET_INPUT_PULLUP(J_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_IMIN) @@ -299,7 +299,7 @@ void Endstops::init() { #endif #endif - #if HAS_J_MAX + #if USE_J_MAX #if ENABLED(ENDSTOPPULLUP_JMAX) SET_INPUT_PULLUP(J_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_JMAX) @@ -309,7 +309,7 @@ void Endstops::init() { #endif #endif - #if HAS_K_MIN + #if USE_K_MIN #if ENABLED(ENDSTOPPULLUP_KMIN) SET_INPUT_PULLUP(K_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_KMIN) @@ -319,7 +319,7 @@ void Endstops::init() { #endif #endif - #if HAS_K_MAX + #if USE_K_MAX #if ENABLED(ENDSTOPPULLUP_KMAX) SET_INPUT_PULLUP(K_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_KMIN) @@ -329,7 +329,7 @@ void Endstops::init() { #endif #endif - #if HAS_U_MIN + #if USE_U_MIN #if ENABLED(ENDSTOPPULLUP_UMIN) SET_INPUT_PULLUP(U_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_UMIN) @@ -339,7 +339,7 @@ void Endstops::init() { #endif #endif - #if HAS_U_MAX + #if USE_U_MAX #if ENABLED(ENDSTOPPULLUP_UMAX) SET_INPUT_PULLUP(U_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_UMIN) @@ -349,7 +349,7 @@ void Endstops::init() { #endif #endif - #if HAS_V_MIN + #if USE_V_MIN #if ENABLED(ENDSTOPPULLUP_VMIN) SET_INPUT_PULLUP(V_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_VMIN) @@ -359,7 +359,7 @@ void Endstops::init() { #endif #endif - #if HAS_V_MAX + #if USE_V_MAX #if ENABLED(ENDSTOPPULLUP_VMAX) SET_INPUT_PULLUP(V_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_VMIN) @@ -369,7 +369,7 @@ void Endstops::init() { #endif #endif - #if HAS_W_MIN + #if USE_W_MIN #if ENABLED(ENDSTOPPULLUP_WMIN) SET_INPUT_PULLUP(W_MIN_PIN); #elif ENABLED(ENDSTOPPULLDOWN_WMIN) @@ -379,7 +379,7 @@ void Endstops::init() { #endif #endif - #if HAS_W_MAX + #if USE_W_MAX #if ENABLED(ENDSTOPPULLUP_WMAX) SET_INPUT_PULLUP(W_MAX_PIN); #elif ENABLED(ENDSTOPPULLDOWN_WMIN) @@ -546,7 +546,7 @@ void Endstops::event_handler() { ) ); - #if BOTH(SD_ABORT_ON_ENDSTOP_HIT, SDSUPPORT) + #if ALL(SD_ABORT_ON_ENDSTOP_HIT, HAS_MEDIA) if (planner.abort_on_endstop_hit) { card.abortFilePrintNow(); quickstop_stepper(); @@ -578,88 +578,88 @@ void __O2 Endstops::report_states() { TERN_(BLTOUCH, bltouch._set_SW_mode()); SERIAL_ECHOLNPGM(STR_M119_REPORT); #define ES_REPORT(S) print_es_state(READ_ENDSTOP(S##_PIN) != S##_ENDSTOP_INVERTING, F(STR_##S)) - #if HAS_X_MIN + #if USE_X_MIN ES_REPORT(X_MIN); #endif - #if HAS_X2_MIN + #if USE_X2_MIN ES_REPORT(X2_MIN); #endif - #if HAS_X_MAX + #if USE_X_MAX ES_REPORT(X_MAX); #endif - #if HAS_X2_MAX + #if USE_X2_MAX ES_REPORT(X2_MAX); #endif - #if HAS_Y_MIN + #if USE_Y_MIN ES_REPORT(Y_MIN); #endif - #if HAS_Y2_MIN + #if USE_Y2_MIN ES_REPORT(Y2_MIN); #endif - #if HAS_Y_MAX + #if USE_Y_MAX ES_REPORT(Y_MAX); #endif - #if HAS_Y2_MAX + #if USE_Y2_MAX ES_REPORT(Y2_MAX); #endif - #if HAS_Z_MIN + #if USE_Z_MIN ES_REPORT(Z_MIN); #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN ES_REPORT(Z2_MIN); #endif - #if HAS_Z3_MIN + #if USE_Z3_MIN ES_REPORT(Z3_MIN); #endif - #if HAS_Z4_MIN + #if USE_Z4_MIN ES_REPORT(Z4_MIN); #endif - #if HAS_Z_MAX + #if USE_Z_MAX ES_REPORT(Z_MAX); #endif - #if HAS_Z2_MAX + #if USE_Z2_MAX ES_REPORT(Z2_MAX); #endif - #if HAS_Z3_MAX + #if USE_Z3_MAX ES_REPORT(Z3_MAX); #endif - #if HAS_Z4_MAX + #if USE_Z4_MAX ES_REPORT(Z4_MAX); #endif - #if HAS_I_MIN + #if USE_I_MIN ES_REPORT(I_MIN); #endif - #if HAS_I_MAX + #if USE_I_MAX ES_REPORT(I_MAX); #endif - #if HAS_J_MIN + #if USE_J_MIN ES_REPORT(J_MIN); #endif - #if HAS_J_MAX + #if USE_J_MAX ES_REPORT(J_MAX); #endif - #if HAS_K_MIN + #if USE_K_MIN ES_REPORT(K_MIN); #endif - #if HAS_K_MAX + #if USE_K_MAX ES_REPORT(K_MAX); #endif - #if HAS_U_MIN + #if USE_U_MIN ES_REPORT(U_MIN); #endif - #if HAS_U_MAX + #if USE_U_MAX ES_REPORT(U_MAX); #endif - #if HAS_V_MIN + #if USE_V_MIN ES_REPORT(V_MIN); #endif - #if HAS_V_MAX + #if USE_V_MAX ES_REPORT(V_MAX); #endif - #if HAS_W_MIN + #if USE_W_MIN ES_REPORT(W_MIN); #endif - #if HAS_W_MAX + #if USE_W_MAX ES_REPORT(W_MAX); #endif #if ENABLED(PROBE_ACTIVATION_SWITCH) @@ -670,7 +670,7 @@ void __O2 Endstops::report_states() { #endif #if MULTI_FILAMENT_SENSOR #define _CASE_RUNOUT(N) case N: pin = FIL_RUNOUT##N##_PIN; state = FIL_RUNOUT##N##_STATE; break; - LOOP_S_LE_N(i, 1, NUM_RUNOUT_SENSORS) { + for (uint8_t i = 1; i <= NUM_RUNOUT_SENSORS; ++i) { pin_t pin; uint8_t state; switch (i) { @@ -747,10 +747,10 @@ void Endstops::update() { /** * Check and update endstops */ - #if HAS_X_MIN && !X_SPI_SENSORLESS + #if USE_X_MIN && !X_SPI_SENSORLESS UPDATE_ENDSTOP_BIT(X, MIN); #if ENABLED(X_DUAL_ENDSTOPS) - #if HAS_X2_MIN + #if USE_X2_MIN UPDATE_ENDSTOP_BIT(X2, MIN); #else COPY_LIVE_STATE(X_MIN, X2_MIN); @@ -758,10 +758,10 @@ void Endstops::update() { #endif #endif - #if HAS_X_MAX && !X_SPI_SENSORLESS + #if USE_X_MAX && !X_SPI_SENSORLESS UPDATE_ENDSTOP_BIT(X, MAX); #if ENABLED(X_DUAL_ENDSTOPS) - #if HAS_X2_MAX + #if USE_X2_MAX UPDATE_ENDSTOP_BIT(X2, MAX); #else COPY_LIVE_STATE(X_MAX, X2_MAX); @@ -769,10 +769,10 @@ void Endstops::update() { #endif #endif - #if HAS_Y_MIN && !Y_SPI_SENSORLESS + #if USE_Y_MIN && !Y_SPI_SENSORLESS UPDATE_ENDSTOP_BIT(Y, MIN); #if ENABLED(Y_DUAL_ENDSTOPS) - #if HAS_Y2_MIN + #if USE_Y2_MIN UPDATE_ENDSTOP_BIT(Y2, MIN); #else COPY_LIVE_STATE(Y_MIN, Y2_MIN); @@ -780,10 +780,10 @@ void Endstops::update() { #endif #endif - #if HAS_Y_MAX && !Y_SPI_SENSORLESS + #if USE_Y_MAX && !Y_SPI_SENSORLESS UPDATE_ENDSTOP_BIT(Y, MAX); #if ENABLED(Y_DUAL_ENDSTOPS) - #if HAS_Y2_MAX + #if USE_Y2_MAX UPDATE_ENDSTOP_BIT(Y2, MAX); #else COPY_LIVE_STATE(Y_MAX, Y2_MAX); @@ -791,23 +791,23 @@ void Endstops::update() { #endif #endif - #if HAS_Z_MIN && NONE(Z_SPI_SENSORLESS, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) + #if USE_Z_MIN && NONE(Z_SPI_SENSORLESS, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) UPDATE_ENDSTOP_BIT(Z, MIN); #if ENABLED(Z_MULTI_ENDSTOPS) - #if HAS_Z2_MIN + #if USE_Z2_MIN UPDATE_ENDSTOP_BIT(Z2, MIN); #else COPY_LIVE_STATE(Z_MIN, Z2_MIN); #endif #if NUM_Z_STEPPERS >= 3 - #if HAS_Z3_MIN + #if USE_Z3_MIN UPDATE_ENDSTOP_BIT(Z3, MIN); #else COPY_LIVE_STATE(Z_MIN, Z3_MIN); #endif #endif #if NUM_Z_STEPPERS >= 4 - #if HAS_Z4_MIN + #if USE_Z4_MIN UPDATE_ENDSTOP_BIT(Z4, MIN); #else COPY_LIVE_STATE(Z_MIN, Z4_MIN); @@ -822,24 +822,24 @@ void Endstops::update() { UPDATE_ENDSTOP_BIT(Z, TERN(USES_Z_MIN_PROBE_PIN, MIN_PROBE, MIN)); #endif - #if HAS_Z_MAX && !Z_SPI_SENSORLESS + #if USE_Z_MAX && !Z_SPI_SENSORLESS // Check both Z dual endstops #if ENABLED(Z_MULTI_ENDSTOPS) UPDATE_ENDSTOP_BIT(Z, MAX); - #if HAS_Z2_MAX + #if USE_Z2_MAX UPDATE_ENDSTOP_BIT(Z2, MAX); #else COPY_LIVE_STATE(Z_MAX, Z2_MAX); #endif #if NUM_Z_STEPPERS >= 3 - #if HAS_Z3_MAX + #if USE_Z3_MAX UPDATE_ENDSTOP_BIT(Z3, MAX); #else COPY_LIVE_STATE(Z_MAX, Z3_MAX); #endif #endif #if NUM_Z_STEPPERS >= 4 - #if HAS_Z4_MAX + #if USE_Z4_MAX UPDATE_ENDSTOP_BIT(Z4, MAX); #else COPY_LIVE_STATE(Z_MAX, Z4_MAX); @@ -851,7 +851,7 @@ void Endstops::update() { #endif #endif - #if HAS_I_MIN && !I_SPI_SENSORLESS + #if USE_I_MIN && !I_SPI_SENSORLESS #if ENABLED(I_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(I, MIN); #if HAS_I2_MIN @@ -864,7 +864,7 @@ void Endstops::update() { #endif #endif - #if HAS_I_MAX && !I_SPI_SENSORLESS + #if USE_I_MAX && !I_SPI_SENSORLESS #if ENABLED(I_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(I, MAX); #if HAS_I2_MAX @@ -877,7 +877,7 @@ void Endstops::update() { #endif #endif - #if HAS_J_MIN && !J_SPI_SENSORLESS + #if USE_J_MIN && !J_SPI_SENSORLESS #if ENABLED(J_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(J, MIN); #if HAS_J2_MIN @@ -890,7 +890,7 @@ void Endstops::update() { #endif #endif - #if HAS_J_MAX && !J_SPI_SENSORLESS + #if USE_J_MAX && !J_SPI_SENSORLESS #if ENABLED(J_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(J, MAX); #if HAS_J2_MAX @@ -903,7 +903,7 @@ void Endstops::update() { #endif #endif - #if HAS_K_MIN && !K_SPI_SENSORLESS + #if USE_K_MIN && !K_SPI_SENSORLESS #if ENABLED(K_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(K, MIN); #if HAS_K2_MIN @@ -916,7 +916,7 @@ void Endstops::update() { #endif #endif - #if HAS_K_MAX && !K_SPI_SENSORLESS + #if USE_K_MAX && !K_SPI_SENSORLESS #if ENABLED(K_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(K, MAX); #if HAS_K2_MAX @@ -929,7 +929,7 @@ void Endstops::update() { #endif #endif - #if HAS_U_MIN && !U_SPI_SENSORLESS + #if USE_U_MIN && !U_SPI_SENSORLESS #if ENABLED(U_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(U, MIN); #if HAS_U2_MIN @@ -942,7 +942,7 @@ void Endstops::update() { #endif #endif - #if HAS_U_MAX && !U_SPI_SENSORLESS + #if USE_U_MAX && !U_SPI_SENSORLESS #if ENABLED(U_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(U, MAX); #if HAS_U2_MAX @@ -955,7 +955,7 @@ void Endstops::update() { #endif #endif - #if HAS_V_MIN && !V_SPI_SENSORLESS + #if USE_V_MIN && !V_SPI_SENSORLESS #if ENABLED(V_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(V, MIN); #if HAS_V2_MIN @@ -967,7 +967,7 @@ void Endstops::update() { UPDATE_ENDSTOP_BIT(V, MIN); #endif #endif - #if HAS_V_MAX && !V_SPI_SENSORLESS + #if USE_V_MAX && !V_SPI_SENSORLESS #if ENABLED(O_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(V, MAX); #if HAS_V2_MAX @@ -980,7 +980,7 @@ void Endstops::update() { #endif #endif - #if HAS_W_MIN && !W_SPI_SENSORLESS + #if USE_W_MIN && !W_SPI_SENSORLESS #if ENABLED(W_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(W, MIN); #if HAS_W2_MIN @@ -992,7 +992,7 @@ void Endstops::update() { UPDATE_ENDSTOP_BIT(W, MIN); #endif #endif - #if HAS_W_MAX && !W_SPI_SENSORLESS + #if USE_W_MAX && !W_SPI_SENSORLESS #if ENABLED(W_DUAL_ENDSTOPS) UPDATE_ENDSTOP_BIT(W, MAX); #if HAS_W2_MAX @@ -1111,7 +1111,7 @@ void Endstops::update() { G38_did_trigger = true; #define _G38_SET(Q) | (stepper.axis_is_moving(_AXIS(Q)) << _AXIS(Q)) #define _G38_RESP(Q) if (moving[_AXIS(Q)]) { _ENDSTOP_HIT(Q, ENDSTOP); planner.endstop_triggered(_AXIS(Q)); } - const Flags moving = { value_t(NUM_AXES)(0 MAIN_AXIS_MAP(_G38_SET)) }; + const Flags moving = { uvalue_t(NUM_AXES)(0 MAIN_AXIS_MAP(_G38_SET)) }; MAIN_AXIS_MAP(_G38_RESP); } #endif @@ -1120,7 +1120,7 @@ void Endstops::update() { if (stepper.axis_is_moving(X_AXIS)) { if (stepper.motor_direction(X_AXIS_HEAD)) { // -direction - #if HAS_X_MIN || (X_SPI_SENSORLESS && X_HOME_TO_MIN) + #if USE_X_MIN || (X_SPI_SENSORLESS && X_HOME_TO_MIN) PROCESS_ENDSTOP_X(MIN); #if CORE_DIAG(XY, Y, MIN) PROCESS_CORE_ENDSTOP(Y,MIN,X,MIN); @@ -1134,7 +1134,7 @@ void Endstops::update() { #endif } else { // +direction - #if HAS_X_MAX || (X_SPI_SENSORLESS && X_HOME_TO_MAX) + #if USE_X_MAX || (X_SPI_SENSORLESS && X_HOME_TO_MAX) PROCESS_ENDSTOP_X(MAX); #if CORE_DIAG(XY, Y, MIN) PROCESS_CORE_ENDSTOP(Y,MIN,X,MAX); @@ -1152,7 +1152,7 @@ void Endstops::update() { #if HAS_Y_AXIS if (stepper.axis_is_moving(Y_AXIS)) { if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction - #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_TO_MIN) + #if USE_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_TO_MIN) PROCESS_ENDSTOP_Y(MIN); #if CORE_DIAG(XY, X, MIN) PROCESS_CORE_ENDSTOP(X,MIN,Y,MIN); @@ -1166,7 +1166,7 @@ void Endstops::update() { #endif } else { // +direction - #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_TO_MAX) + #if USE_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_TO_MAX) PROCESS_ENDSTOP_Y(MAX); #if CORE_DIAG(XY, X, MIN) PROCESS_CORE_ENDSTOP(X,MIN,Y,MAX); @@ -1186,7 +1186,7 @@ void Endstops::update() { if (stepper.axis_is_moving(Z_AXIS)) { if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up. - #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_TO_MIN) + #if USE_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_TO_MIN) if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled) && TERN1(USES_Z_MIN_PROBE_PIN, !z_probe_enabled) ) PROCESS_ENDSTOP_Z(MIN); @@ -1207,7 +1207,7 @@ void Endstops::update() { #endif } else { // Z +direction. Gantry up, bed down. - #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_TO_MAX) + #if USE_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_TO_MAX) #if ENABLED(Z_MULTI_ENDSTOPS) PROCESS_ENDSTOP_Z(MAX); #elif TERN1(USES_Z_MIN_PROBE_PIN, Z_MAX_PIN != Z_MIN_PROBE_PIN) // No probe or probe is Z_MIN || Probe is not Z_MAX @@ -1230,12 +1230,12 @@ void Endstops::update() { #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) + #if USE_I_MIN || (I_SPI_SENSORLESS && I_HOME_TO_MIN) PROCESS_ENDSTOP(I, MIN); #endif } else { // +direction - #if HAS_I_MAX || (I_SPI_SENSORLESS && I_HOME_TO_MAX) + #if USE_I_MAX || (I_SPI_SENSORLESS && I_HOME_TO_MAX) PROCESS_ENDSTOP(I, MAX); #endif } @@ -1245,12 +1245,12 @@ void Endstops::update() { #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) + #if USE_J_MIN || (J_SPI_SENSORLESS && J_HOME_TO_MIN) PROCESS_ENDSTOP(J, MIN); #endif } else { // +direction - #if HAS_J_MAX || (J_SPI_SENSORLESS && J_HOME_TO_MAX) + #if USE_J_MAX || (J_SPI_SENSORLESS && J_HOME_TO_MAX) PROCESS_ENDSTOP(J, MAX); #endif } @@ -1260,12 +1260,12 @@ void Endstops::update() { #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) + #if USE_K_MIN || (K_SPI_SENSORLESS && K_HOME_TO_MIN) PROCESS_ENDSTOP(K, MIN); #endif } else { // +direction - #if HAS_K_MAX || (K_SPI_SENSORLESS && K_HOME_TO_MAX) + #if USE_K_MAX || (K_SPI_SENSORLESS && K_HOME_TO_MAX) PROCESS_ENDSTOP(K, MAX); #endif } @@ -1275,12 +1275,12 @@ void Endstops::update() { #if HAS_U_AXIS if (stepper.axis_is_moving(U_AXIS)) { if (stepper.motor_direction(U_AXIS_HEAD)) { // -direction - #if HAS_U_MIN || (U_SPI_SENSORLESS && U_HOME_TO_MIN) + #if USE_U_MIN || (U_SPI_SENSORLESS && U_HOME_TO_MIN) PROCESS_ENDSTOP(U, MIN); #endif } else { // +direction - #if HAS_U_MAX || (U_SPI_SENSORLESS && U_HOME_TO_MAX) + #if USE_U_MAX || (U_SPI_SENSORLESS && U_HOME_TO_MAX) PROCESS_ENDSTOP(U, MAX); #endif } @@ -1290,12 +1290,12 @@ void Endstops::update() { #if HAS_V_AXIS if (stepper.axis_is_moving(V_AXIS)) { if (stepper.motor_direction(V_AXIS_HEAD)) { // -direction - #if HAS_V_MIN || (V_SPI_SENSORLESS && V_HOME_TO_MIN) + #if USE_V_MIN || (V_SPI_SENSORLESS && V_HOME_TO_MIN) PROCESS_ENDSTOP(V, MIN); #endif } else { // +direction - #if HAS_V_MAX || (V_SPI_SENSORLESS && V_HOME_TO_MAX) + #if USE_V_MAX || (V_SPI_SENSORLESS && V_HOME_TO_MAX) PROCESS_ENDSTOP(V, MAX); #endif } @@ -1305,12 +1305,12 @@ void Endstops::update() { #if HAS_W_AXIS if (stepper.axis_is_moving(W_AXIS)) { if (stepper.motor_direction(W_AXIS_HEAD)) { // -direction - #if HAS_W_MIN || (W_SPI_SENSORLESS && W_HOME_TO_MIN) + #if USE_W_MIN || (W_SPI_SENSORLESS && W_HOME_TO_MIN) PROCESS_ENDSTOP(W, MIN); #endif } else { // +direction - #if HAS_W_MAX || (W_SPI_SENSORLESS && W_HOME_TO_MAX) + #if USE_W_MAX || (W_SPI_SENSORLESS && W_HOME_TO_MAX) PROCESS_ENDSTOP(W, MAX); #endif } @@ -1382,11 +1382,11 @@ void Endstops::update() { void Endstops::clear_endstop_state() { TERN_(X_SPI_SENSORLESS, CBI(live_state, X_ENDSTOP)); - #if BOTH(X_SPI_SENSORLESS, X_DUAL_ENDSTOPS) + #if ALL(X_SPI_SENSORLESS, X_DUAL_ENDSTOPS) CBI(live_state, X2_ENDSTOP); #endif TERN_(Y_SPI_SENSORLESS, CBI(live_state, Y_ENDSTOP)); - #if BOTH(Y_SPI_SENSORLESS, Y_DUAL_ENDSTOPS) + #if ALL(Y_SPI_SENSORLESS, Y_DUAL_ENDSTOPS) CBI(live_state, Y2_ENDSTOP); #endif TERN_(Z_SPI_SENSORLESS, CBI(live_state, Z_ENDSTOP)); @@ -1421,183 +1421,183 @@ void Endstops::update() { #define ES_GET_STATE(S) if (READ_ENDSTOP(S##_PIN)) SBI(live_state_local, S) - #if HAS_X_MIN + #if USE_X_MIN ES_GET_STATE(X_MIN); #endif - #if HAS_X_MAX + #if USE_X_MAX ES_GET_STATE(X_MAX); #endif - #if HAS_Y_MIN + #if USE_Y_MIN ES_GET_STATE(Y_MIN); #endif - #if HAS_Y_MAX + #if USE_Y_MAX ES_GET_STATE(Y_MAX); #endif - #if HAS_Z_MIN + #if USE_Z_MIN ES_GET_STATE(Z_MIN); #endif - #if HAS_Z_MAX + #if USE_Z_MAX ES_GET_STATE(Z_MAX); #endif #if HAS_Z_MIN_PROBE_PIN ES_GET_STATE(Z_MIN_PROBE); #endif - #if HAS_X2_MIN + #if USE_X2_MIN ES_GET_STATE(X2_MIN); #endif - #if HAS_X2_MAX + #if USE_X2_MAX ES_GET_STATE(X2_MAX); #endif - #if HAS_Y2_MIN + #if USE_Y2_MIN ES_GET_STATE(Y2_MIN); #endif - #if HAS_Y2_MAX + #if USE_Y2_MAX ES_GET_STATE(Y2_MAX); #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN ES_GET_STATE(Z2_MIN); #endif - #if HAS_Z2_MAX + #if USE_Z2_MAX ES_GET_STATE(Z2_MAX); #endif - #if HAS_Z3_MIN + #if USE_Z3_MIN ES_GET_STATE(Z3_MIN); #endif - #if HAS_Z3_MAX + #if USE_Z3_MAX ES_GET_STATE(Z3_MAX); #endif - #if HAS_Z4_MIN + #if USE_Z4_MIN ES_GET_STATE(Z4_MIN); #endif - #if HAS_Z4_MAX + #if USE_Z4_MAX ES_GET_STATE(Z4_MAX); #endif - #if HAS_I_MAX + #if USE_I_MAX ES_GET_STATE(I_MAX); #endif - #if HAS_I_MIN + #if USE_I_MIN ES_GET_STATE(I_MIN); #endif - #if HAS_J_MAX + #if USE_J_MAX ES_GET_STATE(J_MAX); #endif - #if HAS_J_MIN + #if USE_J_MIN ES_GET_STATE(J_MIN); #endif - #if HAS_K_MAX + #if USE_K_MAX ES_GET_STATE(K_MAX); #endif - #if HAS_K_MIN + #if USE_K_MIN ES_GET_STATE(K_MIN); #endif - #if HAS_U_MAX + #if USE_U_MAX ES_GET_STATE(U_MAX); #endif - #if HAS_U_MIN + #if USE_U_MIN ES_GET_STATE(U_MIN); #endif - #if HAS_V_MAX + #if USE_V_MAX ES_GET_STATE(V_MAX); #endif - #if HAS_V_MIN + #if USE_V_MIN ES_GET_STATE(V_MIN); #endif - #if HAS_W_MAX + #if USE_W_MAX ES_GET_STATE(W_MAX); #endif - #if HAS_W_MIN + #if USE_W_MIN ES_GET_STATE(W_MIN); #endif - uint16_t endstop_change = live_state_local ^ old_live_state_local; + const uint16_t endstop_change = live_state_local ^ old_live_state_local; #define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPGM(" " STRINGIFY(S) ":", TEST(live_state_local, S)) if (endstop_change) { - #if HAS_X_MIN + #if USE_X_MIN ES_REPORT_CHANGE(X_MIN); #endif - #if HAS_X_MAX + #if USE_X_MAX ES_REPORT_CHANGE(X_MAX); #endif - #if HAS_Y_MIN + #if USE_Y_MIN ES_REPORT_CHANGE(Y_MIN); #endif - #if HAS_Y_MAX + #if USE_Y_MAX ES_REPORT_CHANGE(Y_MAX); #endif - #if HAS_Z_MIN + #if USE_Z_MIN ES_REPORT_CHANGE(Z_MIN); #endif - #if HAS_Z_MAX + #if USE_Z_MAX ES_REPORT_CHANGE(Z_MAX); #endif #if HAS_Z_MIN_PROBE_PIN ES_REPORT_CHANGE(Z_MIN_PROBE); #endif - #if HAS_X2_MIN + #if USE_X2_MIN ES_REPORT_CHANGE(X2_MIN); #endif - #if HAS_X2_MAX + #if USE_X2_MAX ES_REPORT_CHANGE(X2_MAX); #endif - #if HAS_Y2_MIN + #if USE_Y2_MIN ES_REPORT_CHANGE(Y2_MIN); #endif - #if HAS_Y2_MAX + #if USE_Y2_MAX ES_REPORT_CHANGE(Y2_MAX); #endif - #if HAS_Z2_MIN + #if USE_Z2_MIN ES_REPORT_CHANGE(Z2_MIN); #endif - #if HAS_Z2_MAX + #if USE_Z2_MAX ES_REPORT_CHANGE(Z2_MAX); #endif - #if HAS_Z3_MIN + #if USE_Z3_MIN ES_REPORT_CHANGE(Z3_MIN); #endif - #if HAS_Z3_MAX + #if USE_Z3_MAX ES_REPORT_CHANGE(Z3_MAX); #endif - #if HAS_Z4_MIN + #if USE_Z4_MIN ES_REPORT_CHANGE(Z4_MIN); #endif - #if HAS_Z4_MAX + #if USE_Z4_MAX ES_REPORT_CHANGE(Z4_MAX); #endif - #if HAS_I_MIN + #if USE_I_MIN ES_REPORT_CHANGE(I_MIN); #endif - #if HAS_I_MAX + #if USE_I_MAX ES_REPORT_CHANGE(I_MAX); #endif - #if HAS_J_MIN + #if USE_J_MIN ES_REPORT_CHANGE(J_MIN); #endif - #if HAS_J_MAX + #if USE_J_MAX ES_REPORT_CHANGE(J_MAX); #endif - #if HAS_K_MIN + #if USE_K_MIN ES_REPORT_CHANGE(K_MIN); #endif - #if HAS_K_MAX + #if USE_K_MAX ES_REPORT_CHANGE(K_MAX); #endif - #if HAS_U_MIN + #if USE_U_MIN ES_REPORT_CHANGE(U_MIN); #endif - #if HAS_U_MAX + #if USE_U_MAX ES_REPORT_CHANGE(U_MAX); #endif - #if HAS_V_MIN + #if USE_V_MIN ES_REPORT_CHANGE(V_MIN); #endif - #if HAS_V_MAX + #if USE_V_MAX ES_REPORT_CHANGE(V_MAX); #endif - #if HAS_W_MIN + #if USE_W_MIN ES_REPORT_CHANGE(W_MIN); #endif - #if HAS_W_MAX + #if USE_W_MAX ES_REPORT_CHANGE(W_MAX); #endif diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 20e258f65255..e79646ccb078 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -31,46 +31,64 @@ #define __ES_ITEM(N) N, #define _ES_ITEM(K,N) TERN_(K,DEFER4(__ES_ITEM)(N)) +/** + * Basic Endstop Flag Bits: + * - Each axis with an endstop gets a flag for its homing direction. + * (The use of "MIN" or "MAX" makes it easier to pair with similarly-named endstop pins.) + * - Bed probes with a single pin get a Z_MIN_PROBE flag. This includes Sensorless Z Probe. + * + * Extended Flag Bits: + * - Multi-stepper axes may have multi-endstops such as X2_MIN, Y2_MAX, etc. + * - DELTA gets X_MAX, Y_MAX, and Z_MAX corresponding to its "A", "B", "C" towers. + * - For DUAL_X_CARRIAGE the X axis has both X_MIN and X_MAX flags. + * - The Z axis may have both MIN and MAX when homing to MAX and the probe is Z_MIN. + * - DELTA Sensorless Probe uses X/Y/Z_MAX but sets the Z_MIN flag. + * + * Endstop Flag Bit Aliases: + * - Each *_MIN or *_MAX flag is aliased to *_ENDSTOP. + * - Z_MIN_PROBE is an alias to Z_MIN when the Z_MIN_PIN is being used as the probe pin. + * - When homing with the probe Z_ENDSTOP is a Z_MIN_PROBE alias, otherwise a Z_MIN/MAX alias. + */ enum EndstopEnum : char { // Common XYZ (ABC) endstops. Defined according to USE_[XYZ](MIN|MAX)_PLUG settings. - _ES_ITEM(HAS_X_MIN, X_MIN) - _ES_ITEM(HAS_X_MAX, X_MAX) - _ES_ITEM(HAS_Y_MIN, Y_MIN) - _ES_ITEM(HAS_Y_MAX, Y_MAX) - _ES_ITEM(HAS_Z_MIN, Z_MIN) - _ES_ITEM(HAS_Z_MAX, Z_MAX) - _ES_ITEM(HAS_I_MIN, I_MIN) - _ES_ITEM(HAS_I_MAX, I_MAX) - _ES_ITEM(HAS_J_MIN, J_MIN) - _ES_ITEM(HAS_J_MAX, J_MAX) - _ES_ITEM(HAS_K_MIN, K_MIN) - _ES_ITEM(HAS_K_MAX, K_MAX) - _ES_ITEM(HAS_U_MIN, U_MIN) - _ES_ITEM(HAS_U_MAX, U_MAX) - _ES_ITEM(HAS_V_MIN, V_MIN) - _ES_ITEM(HAS_V_MAX, V_MAX) - _ES_ITEM(HAS_W_MIN, W_MIN) - _ES_ITEM(HAS_W_MAX, W_MAX) + _ES_ITEM(USE_X_MIN, X_MIN) + _ES_ITEM(USE_X_MAX, X_MAX) + _ES_ITEM(USE_Y_MIN, Y_MIN) + _ES_ITEM(USE_Y_MAX, Y_MAX) + _ES_ITEM(USE_Z_MIN, Z_MIN) + _ES_ITEM(USE_Z_MAX, Z_MAX) + _ES_ITEM(USE_I_MIN, I_MIN) + _ES_ITEM(USE_I_MAX, I_MAX) + _ES_ITEM(USE_J_MIN, J_MIN) + _ES_ITEM(USE_J_MAX, J_MAX) + _ES_ITEM(USE_K_MIN, K_MIN) + _ES_ITEM(USE_K_MAX, K_MAX) + _ES_ITEM(USE_U_MIN, U_MIN) + _ES_ITEM(USE_U_MAX, U_MAX) + _ES_ITEM(USE_V_MIN, V_MIN) + _ES_ITEM(USE_V_MAX, V_MAX) + _ES_ITEM(USE_W_MIN, W_MIN) + _ES_ITEM(USE_W_MAX, W_MAX) // Extra Endstops for XYZ #if ENABLED(X_DUAL_ENDSTOPS) - _ES_ITEM(HAS_X_MIN, X2_MIN) - _ES_ITEM(HAS_X_MAX, X2_MAX) + _ES_ITEM(USE_X_MIN, X2_MIN) + _ES_ITEM(USE_X_MAX, X2_MAX) #endif #if ENABLED(Y_DUAL_ENDSTOPS) - _ES_ITEM(HAS_Y_MIN, Y2_MIN) - _ES_ITEM(HAS_Y_MAX, Y2_MAX) + _ES_ITEM(USE_Y_MIN, Y2_MIN) + _ES_ITEM(USE_Y_MAX, Y2_MAX) #endif #if ENABLED(Z_MULTI_ENDSTOPS) - _ES_ITEM(HAS_Z_MIN, Z2_MIN) - _ES_ITEM(HAS_Z_MAX, Z2_MAX) + _ES_ITEM(USE_Z_MIN, Z2_MIN) + _ES_ITEM(USE_Z_MAX, Z2_MAX) #if NUM_Z_STEPPERS >= 3 - _ES_ITEM(HAS_Z_MIN, Z3_MIN) - _ES_ITEM(HAS_Z_MAX, Z3_MAX) + _ES_ITEM(USE_Z_MIN, Z3_MIN) + _ES_ITEM(USE_Z_MAX, Z3_MAX) #endif #if NUM_Z_STEPPERS >= 4 - _ES_ITEM(HAS_Z_MIN, Z4_MIN) - _ES_ITEM(HAS_Z_MAX, Z4_MAX) + _ES_ITEM(USE_Z_MIN, Z4_MIN) + _ES_ITEM(USE_Z_MAX, Z4_MAX) #endif #endif @@ -83,28 +101,28 @@ enum EndstopEnum : char { NUM_ENDSTOP_STATES // Endstops can be either MIN or MAX but not both - #if HAS_X_MIN || HAS_X_MAX + #if USE_X_MIN || USE_X_MAX , X_ENDSTOP = TERN(X_HOME_TO_MAX, X_MAX, X_MIN) #if ENABLED(X_DUAL_ENDSTOPS) , X2_ENDSTOP = TERN(X_HOME_TO_MAX, X2_MAX, X2_MIN) #endif #endif - #if HAS_Y_MIN || HAS_Y_MAX + #if USE_Y_MIN || USE_Y_MAX , Y_ENDSTOP = TERN(Y_HOME_TO_MAX, Y_MAX, Y_MIN) #if ENABLED(Y_DUAL_ENDSTOPS) , Y2_ENDSTOP = TERN(Y_HOME_TO_MAX, Y2_MAX, Y2_MIN) #endif #endif - #if HAS_Z_MIN || HAS_Z_MAX || HOMING_Z_WITH_PROBE + #if USE_Z_MIN || USE_Z_MAX || HOMING_Z_WITH_PROBE , Z_ENDSTOP = TERN(HOMING_Z_WITH_PROBE, Z_MIN_PROBE, TERN(Z_HOME_TO_MAX, Z_MAX, Z_MIN)) #endif - #if HAS_I_MIN || HAS_I_MAX + #if USE_I_MIN || USE_I_MAX , I_ENDSTOP = TERN(I_HOME_TO_MAX, I_MAX, I_MIN) #endif - #if HAS_J_MIN || HAS_J_MAX + #if USE_J_MIN || USE_J_MAX , J_ENDSTOP = TERN(J_HOME_TO_MAX, J_MAX, J_MIN) #endif - #if HAS_K_MIN || HAS_K_MAX + #if USE_K_MIN || USE_K_MAX , K_ENDSTOP = TERN(K_HOME_TO_MAX, K_MAX, K_MIN) #endif }; @@ -115,7 +133,7 @@ enum EndstopEnum : char { class Endstops { public: - typedef IF<(NUM_ENDSTOP_STATES > 8), uint16_t, uint8_t>::type endstop_mask_t; + typedef bits_t(NUM_ENDSTOP_STATES) endstop_mask_t; #if ENABLED(X_DUAL_ENDSTOPS) static float x2_endstop_adj; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 51081f5165fb..a4dcd7e0e57a 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -191,22 +191,24 @@ inline void report_more_positions() { // Report the logical position for a given machine position inline void report_logical_position(const xyze_pos_t &rpos) { const xyze_pos_t lpos = rpos.asLogical(); - SERIAL_ECHOPGM_P( - LIST_N(DOUBLE(NUM_AXES), - 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, - SP_U_LBL, lpos.u, - SP_V_LBL, lpos.v, - SP_W_LBL, lpos.w - ) - #if HAS_EXTRUDERS - , SP_E_LBL, lpos.e - #endif - ); + #if NUM_AXES + SERIAL_ECHOPGM_P( + LIST_N(DOUBLE(NUM_AXES), + 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, + SP_U_LBL, lpos.u, + SP_V_LBL, lpos.v, + SP_W_LBL, lpos.w + ) + ); + #endif + #if HAS_EXTRUDERS + SERIAL_ECHOPGM_P(SP_E_LBL, lpos.e); + #endif } // Report the real current position according to the steppers. @@ -247,7 +249,7 @@ void report_current_position_projected() { AutoReporter position_auto_reporter; #endif -#if EITHER(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS) +#if ANY(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS) M_StateEnum M_State_grbl = M_INIT; @@ -354,7 +356,7 @@ void report_current_position_projected() { #else // CARTESIAN // Return true if the given position is within the machine bounds. - bool position_is_reachable(const_float_t rx, const_float_t ry) { + bool position_is_reachable(TERN_(HAS_X_AXIS, const_float_t rx) OPTARG(HAS_Y_AXIS, const_float_t ry)) { if (TERN0(HAS_Y_AXIS, !COORDINATE_OKAY(ry, Y_MIN_POS - fslop, Y_MAX_POS + fslop))) return false; #if ENABLED(DUAL_X_CARRIAGE) if (active_extruder) @@ -362,13 +364,13 @@ void report_current_position_projected() { else return COORDINATE_OKAY(rx, X1_MIN_POS - fslop, X1_MAX_POS + fslop); #else - return COORDINATE_OKAY(rx, X_MIN_POS - fslop, X_MAX_POS + fslop); + if (TERN0(HAS_X_AXIS, !COORDINATE_OKAY(rx, X_MIN_POS - fslop, X_MAX_POS + fslop))) return false; + return true; #endif } #endif // CARTESIAN - void home_if_needed(const bool keeplev/*=false*/) { if (!all_axes_trusted()) gcode.home_all_axes(keeplev); } @@ -516,27 +518,32 @@ void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) { void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ OPTARG(IS_KINEMATIC, const bool is_fast/*=false*/) ) { - const feedRate_t old_feedrate = feedrate_mm_s; - if (fr_mm_s) feedrate_mm_s = fr_mm_s; - - const uint16_t old_pct = feedrate_percentage; - feedrate_percentage = 100; - - #if HAS_EXTRUDERS - const float old_fac = planner.e_factor[active_extruder]; - planner.e_factor[active_extruder] = 1.0f; - #endif + REMEMBER(fr, feedrate_mm_s); + REMEMBER(pct, feedrate_percentage, 100); + TERN_(HAS_EXTRUDERS, REMEMBER(fac, planner.e_factor[active_extruder], 1.0f)); + if (fr_mm_s) feedrate_mm_s = fr_mm_s; if (TERN0(IS_KINEMATIC, is_fast)) TERN(IS_KINEMATIC, prepare_fast_move_to_destination(), NOOP); else prepare_line_to_destination(); - - feedrate_mm_s = old_feedrate; - feedrate_percentage = old_pct; - TERN_(HAS_EXTRUDERS, planner.e_factor[active_extruder] = old_fac); } +#if SECONDARY_AXES + + void secondary_axis_moves(SECONDARY_AXIS_ARGS(const_float_t), const_feedRate_t fr_mm_s) { + auto move_one = [&](const AxisEnum a, const_float_t p) { + const feedRate_t fr = fr_mm_s ?: homing_feedrate(a); + current_position[a] = p; line_to_current_position(fr); + }; + SECONDARY_AXIS_CODE( + move_one(I_AXIS, i), move_one(J_AXIS, j), move_one(K_AXIS, k), + move_one(U_AXIS, u), move_one(V_AXIS, v), move_one(W_AXIS, w) + ); + } + +#endif + /** * Plan a move to (X, Y, Z, [I, [J, [K...]]]) and set the current_position * Plan a move to (X, Y, Z, [I, [J, [K...]]]) with separation of Z from other components. @@ -546,23 +553,17 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ * - Delta may lower Z first to get into the free motion zone. * - Before returning, wait for the planner buffer to empty. */ -void do_blocking_move_to(NUM_AXIS_ARGS(const_float_t), const_feedRate_t fr_mm_s/*=0.0f*/) { +void do_blocking_move_to(NUM_AXIS_ARGS_(const_float_t) const_feedRate_t fr_mm_s/*=0.0f*/) { DEBUG_SECTION(log_move, "do_blocking_move_to", DEBUGGING(LEVELING)); - if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", NUM_AXIS_ARGS()); + #if NUM_AXES + if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", NUM_AXIS_ARGS()); + #endif const feedRate_t xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S); #if HAS_Z_AXIS const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS); #endif - SECONDARY_AXIS_CODE( - const feedRate_t i_feedrate = fr_mm_s ?: homing_feedrate(I_AXIS), - const feedRate_t j_feedrate = fr_mm_s ?: homing_feedrate(J_AXIS), - const feedRate_t k_feedrate = fr_mm_s ?: homing_feedrate(K_AXIS), - const feedRate_t u_feedrate = fr_mm_s ?: homing_feedrate(U_AXIS), - const feedRate_t v_feedrate = fr_mm_s ?: homing_feedrate(V_AXIS), - const feedRate_t w_feedrate = fr_mm_s ?: homing_feedrate(W_AXIS) - ); #if IS_KINEMATIC && DISABLED(POLARGRAPH) // kinematic machines are expected to home to a point 1.5x their range? never reachable. @@ -605,6 +606,10 @@ void do_blocking_move_to(NUM_AXIS_ARGS(const_float_t), const_feedRate_t fr_mm_s/ if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position); } + #if SECONDARY_AXES + secondary_axis_moves(SECONDARY_AXIS_LIST(i, j, k, u, v, w), fr_mm_s); + #endif + #elif IS_SCARA // If Z needs to raise, do it before moving XY @@ -612,6 +617,10 @@ void do_blocking_move_to(NUM_AXIS_ARGS(const_float_t), const_feedRate_t fr_mm_s/ destination.set(x, y); prepare_internal_fast_move_to_destination(xy_feedrate); + #if SECONDARY_AXES + secondary_axis_moves(SECONDARY_AXIS_LIST(i, j, k, u, v, w), fr_mm_s); + #endif + // If Z needs to lower, do it after moving XY if (destination.z > z) { destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); } @@ -621,25 +630,10 @@ void do_blocking_move_to(NUM_AXIS_ARGS(const_float_t), const_feedRate_t fr_mm_s/ if (current_position.z < z) { current_position.z = z; line_to_current_position(z_feedrate); } #endif - current_position.set(x OPTARG(HAS_Y_AXIS, y)); line_to_current_position(xy_feedrate); + current_position.set(TERN_(HAS_X_AXIS, x) OPTARG(HAS_Y_AXIS, y)); line_to_current_position(xy_feedrate); - #if HAS_I_AXIS - current_position.i = i; line_to_current_position(i_feedrate); - #endif - #if HAS_J_AXIS - current_position.j = j; line_to_current_position(j_feedrate); - #endif - #if HAS_K_AXIS - current_position.k = k; line_to_current_position(k_feedrate); - #endif - #if HAS_U_AXIS - current_position.u = u; line_to_current_position(u_feedrate); - #endif - #if HAS_V_AXIS - current_position.v = v; line_to_current_position(v_feedrate); - #endif - #if HAS_W_AXIS - current_position.w = w; line_to_current_position(w_feedrate); + #if SECONDARY_AXES + secondary_axis_moves(SECONDARY_AXIS_LIST(i, j, k, u, v, w), fr_mm_s); #endif #if HAS_Z_AXIS @@ -653,28 +647,33 @@ void do_blocking_move_to(NUM_AXIS_ARGS(const_float_t), const_feedRate_t fr_mm_s/ } void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(NUM_AXIS_LIST(raw.x, raw.y, current_position.z, current_position.i, current_position.j, current_position.k, - current_position.u, current_position.v, current_position.w), fr_mm_s); + do_blocking_move_to(NUM_AXIS_LIST_(raw.x, raw.y, current_position.z, current_position.i, current_position.j, current_position.k, + current_position.u, current_position.v, current_position.w) fr_mm_s); } void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(NUM_AXIS_ELEM(raw), fr_mm_s); + do_blocking_move_to(NUM_AXIS_ELEM_(raw) fr_mm_s); } void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(NUM_AXIS_ELEM(raw), fr_mm_s); -} -void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { - do_blocking_move_to( - NUM_AXIS_LIST(rx, current_position.y, current_position.z, current_position.i, current_position.j, current_position.k, - current_position.u, current_position.v, current_position.w), - fr_mm_s - ); + do_blocking_move_to(NUM_AXIS_ELEM_(raw) fr_mm_s); } +#if HAS_X_AXIS + void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("do_blocking_move_to_x(", rx, ", ", fr_mm_s, ")"); + do_blocking_move_to( + NUM_AXIS_LIST_(rx, current_position.y, current_position.z, current_position.i, current_position.j, current_position.k, + current_position.u, current_position.v, current_position.w) + fr_mm_s + ); + } +#endif + #if HAS_Y_AXIS void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("do_blocking_move_to_y(", ry, ", ", fr_mm_s, ")"); do_blocking_move_to( - NUM_AXIS_LIST(current_position.x, ry, current_position.z, current_position.i, current_position.j, current_position.k, - current_position.u, current_position.v, current_position.w), + NUM_AXIS_LIST_(current_position.x, ry, current_position.z, current_position.i, current_position.j, current_position.k, + current_position.u, current_position.v, current_position.w) fr_mm_s ); } @@ -682,6 +681,7 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { #if HAS_Z_AXIS void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s/*=0.0*/) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("do_blocking_move_to_z(", rz, ", ", fr_mm_s, ")"); do_blocking_move_to_xy_z(current_position, rz, fr_mm_s); } #endif @@ -692,7 +692,7 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { } void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s/*=0.0f*/) { do_blocking_move_to( - NUM_AXIS_LIST(raw.x, raw.y, raw.z, i, raw.j, raw.k, raw.u, raw.v, raw.w), + NUM_AXIS_LIST_(raw.x, raw.y, raw.z, i, raw.j, raw.k, raw.u, raw.v, raw.w) fr_mm_s ); } @@ -704,7 +704,7 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { } void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s/*=0.0f*/) { do_blocking_move_to( - NUM_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, j, raw.k, raw.u, raw.v, raw.w), + NUM_AXIS_LIST_(raw.x, raw.y, raw.z, raw.i, j, raw.k, raw.u, raw.v, raw.w) fr_mm_s ); } @@ -716,7 +716,7 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { } void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s/*=0.0f*/) { do_blocking_move_to( - NUM_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, raw.j, k, raw.u, raw.v, raw.w), + NUM_AXIS_LIST_(raw.x, raw.y, raw.z, raw.i, raw.j, k, raw.u, raw.v, raw.w) fr_mm_s ); } @@ -728,7 +728,7 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { } void do_blocking_move_to_xyzijk_u(const xyze_pos_t &raw, const_float_t u, const_feedRate_t fr_mm_s/*=0.0f*/) { do_blocking_move_to( - NUM_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, raw.j, raw.k, u, raw.v, raw.w), + NUM_AXIS_LIST_(raw.x, raw.y, raw.z, raw.i, raw.j, raw.k, u, raw.v, raw.w) fr_mm_s ); } @@ -740,7 +740,7 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { } void do_blocking_move_to_xyzijku_v(const xyze_pos_t &raw, const_float_t v, const_feedRate_t fr_mm_s/*=0.0f*/) { do_blocking_move_to( - NUM_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, raw.j, raw.k, raw.u, v, raw.w), + NUM_AXIS_LIST_(raw.x, raw.y, raw.z, raw.i, raw.j, raw.k, raw.u, v, raw.w) fr_mm_s ); } @@ -752,7 +752,7 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { } void do_blocking_move_to_xyzijkuv_w(const xyze_pos_t &raw, const_float_t w, const_feedRate_t fr_mm_s/*=0.0f*/) { do_blocking_move_to( - NUM_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, raw.j, raw.k, raw.u, raw.v, w), + NUM_AXIS_LIST_(raw.x, raw.y, raw.z, raw.i, raw.j, raw.k, raw.u, raw.v, w) fr_mm_s ); } @@ -760,9 +760,10 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { #if HAS_Y_AXIS void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("do_blocking_move_to_xy(", rx, ", ", ry, ", ", fr_mm_s, ")"); do_blocking_move_to( - NUM_AXIS_LIST(rx, ry, current_position.z, current_position.i, current_position.j, current_position.k, - current_position.u, current_position.v, current_position.w), + NUM_AXIS_LIST_(rx, ry, current_position.z, current_position.i, current_position.j, current_position.k, + current_position.u, current_position.v, current_position.w) fr_mm_s ); } @@ -774,8 +775,8 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { #if HAS_Z_AXIS void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s/*=0.0f*/) { do_blocking_move_to( - NUM_AXIS_LIST(raw.x, raw.y, z, current_position.i, current_position.j, current_position.k, - current_position.u, current_position.v, current_position.w), + NUM_AXIS_LIST_(raw.x, raw.y, z, current_position.i, current_position.j, current_position.k, + current_position.u, current_position.v, current_position.w) fr_mm_s ); } @@ -784,6 +785,10 @@ void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { if (!lower_allowed) NOLESS(zdest, current_position.z); do_blocking_move_to_z(_MIN(zdest, Z_MAX_POS), TERN(HAS_BED_PROBE, z_probe_fast_mm_s, homing_feedrate(Z_AXIS))); } + void do_z_clearance_by(const_float_t zclear) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("do_z_clearance_by(", zclear, ")"); + do_z_clearance(current_position.z + zclear); + } #endif // @@ -897,7 +902,7 @@ void restore_feedrate_and_scaling() { #endif if (DEBUGGING(LEVELING)) - SERIAL_ECHOLNPGM("Axis ", AS_CHAR(AXIS_CHAR(axis)), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]); + SERIAL_ECHOLNPGM("Axis ", C(AXIS_CHAR(axis)), " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]); } /** @@ -914,7 +919,7 @@ void restore_feedrate_and_scaling() { if (TERN0(DELTA, !all_axes_homed())) return; - #if BOTH(HAS_HOTEND_OFFSET, DELTA) + #if ALL(HAS_HOTEND_OFFSET, DELTA) // The effector center position will be the target minus the hotend offset. const xy_pos_t offs = hotend_offset[active_extruder]; #else @@ -935,14 +940,16 @@ void restore_feedrate_and_scaling() { #else - if (axis_was_homed(X_AXIS)) { - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_X) - NOLESS(target.x, soft_endstop.min.x); - #endif - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_X) - NOMORE(target.x, soft_endstop.max.x); - #endif - } + #if HAS_X_AXIS + if (axis_was_homed(X_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_X) + NOLESS(target.x, soft_endstop.min.x); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_X) + NOMORE(target.x, soft_endstop.max.x); + #endif + } + #endif #if HAS_Y_AXIS if (axis_was_homed(Y_AXIS)) { @@ -1290,13 +1297,13 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { void idex_set_mirrored_mode(const bool mirr) { idex_mirrored_mode = mirr; - stepper.set_directions(); + stepper.apply_directions(); } void set_duplication_enabled(const bool dupe, const int8_t tool_index/*=-1*/) { extruder_duplication_enabled = dupe; if (tool_index >= 0) active_extruder = tool_index; - stepper.set_directions(); + stepper.apply_directions(); } void idex_set_parked(const bool park/*=true*/) { @@ -1342,7 +1349,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { line_to_current_position(fr_zfast); } } - stepper.set_directions(); + stepper.apply_directions(); idex_set_parked(false); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("idex_set_parked(false)"); @@ -1398,15 +1405,11 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { void prepare_line_to_destination() { apply_motion_limits(destination); - #if EITHER(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE) + #if ANY(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE) if (!DEBUGGING(DRYRUN) && destination.e != current_position.e) { - bool ignore_e = false; - - #if ENABLED(PREVENT_COLD_EXTRUSION) - ignore_e = thermalManager.tooColdToExtrude(active_extruder); - if (ignore_e) SERIAL_ECHO_MSG(STR_ERR_COLD_EXTRUDE_STOP); - #endif + bool ignore_e = thermalManager.tooColdToExtrude(active_extruder); + if (ignore_e) SERIAL_ECHO_MSG(STR_ERR_COLD_EXTRUDE_STOP); #if ENABLED(PREVENT_LENGTHY_EXTRUDE) const float e_delta = ABS(destination.e - current_position.e) * planner.e_factor[active_extruder]; @@ -1572,36 +1575,36 @@ void prepare_line_to_destination() { #endif } - #if ENABLED(SPI_ENDSTOPS) - switch (axis) { - case X_AXIS: if (ENABLED(X_SPI_SENSORLESS)) endstops.tmc_spi_homing.x = true; break; - #if HAS_Y_AXIS - case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = true; break; - #endif - #if HAS_Z_AXIS - case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = true; break; - #endif - #if HAS_I_AXIS - case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = true; break; - #endif - #if HAS_J_AXIS - case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = true; break; - #endif - #if HAS_K_AXIS - case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = true; break; - #endif - #if HAS_U_AXIS - case U_AXIS: if (ENABLED(U_SPI_SENSORLESS)) endstops.tmc_spi_homing.u = true; break; - #endif - #if HAS_V_AXIS - case V_AXIS: if (ENABLED(V_SPI_SENSORLESS)) endstops.tmc_spi_homing.v = true; break; - #endif - #if HAS_W_AXIS - case W_AXIS: if (ENABLED(W_SPI_SENSORLESS)) endstops.tmc_spi_homing.w = true; break; - #endif - default: break; - } - #endif + switch (axis) { + #if X_SPI_SENSORLESS + case X_AXIS: endstops.tmc_spi_homing.x = true; break; + #endif + #if Y_SPI_SENSORLESS + case Y_AXIS: endstops.tmc_spi_homing.y = true; break; + #endif + #if Z_SPI_SENSORLESS + case Z_AXIS: endstops.tmc_spi_homing.z = true; break; + #endif + #if I_SPI_SENSORLESS + case I_AXIS: endstops.tmc_spi_homing.i = true; break; + #endif + #if J_SPI_SENSORLESS + case J_AXIS: endstops.tmc_spi_homing.j = true; break; + #endif + #if K_SPI_SENSORLESS + case K_AXIS: endstops.tmc_spi_homing.k = true; break; + #endif + #if U_SPI_SENSORLESS + case U_AXIS: endstops.tmc_spi_homing.u = true; break; + #endif + #if V_SPI_SENSORLESS + case V_AXIS: endstops.tmc_spi_homing.v = true; break; + #endif + #if W_SPI_SENSORLESS + case W_AXIS: endstops.tmc_spi_homing.w = true; break; + #endif + default: break; + } TERN_(IMPROVE_HOMING_RELIABILITY, sg_guard_period = millis() + default_sg_guard_duration); @@ -1666,36 +1669,36 @@ void prepare_line_to_destination() { #endif } - #if ENABLED(SPI_ENDSTOPS) - switch (axis) { - case X_AXIS: if (ENABLED(X_SPI_SENSORLESS)) endstops.tmc_spi_homing.x = false; break; - #if HAS_Y_AXIS - case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = false; break; - #endif - #if HAS_Z_AXIS - case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = false; break; - #endif - #if HAS_I_AXIS - case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = false; break; - #endif - #if HAS_J_AXIS - case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = false; break; - #endif - #if HAS_K_AXIS - case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = false; break; - #endif - #if HAS_U_AXIS - case U_AXIS: if (ENABLED(U_SPI_SENSORLESS)) endstops.tmc_spi_homing.u = false; break; - #endif - #if HAS_V_AXIS - case V_AXIS: if (ENABLED(V_SPI_SENSORLESS)) endstops.tmc_spi_homing.v = false; break; - #endif - #if HAS_W_AXIS - case W_AXIS: if (ENABLED(W_SPI_SENSORLESS)) endstops.tmc_spi_homing.w = false; break; - #endif - default: break; - } - #endif + switch (axis) { + #if X_SPI_SENSORLESS + case X_AXIS: endstops.tmc_spi_homing.x = false; break; + #endif + #if Y_SPI_SENSORLESS + case Y_AXIS: endstops.tmc_spi_homing.y = false; break; + #endif + #if Z_SPI_SENSORLESS + case Z_AXIS: endstops.tmc_spi_homing.z = false; break; + #endif + #if I_SPI_SENSORLESS + case I_AXIS: endstops.tmc_spi_homing.i = false; break; + #endif + #if J_SPI_SENSORLESS + case J_AXIS: endstops.tmc_spi_homing.j = false; break; + #endif + #if K_SPI_SENSORLESS + case K_AXIS: endstops.tmc_spi_homing.k = false; break; + #endif + #if U_SPI_SENSORLESS + case U_AXIS: endstops.tmc_spi_homing.u = false; break; + #endif + #if V_SPI_SENSORLESS + case V_AXIS: endstops.tmc_spi_homing.v = false; break; + #endif + #if W_SPI_SENSORLESS + case W_AXIS: endstops.tmc_spi_homing.w = false; break; + #endif + default: break; + } } #endif // SENSORLESS_HOMING @@ -1709,7 +1712,7 @@ void prepare_line_to_destination() { const feedRate_t home_fr_mm_s = fr_mm_s ?: homing_feedrate(axis); if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPGM("...(", AS_CHAR(AXIS_CHAR(axis)), ", ", distance, ", "); + DEBUG_ECHOPGM("...(", C(AXIS_CHAR(axis)), ", ", distance, ", "); if (fr_mm_s) DEBUG_ECHO(fr_mm_s); else @@ -1729,12 +1732,12 @@ void prepare_line_to_destination() { if (is_home_dir) { if (TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS)) { - #if BOTH(HAS_HEATED_BED, WAIT_FOR_BED_HEATER) + #if ALL(HAS_HEATED_BED, WAIT_FOR_BED_HEATER) // Wait for bed to heat back up between probing points thermalManager.wait_for_bed_heating(); #endif - #if BOTH(HAS_HOTEND, WAIT_FOR_HOTEND) + #if ALL(HAS_HOTEND, WAIT_FOR_HOTEND) // Wait for the hotend to heat back up between probing points thermalManager.wait_for_hotend_heating(active_extruder); #endif @@ -1751,7 +1754,7 @@ void prepare_line_to_destination() { #endif } - #if EITHER(MORGAN_SCARA, MP_SCARA) + #if ANY(MORGAN_SCARA, MP_SCARA) // Tell the planner the axis is at 0 current_position[axis] = 0; sync_plan_position(); @@ -1799,12 +1802,12 @@ void prepare_line_to_destination() { * "trusted" position). */ void set_axis_never_homed(const AxisEnum axis) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(">>> set_axis_never_homed(", AS_CHAR(AXIS_CHAR(axis)), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(">>> set_axis_never_homed(", C(AXIS_CHAR(axis)), ")"); set_axis_untrusted(axis); set_axis_unhomed(axis); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< set_axis_never_homed(", AS_CHAR(AXIS_CHAR(axis)), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< set_axis_never_homed(", C(AXIS_CHAR(axis)), ")"); TERN_(I2C_POSITION_ENCODERS, I2CPEM.unhomed(axis)); } @@ -1835,72 +1838,72 @@ void prepare_line_to_destination() { case X_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(X); phaseCurrent = stepperX.get_microstep_counter(); - effectorBackoutDir = -X_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_X_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(X_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_X_DIR, -)(-effectorBackoutDir); break; #endif #ifdef Y_MICROSTEPS case Y_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(Y); phaseCurrent = stepperY.get_microstep_counter(); - effectorBackoutDir = -Y_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_Y_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(Y_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_Y_DIR, -)(-effectorBackoutDir); break; #endif #ifdef Z_MICROSTEPS case Z_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(Z); phaseCurrent = stepperZ.get_microstep_counter(); - effectorBackoutDir = -Z_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_Z_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(Z_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_Z_DIR, -)(-effectorBackoutDir); break; #endif #ifdef I_MICROSTEPS case I_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(I); phaseCurrent = stepperI.get_microstep_counter(); - effectorBackoutDir = -I_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_I_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(I_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_I_DIR, -)(-effectorBackoutDir); break; #endif #ifdef J_MICROSTEPS case J_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(J); phaseCurrent = stepperJ.get_microstep_counter(); - effectorBackoutDir = -J_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_J_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(J_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_J_DIR, -)(-effectorBackoutDir); break; #endif #ifdef K_MICROSTEPS case K_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(K); phaseCurrent = stepperK.get_microstep_counter(); - effectorBackoutDir = -K_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_K_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(K_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_K_DIR, -)(-effectorBackoutDir); break; #endif #ifdef U_MICROSTEPS case U_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(U); phaseCurrent = stepperU.get_microstep_counter(); - effectorBackoutDir = -U_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_U_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(U_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_U_DIR, -)(-effectorBackoutDir); break; #endif #ifdef V_MICROSTEPS case V_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(V); phaseCurrent = stepperV.get_microstep_counter(); - effectorBackoutDir = -V_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_V_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(V_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_V_DIR, -)(-effectorBackoutDir); break; #endif #ifdef W_MICROSTEPS case W_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(W); phaseCurrent = stepperW.get_microstep_counter(); - effectorBackoutDir = -W_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_W_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(W_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_W_DIR, -)(-effectorBackoutDir); break; #endif default: return; @@ -1913,7 +1916,7 @@ void prepare_line_to_destination() { if (ABS(phaseDelta) * planner.mm_per_step[axis] / phasePerUStep < 0.05f) SERIAL_ECHOLNPGM("Selected home phase ", home_phase[axis], " too close to endstop trigger phase ", phaseCurrent, - ". Pick a different phase for ", AS_CHAR(AXIS_CHAR(axis))); + ". Pick a different phase for ", C(AXIS_CHAR(axis))); // Skip to next if target position is behind current. So it only moves away from endstop. if (phaseDelta < 0) phaseDelta += 1024; @@ -1924,7 +1927,7 @@ void prepare_line_to_destination() { // Optional debug messages if (DEBUGGING(LEVELING)) { DEBUG_ECHOLNPGM( - "Endstop ", AS_CHAR(AXIS_CHAR(axis)), " hit at Phase:", phaseCurrent, + "Endstop ", C(AXIS_CHAR(axis)), " hit at Phase:", phaseCurrent, " Delta:", phaseDelta, " Distance:", mmDelta ); } @@ -1949,7 +1952,7 @@ void prepare_line_to_destination() { void homeaxis(const AxisEnum axis) { - #if EITHER(MORGAN_SCARA, MP_SCARA) + #if ANY(MORGAN_SCARA, MP_SCARA) // Only Z homing (with probe) is permitted if (axis != Z_AXIS) { BUZZ(100, 880); return; } #else @@ -1963,7 +1966,7 @@ void prepare_line_to_destination() { if (true MAIN_AXIS_MAP(_ANDCANT)) return; #endif - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(">>> homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(">>> homeaxis(", C(AXIS_CHAR(axis)), ")"); const int axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) ? TOOL_X_HOME_DIR(active_extruder) : home_dir(axis); @@ -2032,12 +2035,12 @@ 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) - if (axis == Z_AXIS && !bltouch.high_speed_mode) bltouch.stow(); // Intermediate STOW (in LOW SPEED MODE) - #endif - // If a second homing move is configured... if (bump) { + #if ALL(HOMING_Z_WITH_PROBE, BLTOUCH) + if (axis == Z_AXIS && !bltouch.high_speed_mode) bltouch.stow(); // Intermediate STOW (in LOW SPEED MODE) + #endif + // Move away from the endstop by the axis HOMING_BUMP_MM if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Move Away: ", -bump, "mm"); do_homing_move(axis, -bump, TERN(HOMING_Z_WITH_PROBE, (axis == Z_AXIS ? z_probe_fast_mm_s : 0), 0), false); @@ -2046,40 +2049,17 @@ void prepare_line_to_destination() { // Check for a broken endstop EndstopEnum es; switch (axis) { - default: - case X_AXIS: es = X_ENDSTOP; break; - #if HAS_Y_AXIS - case Y_AXIS: es = Y_ENDSTOP; break; - #endif - #if HAS_Z_AXIS - case Z_AXIS: es = Z_ENDSTOP; break; - #endif - #if HAS_I_AXIS - case I_AXIS: es = I_ENDSTOP; break; - #endif - #if HAS_J_AXIS - case J_AXIS: es = J_ENDSTOP; break; - #endif - #if HAS_K_AXIS - case K_AXIS: es = K_ENDSTOP; break; - #endif - #if HAS_U_AXIS - case U_AXIS: es = U_ENDSTOP; break; - #endif - #if HAS_V_AXIS - case V_AXIS: es = V_ENDSTOP; break; - #endif - #if HAS_W_AXIS - case W_AXIS: es = W_ENDSTOP; break; - #endif + #define _ESCASE(A) case A##_AXIS: es = A##_ENDSTOP; break; + MAIN_AXIS_MAP(_ESCASE) + default: break; } if (TEST(endstops.state(), es)) { - SERIAL_ECHO_MSG("Bad ", AS_CHAR(AXIS_CHAR(axis)), " Endstop?"); + SERIAL_ECHO_MSG("Bad ", C(AXIS_CHAR(axis)), " Endstop?"); kill(GET_TEXT_F(MSG_KILL_HOMING_FAILED)); } #endif - #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) + #if ALL(HOMING_Z_WITH_PROBE, BLTOUCH) if (axis == Z_AXIS && !bltouch.high_speed_mode && bltouch.deploy()) return; // Intermediate DEPLOY (in LOW SPEED MODE) #endif @@ -2088,12 +2068,12 @@ void prepare_line_to_destination() { const float rebump = bump * 2; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Re-bump: ", rebump, "mm"); do_homing_move(axis, rebump, get_homing_bump_feedrate(axis), true); - - #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) - if (axis == Z_AXIS) bltouch.stow(); // The final STOW - #endif } + #if ALL(HOMING_Z_WITH_PROBE, BLTOUCH) + if (axis == Z_AXIS) bltouch.stow(); // The final STOW + #endif + #if HAS_EXTRA_ENDSTOPS const bool pos_dir = axis_home_dir > 0; #if ENABLED(X_DUAL_ENDSTOPS) @@ -2290,7 +2270,7 @@ void prepare_line_to_destination() { if (axis == Z_AXIS) fwretract.current_hop = 0.0; #endif - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("<<< homeaxis(", C(AXIS_CHAR(axis)), ")"); } // homeaxis() @@ -2315,7 +2295,7 @@ void prepare_line_to_destination() { * Callers must sync the planner position after calling this! */ void set_axis_is_at_home(const AxisEnum axis) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(">>> set_axis_is_at_home(", AS_CHAR(AXIS_CHAR(axis)), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(">>> set_axis_is_at_home(", C(AXIS_CHAR(axis)), ")"); set_axis_trusted(axis); set_axis_homed(axis); @@ -2327,7 +2307,7 @@ void set_axis_is_at_home(const AxisEnum axis) { } #endif - #if EITHER(MORGAN_SCARA, AXEL_TPARA) + #if ANY(MORGAN_SCARA, AXEL_TPARA) scara_set_axis_is_at_home(axis); #elif ENABLED(DELTA) current_position[axis] = (axis == Z_AXIS) ? DIFF_TERN(HAS_BED_PROBE, delta_height, probe.offset.z) : base_home_pos(axis); @@ -2341,15 +2321,10 @@ void set_axis_is_at_home(const AxisEnum axis) { #if HAS_BED_PROBE && Z_HOME_TO_MIN if (axis == Z_AXIS) { #if HOMING_Z_WITH_PROBE - current_position.z -= probe.offset.z; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("*** Z HOMED WITH PROBE (Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) ***\n> probe.offset.z = ", probe.offset.z); - #else - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("*** Z HOMED TO ENDSTOP ***"); - #endif } #endif @@ -2365,17 +2340,17 @@ void set_axis_is_at_home(const AxisEnum axis) { if (DEBUGGING(LEVELING)) { #if HAS_HOME_OFFSET - DEBUG_ECHOLNPGM("> home_offset[", AS_CHAR(AXIS_CHAR(axis)), "] = ", home_offset[axis]); + DEBUG_ECHOLNPGM("> home_offset[", C(AXIS_CHAR(axis)), "] = ", home_offset[axis]); #endif DEBUG_POS("", current_position); - DEBUG_ECHOLNPGM("<<< set_axis_is_at_home(", AS_CHAR(AXIS_CHAR(axis)), ")"); + DEBUG_ECHOLNPGM("<<< set_axis_is_at_home(", C(AXIS_CHAR(axis)), ")"); } } #if HAS_WORKSPACE_OFFSET void update_workspace_offset(const AxisEnum axis) { workspace_offset[axis] = home_offset[axis] + position_shift[axis]; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Axis ", AS_CHAR(AXIS_CHAR(axis)), " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Axis ", C(AXIS_CHAR(axis)), " home_offset = ", home_offset[axis], " position_shift = ", position_shift[axis]); } #endif diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 68cadcc47fc9..b4b7d785d606 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -151,9 +151,9 @@ inline float home_bump_mm(const AxisEnum axis) { extern xyz_pos_t hotend_offset[HOTENDS]; void reset_hotend_offsets(); #elif HOTENDS - constexpr xyz_pos_t hotend_offset[HOTENDS] = { { 0 } }; + constexpr xyz_pos_t hotend_offset[HOTENDS] = { { TERN_(HAS_X_AXIS, 0) } }; #else - constexpr xyz_pos_t hotend_offset[1] = { { 0 } }; + constexpr xyz_pos_t hotend_offset[1] = { { TERN_(HAS_X_AXIS, 0) } }; #endif #if HAS_SOFTWARE_ENDSTOPS @@ -167,10 +167,12 @@ inline float home_bump_mm(const AxisEnum axis) { amin = -100000; amax = 100000; // "No limits" #if HAS_SOFTWARE_ENDSTOPS if (enabled()) switch (axis) { - case X_AXIS: - TERN_(MIN_SOFTWARE_ENDSTOP_X, amin = min.x); - TERN_(MAX_SOFTWARE_ENDSTOP_X, amax = max.x); - break; + #if HAS_X_AXIS + case X_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_X, amin = min.x); + TERN_(MAX_SOFTWARE_ENDSTOP_X, amax = max.x); + break; + #endif #if HAS_Y_AXIS case Y_AXIS: TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y); @@ -261,7 +263,7 @@ void report_current_position_projected(); extern AutoReporter position_auto_reporter; #endif -#if EITHER(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS) +#if ANY(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS) #define HAS_GRBL_STATE 1 /** * Machine states for GRBL or TinyG @@ -344,12 +346,14 @@ inline void prepare_internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f) /** * Blocking movement and shorthand functions */ -void do_blocking_move_to(NUM_AXIS_ARGS(const_float_t), const_feedRate_t fr_mm_s=0.0f); +void do_blocking_move_to(NUM_AXIS_ARGS_(const_float_t) const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); -void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s=0.0f); +#if HAS_X_AXIS + void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s=0.0f); +#endif #if HAS_Y_AXIS void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s=0.0f); #endif @@ -400,19 +404,18 @@ void restore_feedrate_and_scaling(); #if HAS_Z_AXIS void do_z_clearance(const_float_t zclear, const bool lower_allowed=false); + void do_z_clearance_by(const_float_t zclear); #else inline void do_z_clearance(float, bool=false) {} + inline void do_z_clearance_by(float) {} #endif /** * Homing and Trusted Axes */ -typedef IF<(NUM_AXES > 8), uint16_t, uint8_t>::type main_axes_bits_t; +typedef bits_t(NUM_AXES) main_axes_bits_t; constexpr main_axes_bits_t main_axes_mask = _BV(NUM_AXES) - 1; -typedef IF<(NUM_AXES + EXTRUDERS > 8), uint16_t, uint8_t>::type e_axis_bits_t; -constexpr e_axis_bits_t e_axis_mask = (_BV(EXTRUDERS) - 1) << NUM_AXES; - void set_axis_is_at_home(const AxisEnum axis); #if HAS_ENDSTOPS @@ -430,26 +433,21 @@ void set_axis_is_at_home(const AxisEnum axis); void set_axis_never_homed(const AxisEnum axis); main_axes_bits_t axes_should_home(main_axes_bits_t axes_mask=main_axes_mask); bool homing_needed_error(main_axes_bits_t axes_mask=main_axes_mask); - inline void set_axis_unhomed(const AxisEnum axis) { CBI(axes_homed, axis); } - inline void set_axis_untrusted(const AxisEnum axis) { CBI(axes_trusted, axis); } - inline void set_all_unhomed() { axes_homed = axes_trusted = 0; } - inline void set_axis_homed(const AxisEnum axis) { SBI(axes_homed, axis); } - inline void set_axis_trusted(const AxisEnum axis) { SBI(axes_trusted, axis); } - inline void set_all_homed() { axes_homed = axes_trusted = main_axes_mask; } #else constexpr main_axes_bits_t axes_homed = main_axes_mask, axes_trusted = main_axes_mask; // Zero-endstop machines are always homed and trusted inline void homeaxis(const AxisEnum axis) {} inline void set_axis_never_homed(const AxisEnum) {} inline main_axes_bits_t axes_should_home(main_axes_bits_t=main_axes_mask) { return 0; } inline bool homing_needed_error(main_axes_bits_t=main_axes_mask) { return false; } - inline void set_axis_unhomed(const AxisEnum axis) {} - inline void set_axis_untrusted(const AxisEnum axis) {} - inline void set_all_unhomed() {} - inline void set_axis_homed(const AxisEnum axis) {} - inline void set_axis_trusted(const AxisEnum axis) {} - inline void set_all_homed() {} #endif +inline void set_axis_unhomed(const AxisEnum axis) { TERN_(HAS_ENDSTOPS, CBI(axes_homed, axis)); } +inline void set_axis_untrusted(const AxisEnum axis) { TERN_(HAS_ENDSTOPS, CBI(axes_trusted, axis)); } +inline void set_all_unhomed() { TERN_(HAS_ENDSTOPS, axes_homed = axes_trusted = 0); } +inline void set_axis_homed(const AxisEnum axis) { TERN_(HAS_ENDSTOPS, SBI(axes_homed, axis)); } +inline void set_axis_trusted(const AxisEnum axis) { TERN_(HAS_ENDSTOPS, SBI(axes_trusted, axis)); } +inline void set_all_homed() { TERN_(HAS_ENDSTOPS, axes_homed = axes_trusted = main_axes_mask); } + inline bool axis_was_homed(const AxisEnum axis) { return TEST(axes_homed, axis); } inline bool axis_is_trusted(const AxisEnum axis) { return TEST(axes_trusted, axis); } inline bool axis_should_home(const AxisEnum axis) { return (axes_should_home() & _BV(axis)) != 0; } @@ -504,8 +502,10 @@ void home_if_needed(const bool keeplev=false); FORCE_INLINE void toNative(xyz_pos_t&) {} FORCE_INLINE void toNative(xyze_pos_t&) {} #endif -#define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS) -#define RAW_X_POSITION(POS) LOGICAL_TO_NATIVE(POS, X_AXIS) +#if HAS_X_AXIS + #define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS) + #define RAW_X_POSITION(POS) LOGICAL_TO_NATIVE(POS, X_AXIS) +#endif #if HAS_Y_AXIS #define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS) #define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS) @@ -558,9 +558,9 @@ void home_if_needed(const bool keeplev=false); #else // Return true if the given position is within the machine bounds. - bool position_is_reachable(const_float_t rx, const_float_t ry); + bool position_is_reachable(TERN_(HAS_X_AXIS, const_float_t rx) OPTARG(HAS_Y_AXIS, const_float_t ry)); inline bool position_is_reachable(const xy_pos_t &pos) { - return position_is_reachable(pos.x, pos.y); + return position_is_reachable(TERN_(HAS_X_AXIS, pos.x) OPTARG(HAS_Y_AXIS, pos.y)); } #endif @@ -597,7 +597,7 @@ void home_if_needed(const bool keeplev=false); float x_home_pos(const uint8_t extruder); - #define TOOL_X_HOME_DIR(T) ((T) ? X2_HOME_DIR : X_HOME_DIR) + #define TOOL_X_HOME_DIR(T) ((T) ? 1 : -1) void set_duplication_enabled(const bool dupe, const int8_t tool_index=-1); void idex_set_mirrored_mode(const bool mirr); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index d4e5be306eea..f1612e69f6e1 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -112,7 +112,7 @@ // Delay for delivery of first block to the stepper ISR, if the queue contains 2 or // fewer movements. The delay is measured in milliseconds, and must be less than 250ms -#define BLOCK_DELAY_FOR_1ST_MOVE 100 +#define BLOCK_DELAY_FOR_1ST_MOVE 100U Planner planner; @@ -127,7 +127,7 @@ volatile uint8_t Planner::block_buffer_head, // Index of the next block to be Planner::block_buffer_planned, // Index of the optimally planned block Planner::block_buffer_tail; // Index of the busy block, if any uint16_t Planner::cleaning_buffer_counter; // A counter to disable queuing of blocks -uint8_t Planner::delay_before_delivering; // This counter delays delivery of blocks when queue becomes empty to allow the opportunity of merging blocks +uint8_t Planner::delay_before_delivering; // Delay block delivery so initial blocks in an empty queue may merge planner_settings_t Planner::settings; // Initialized by settings.load() @@ -198,7 +198,9 @@ float Planner::mm_per_step[DISTINCT_AXES]; // (mm) Millimeters per step constexpr bool Planner::leveling_active; #endif -skew_factor_t Planner::skew_factor; // Initialized by settings.load() +#if ENABLED(SKEW_CORRECTION) + skew_factor_t Planner::skew_factor; // Initialized by settings.load() +#endif #if ENABLED(AUTOTEMP) celsius_t Planner::autotemp_max = 250, @@ -216,7 +218,7 @@ uint32_t Planner::acceleration_long_cutoff; xyze_float_t Planner::previous_speed; float Planner::previous_nominal_speed; -#if ENABLED(DISABLE_INACTIVE_EXTRUDER) +#if ENABLED(DISABLE_OTHER_EXTRUDERS) last_move_t Planner::g_uc_extruder_last_move[E_STEPPERS] = { 0 }; #endif @@ -252,11 +254,15 @@ void Planner::init() { position.reset(); TERN_(HAS_POSITION_FLOAT, position_float.reset()); TERN_(IS_KINEMATIC, position_cart.reset()); + previous_speed.reset(); previous_nominal_speed = 0; + TERN_(ABL_PLANAR, bed_level_matrix.set_to_identity()); + clear_block_buffer(); delay_before_delivering = 0; + #if ENABLED(DIRECT_STEPPING) last_page_step_rate = 0; last_page_dir.reset(); @@ -788,7 +794,7 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t NOLESS(initial_rate, uint32_t(MINIMAL_STEP_RATE)); NOLESS(final_rate, uint32_t(MINIMAL_STEP_RATE)); - #if EITHER(S_CURVE_ACCELERATION, LIN_ADVANCE) + #if ANY(S_CURVE_ACCELERATION, LIN_ADVANCE) // If we have some plateau time, the cruise rate will be the nominal rate uint32_t cruise_rate = block->nominal_rate; #endif @@ -822,7 +828,7 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t accelerate_steps = _MIN(uint32_t(_MAX(accelerate_steps_float, 0)), block->step_event_count); decelerate_steps = block->step_event_count - accelerate_steps; - #if EITHER(S_CURVE_ACCELERATION, LIN_ADVANCE) + #if ANY(S_CURVE_ACCELERATION, LIN_ADVANCE) // We won't reach the cruising rate. Let's calculate the speed we will reach cruise_rate = final_speed(initial_rate, accel, accelerate_steps); #endif @@ -1321,7 +1327,7 @@ void Planner::recalculate(TERN_(HINTS_SAFE_EXIT_SPEED, const_float_t safe_exit_s */ void Planner::check_axes_activity() { - #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K, DISABLE_U, DISABLE_V, DISABLE_W, DISABLE_E) + #if HAS_DISABLE_AXES xyze_bool_t axis_active = { false }; #endif @@ -1342,7 +1348,7 @@ void Planner::check_axes_activity() { if (has_blocks_queued()) { - #if EITHER(HAS_TAIL_FAN_SPEED, BARICUDA) + #if ANY(HAS_TAIL_FAN_SPEED, BARICUDA) block_t *block = &block_buffer[block_buffer_tail]; #endif @@ -1361,7 +1367,7 @@ void Planner::check_axes_activity() { TERN_(HAS_HEATER_2, tail_e_to_p_pressure = block->e_to_p_pressure); #endif - #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K, DISABLE_E) + #if HAS_DISABLE_AXES for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) { block_t * const bnext = &block_buffer[b]; LOGICAL_AXIS_CODE( @@ -1402,18 +1408,20 @@ void Planner::check_axes_activity() { // // Disable inactive axes // - LOGICAL_AXIS_CODE( - if (TERN0(DISABLE_E, !axis_active.e)) stepper.disable_e_steppers(), - if (TERN0(DISABLE_X, !axis_active.x)) stepper.disable_axis(X_AXIS), - if (TERN0(DISABLE_Y, !axis_active.y)) stepper.disable_axis(Y_AXIS), - if (TERN0(DISABLE_Z, !axis_active.z)) stepper.disable_axis(Z_AXIS), - if (TERN0(DISABLE_I, !axis_active.i)) stepper.disable_axis(I_AXIS), - if (TERN0(DISABLE_J, !axis_active.j)) stepper.disable_axis(J_AXIS), - if (TERN0(DISABLE_K, !axis_active.k)) stepper.disable_axis(K_AXIS), - if (TERN0(DISABLE_U, !axis_active.u)) stepper.disable_axis(U_AXIS), - if (TERN0(DISABLE_V, !axis_active.v)) stepper.disable_axis(V_AXIS), - if (TERN0(DISABLE_W, !axis_active.w)) stepper.disable_axis(W_AXIS) - ); + #if HAS_DISABLE_AXES + LOGICAL_AXIS_CODE( + if (TERN0(DISABLE_E, !axis_active.e)) stepper.disable_e_steppers(), + if (TERN0(DISABLE_X, !axis_active.x)) stepper.disable_axis(X_AXIS), + if (TERN0(DISABLE_Y, !axis_active.y)) stepper.disable_axis(Y_AXIS), + if (TERN0(DISABLE_Z, !axis_active.z)) stepper.disable_axis(Z_AXIS), + if (TERN0(DISABLE_I, !axis_active.i)) stepper.disable_axis(I_AXIS), + if (TERN0(DISABLE_J, !axis_active.j)) stepper.disable_axis(J_AXIS), + if (TERN0(DISABLE_K, !axis_active.k)) stepper.disable_axis(K_AXIS), + if (TERN0(DISABLE_U, !axis_active.u)) stepper.disable_axis(U_AXIS), + if (TERN0(DISABLE_V, !axis_active.v)) stepper.disable_axis(V_AXIS), + if (TERN0(DISABLE_W, !axis_active.w)) stepper.disable_axis(W_AXIS) + ); + #endif // // Update Fan speeds @@ -1493,7 +1501,7 @@ void Planner::check_axes_activity() { thermalManager.setTargetHotend(t, active_extruder); } -#endif +#endif // AUTOTEMP #if DISABLED(NO_VOLUMETRICS) @@ -1511,7 +1519,7 @@ void Planner::check_axes_activity() { * The multiplier converts a given E value into a length. */ void Planner::calculate_volumetric_multipliers() { - LOOP_L_N(i, COUNT(filament_size)) { + for (uint8_t i = 0; i < COUNT(filament_size); ++i) { volumetric_multiplier[i] = calculate_volumetric_multiplier(filament_size[i]); refresh_e_factor(i); } @@ -1727,7 +1735,7 @@ float Planner::triggered_position_mm(const AxisEnum axis) { bool Planner::busy() { return (has_blocks_queued() || cleaning_buffer_counter || TERN0(EXTERNAL_CLOSED_LOOP_CONTROLLER, CLOSED_LOOP_WAITING()) - || TERN0(HAS_SHAPING, stepper.input_shaping_busy()) + || TERN0(HAS_ZV_SHAPING, stepper.input_shaping_busy()) ); } @@ -1762,7 +1770,7 @@ float Planner::get_axis_position_mm(const AxisEnum axis) { else axis_steps = DIFF_TERN(BACKLASH_COMPENSATION, stepper.position(axis), backlash.get_applied_steps(axis)); - #elif EITHER(MARKFORGED_XY, MARKFORGED_YX) + #elif ANY(MARKFORGED_XY, MARKFORGED_YX) // Requesting one of the joined axes? if (axis == CORE_AXIS_1 || axis == CORE_AXIS_2) { @@ -1922,7 +1930,7 @@ bool Planner::_populate_block( ); //*/ - #if EITHER(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE) + #if ANY(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE) if (de) { #if ENABLED(PREVENT_COLD_EXTRUSION) if (thermalManager.tooColdToExtrude(extruder)) { @@ -1963,29 +1971,27 @@ bool Planner::_populate_block( if (db < 0) SBI(dm, Y_HEAD); // ...and Y TERN_(HAS_Z_AXIS, if (dc < 0) SBI(dm, Z_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 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 #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 + 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 + if (da < 0) SBI(dm, A_AXIS); // Motor A direction + if (db + da < 0) SBI(dm, B_AXIS); // Motor B direction #else XYZ_CODE( if (da < 0) SBI(dm, X_AXIS), @@ -2087,23 +2093,21 @@ bool Planner::_populate_block( steps_dist_mm.head.y = db * mm_per_step[B_AXIS]; TERN_(HAS_Z_AXIS, steps_dist_mm.z = dc * mm_per_step[Z_AXIS]); #endif - #if IS_CORE - #if CORE_IS_XY - 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 - steps_dist_mm.head.x = da * mm_per_step[A_AXIS]; - steps_dist_mm.y = db * mm_per_step[Y_AXIS]; - steps_dist_mm.head.z = dc * mm_per_step[C_AXIS]; - steps_dist_mm.a = (da + dc) * mm_per_step[A_AXIS]; - steps_dist_mm.c = CORESIGN(da - dc) * mm_per_step[C_AXIS]; - #elif CORE_IS_YZ - steps_dist_mm.x = da * mm_per_step[X_AXIS]; - steps_dist_mm.head.y = db * mm_per_step[B_AXIS]; - steps_dist_mm.head.z = dc * mm_per_step[C_AXIS]; - 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 CORE_IS_XY + 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 + steps_dist_mm.head.x = da * mm_per_step[A_AXIS]; + steps_dist_mm.y = db * mm_per_step[Y_AXIS]; + steps_dist_mm.head.z = dc * mm_per_step[C_AXIS]; + steps_dist_mm.a = (da + dc) * mm_per_step[A_AXIS]; + steps_dist_mm.c = CORESIGN(da - dc) * mm_per_step[C_AXIS]; + #elif CORE_IS_YZ + steps_dist_mm.x = da * mm_per_step[X_AXIS]; + steps_dist_mm.head.y = db * mm_per_step[B_AXIS]; + steps_dist_mm.head.z = dc * mm_per_step[C_AXIS]; + steps_dist_mm.b = (db + dc) * mm_per_step[B_AXIS]; + steps_dist_mm.c = CORESIGN(db - dc) * mm_per_step[C_AXIS]; #elif ENABLED(MARKFORGED_XY) steps_dist_mm.a = (da - db) * mm_per_step[A_AXIS]; steps_dist_mm.b = db * mm_per_step[B_AXIS]; @@ -2131,20 +2135,14 @@ bool Planner::_populate_block( TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator += steps_dist_mm.e); - #if BOTH(HAS_ROTATIONAL_AXES, INCH_MODE_SUPPORT) + #if ALL(HAS_ROTATIONAL_AXES, INCH_MODE_SUPPORT) bool cartesian_move = true; #endif if (true NUM_AXIS_GANG( - && block->steps.a < MIN_STEPS_PER_SEGMENT, - && block->steps.b < MIN_STEPS_PER_SEGMENT, - && block->steps.c < MIN_STEPS_PER_SEGMENT, - && block->steps.i < MIN_STEPS_PER_SEGMENT, - && block->steps.j < MIN_STEPS_PER_SEGMENT, - && block->steps.k < MIN_STEPS_PER_SEGMENT, - && block->steps.u < MIN_STEPS_PER_SEGMENT, - && block->steps.v < MIN_STEPS_PER_SEGMENT, - && block->steps.w < MIN_STEPS_PER_SEGMENT + && block->steps.a < MIN_STEPS_PER_SEGMENT, && block->steps.b < MIN_STEPS_PER_SEGMENT, && block->steps.c < MIN_STEPS_PER_SEGMENT, + && block->steps.i < MIN_STEPS_PER_SEGMENT, && block->steps.j < MIN_STEPS_PER_SEGMENT, && block->steps.k < MIN_STEPS_PER_SEGMENT, + && block->steps.u < MIN_STEPS_PER_SEGMENT, && block->steps.v < MIN_STEPS_PER_SEGMENT, && block->steps.w < MIN_STEPS_PER_SEGMENT ) ) { block->millimeters = TERN0(HAS_EXTRUDERS, ABS(steps_dist_mm.e)); @@ -2234,11 +2232,17 @@ bool Planner::_populate_block( TERN_(HAS_EXTRUDERS, block->steps.e = esteps); - block->step_event_count = _MAX(LOGICAL_AXIS_LIST(esteps, - block->steps.a, block->steps.b, block->steps.c, - block->steps.i, block->steps.j, block->steps.k, - block->steps.u, block->steps.v, block->steps.w - )); + block->step_event_count = ( + #if NUM_AXES + _MAX(LOGICAL_AXIS_LIST(esteps, + block->steps.a, block->steps.b, block->steps.c, + block->steps.i, block->steps.j, block->steps.k, + block->steps.u, block->steps.v, block->steps.w + )) + #elif HAS_EXTRUDERS + esteps + #endif + ); // Bail if this is a zero-length block if (block->step_event_count < MIN_STEPS_PER_SEGMENT) return false; @@ -2300,12 +2304,9 @@ bool Planner::_populate_block( #endif #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) SECONDARY_AXIS_CODE( - if (block->steps.i) stepper.enable_axis(I_AXIS), - if (block->steps.j) stepper.enable_axis(J_AXIS), - if (block->steps.k) stepper.enable_axis(K_AXIS), - if (block->steps.u) stepper.enable_axis(U_AXIS), - if (block->steps.v) stepper.enable_axis(V_AXIS), - if (block->steps.w) stepper.enable_axis(W_AXIS) + if (block->steps.i) stepper.enable_axis(I_AXIS), if (block->steps.j) stepper.enable_axis(J_AXIS), + if (block->steps.k) stepper.enable_axis(K_AXIS), if (block->steps.u) stepper.enable_axis(U_AXIS), + if (block->steps.v) stepper.enable_axis(V_AXIS), if (block->steps.w) stepper.enable_axis(W_AXIS) ); #endif @@ -2314,10 +2315,10 @@ bool Planner::_populate_block( if (esteps) { TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); - #if ENABLED(DISABLE_INACTIVE_EXTRUDER) // Enable only the selected extruder + #if ENABLED(DISABLE_OTHER_EXTRUDERS) // Enable only the selected extruder // Count down all steppers that were recently moved - LOOP_L_N(i, E_STEPPERS) + for (uint8_t i = 0; i < E_STEPPERS; ++i) if (g_uc_extruder_last_move[i]) g_uc_extruder_last_move[i]--; // Switching Extruder uses one E stepper motor per two nozzles @@ -2355,18 +2356,19 @@ bool Planner::_populate_block( // Calculate inverse time for this move. No divide by zero due to previous checks. // Example: At 120mm/s a 60mm move involving XYZ axes takes 0.5s. So this will give 2.0. // Example 2: At 120°/s a 60° move involving only rotational axes takes 0.5s. So this will give 2.0. - float inverse_secs; - #if BOTH(HAS_ROTATIONAL_AXES, INCH_MODE_SUPPORT) - inverse_secs = inverse_millimeters * (cartesian_move ? fr_mm_s : LINEAR_UNIT(fr_mm_s)); - #else - inverse_secs = fr_mm_s * inverse_millimeters; - #endif + float inverse_secs = inverse_millimeters * ( + #if ALL(HAS_ROTATIONAL_AXES, INCH_MODE_SUPPORT) + cartesian_move ? fr_mm_s : LINEAR_UNIT(fr_mm_s) + #else + fr_mm_s + #endif + ); // Get the number of non busy movements in queue (non busy means that they can be altered) const uint8_t moves_queued = nonbusy_movesplanned(); // Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill - #if EITHER(SLOWDOWN, HAS_WIRED_LCD) || defined(XY_FREQUENCY_LIMIT) + #if ANY(SLOWDOWN, HAS_WIRED_LCD) || defined(XY_FREQUENCY_LIMIT) // Segment time in microseconds int32_t segment_time_us = LROUND(1000000.0f / inverse_secs); #endif @@ -2503,8 +2505,8 @@ bool Planner::_populate_block( #if ENABLED(LIN_ADVANCE) bool use_advance_lead = false; #endif - if (NUM_AXIS_GANG( - !block->steps.a, && !block->steps.b, && !block->steps.c, + if (true NUM_AXIS_GANG( + && !block->steps.a, && !block->steps.b, && !block->steps.c, && !block->steps.i, && !block->steps.j, && !block->steps.k, && !block->steps.u, && !block->steps.v, && !block->steps.w) ) { // Is this a retract / recover move? @@ -2558,9 +2560,10 @@ bool Planner::_populate_block( else { // Scale E acceleration so that it will be possible to jump to the advance speed. const uint32_t max_accel_steps_per_s2 = MAX_E_JERK(extruder) / (extruder_advance_K[E_INDEX_N(extruder)] * e_D_ratio) * steps_per_mm; - if (TERN0(LA_DEBUG, accel > max_accel_steps_per_s2)) - SERIAL_ECHOLNPGM("Acceleration limited."); - NOMORE(accel, max_accel_steps_per_s2); + if (accel > max_accel_steps_per_s2) { + accel = max_accel_steps_per_s2; + if (ENABLED(LA_DEBUG)) SERIAL_ECHOLNPGM("Acceleration limited."); + } } } #endif @@ -2588,6 +2591,7 @@ bool Planner::_populate_block( #if DISABLED(S_CURVE_ACCELERATION) block->acceleration_rate = (uint32_t)(accel * (float(1UL << 24) / (STEPPER_TIMER_RATE))); #endif + #if ENABLED(LIN_ADVANCE) block->la_advance_rate = 0; block->la_scaling = 0; @@ -2963,7 +2967,7 @@ void Planner::buffer_sync_block(const BlockFlagBit sync_flag/*=BLOCK_BIT_SYNC_PO #if ENABLED(BACKLASH_COMPENSATION) LOOP_NUM_AXES(axis) block->position[axis] += backlash.get_applied_steps((AxisEnum)axis); #endif - #if BOTH(HAS_FAN, LASER_SYNCHRONOUS_M106_M107) + #if ALL(HAS_FAN, LASER_SYNCHRONOUS_M106_M107) FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; #endif diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index dcfdb1c28e6b..8731dd00facc 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -110,7 +110,6 @@ enum BlockFlagBit { // Direct stepping page OPTARG(DIRECT_STEPPING, BLOCK_BIT_PAGE) - // Sync the fan speeds from the block OPTARG(LASER_SYNCHRONOUS_M106_M107, BLOCK_BIT_SYNC_FANS) @@ -287,7 +286,19 @@ typedef struct PlannerBlock { #define HAS_POSITION_FLOAT 1 #endif -#define BLOCK_MOD(n) ((n)&(BLOCK_BUFFER_SIZE-1)) +constexpr uint8_t block_dec_mod(const uint8_t v1, const uint8_t v2) { + return v1 >= v2 ? v1 - v2 : v1 - v2 + BLOCK_BUFFER_SIZE; +} + +constexpr uint8_t block_inc_mod(const uint8_t v1, const uint8_t v2) { + return v1 + v2 < BLOCK_BUFFER_SIZE ? v1 + v2 : v1 + v2 - BLOCK_BUFFER_SIZE; +} + +#if IS_POWER_OF_2(BLOCK_BUFFER_SIZE) + #define BLOCK_MOD(n) ((n)&((BLOCK_BUFFER_SIZE)-1)) +#else + #define BLOCK_MOD(n) ((n)%(BLOCK_BUFFER_SIZE)) +#endif #if ENABLED(LASER_FEATURE) typedef struct { @@ -346,8 +357,8 @@ typedef struct { #endif } skew_factor_t; -#if ENABLED(DISABLE_INACTIVE_EXTRUDER) - typedef IF<(BLOCK_BUFFER_SIZE > 64), uint16_t, uint8_t>::type last_move_t; +#if ENABLED(DISABLE_OTHER_EXTRUDERS) + typedef uvalue_t((BLOCK_BUFFER_SIZE) * 2) last_move_t; #endif #if ENABLED(ARC_SUPPORT) @@ -398,7 +409,6 @@ class Planner { static uint16_t cleaning_buffer_counter; // A counter to disable queuing of blocks static uint8_t delay_before_delivering; // This counter delays delivery of blocks when queue becomes empty to allow the opportunity of merging blocks - #if ENABLED(DISTINCT_E_FACTORS) static uint8_t last_extruder; // Respond to extruder change #endif @@ -414,15 +424,15 @@ class Planner { #endif #if DISABLED(NO_VOLUMETRICS) - static float filament_size[EXTRUDERS], // diameter of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder - volumetric_area_nominal, // Nominal cross-sectional area - volumetric_multiplier[EXTRUDERS]; // Reciprocal of cross-sectional area of filament (in mm^2). Pre-calculated to reduce computation in the planner + static float filament_size[EXTRUDERS], // (mm) Diameter of filament, typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder + volumetric_area_nominal, // (mm^3) Nominal cross-sectional area + volumetric_multiplier[EXTRUDERS]; // (1/mm^2) Reciprocal of cross-sectional area of filament. Pre-calculated to reduce computation in the planner // May be auto-adjusted by a filament width sensor #endif #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) - static float volumetric_extruder_limit[EXTRUDERS], // Maximum mm^3/sec the extruder can handle - volumetric_extruder_feedrate_limit[EXTRUDERS]; // Feedrate limit (mm/s) calculated from volume limit + static float volumetric_extruder_limit[EXTRUDERS], // (mm^3/sec) Maximum volume the extruder can handle + volumetric_extruder_feedrate_limit[EXTRUDERS]; // (mm/s) Feedrate limit calculated from volume limit #endif static planner_settings_t settings; @@ -476,7 +486,9 @@ class Planner { static xyze_pos_t position_cart; #endif - static skew_factor_t skew_factor; + #if ENABLED(SKEW_CORRECTION) + static skew_factor_t skew_factor; + #endif #if ENABLED(SD_ABORT_ON_ENDSTOP_HIT) static bool abort_on_endstop_hit; @@ -520,7 +532,7 @@ class Planner { static float last_fade_z; #endif - #if ENABLED(DISABLE_INACTIVE_EXTRUDER) + #if ENABLED(DISABLE_OTHER_EXTRUDERS) // Counters to manage disabling inactive extruder steppers static last_move_t g_uc_extruder_last_move[E_STEPPERS]; #endif @@ -620,7 +632,7 @@ class Planner { filament_size[e] = v; if (v > 0) volumetric_area_nominal = CIRCLE_AREA(v * 0.5); //TODO: should it be per extruder // make sure all extruders have some sane value for the filament size - LOOP_L_N(i, COUNT(filament_size)) + for (uint8_t i = 0; i < COUNT(filament_size); ++i) if (!filament_size[i]) filament_size[i] = DEFAULT_NOMINAL_FILAMENT_DIA; } @@ -738,10 +750,10 @@ class Planner { #endif // HAS_POSITION_MODIFIERS // Number of moves currently in the planner including the busy block, if any - FORCE_INLINE static uint8_t movesplanned() { return BLOCK_MOD(block_buffer_head - block_buffer_tail); } + FORCE_INLINE static uint8_t movesplanned() { return block_dec_mod(block_buffer_head, block_buffer_tail); } // Number of nonbusy moves currently in the planner - FORCE_INLINE static uint8_t nonbusy_movesplanned() { return BLOCK_MOD(block_buffer_head - block_buffer_nonbusy); } + FORCE_INLINE static uint8_t nonbusy_movesplanned() { return block_dec_mod(block_buffer_head, block_buffer_nonbusy); } // Remove all blocks from the buffer FORCE_INLINE static void clear_block_buffer() { block_buffer_nonbusy = block_buffer_planned = block_buffer_head = block_buffer_tail = 0; } @@ -750,7 +762,7 @@ class Planner { FORCE_INLINE static bool is_full() { return block_buffer_tail == next_block_index(block_buffer_head); } // Get count of movement slots free - FORCE_INLINE static uint8_t moves_free() { return BLOCK_BUFFER_SIZE - 1 - movesplanned(); } + FORCE_INLINE static uint8_t moves_free() { return (BLOCK_BUFFER_SIZE) - 1 - movesplanned(); } /** * Planner::get_next_free_block @@ -1001,8 +1013,8 @@ class Planner { /** * Get the index of the next / previous block in the ring buffer */ - static constexpr uint8_t next_block_index(const uint8_t block_index) { return BLOCK_MOD(block_index + 1); } - static constexpr uint8_t prev_block_index(const uint8_t block_index) { return BLOCK_MOD(block_index - 1); } + static constexpr uint8_t next_block_index(const uint8_t block_index) { return block_inc_mod(block_index, 1); } + static constexpr uint8_t prev_block_index(const uint8_t block_index) { return block_dec_mod(block_index, 1); } /** * Calculate the maximum allowable speed squared at this point, in order @@ -1013,7 +1025,7 @@ class Planner { return target_velocity_sqr - 2 * accel * distance; } - #if EITHER(S_CURVE_ACCELERATION, LIN_ADVANCE) + #if ANY(S_CURVE_ACCELERATION, LIN_ADVANCE) /** * Calculate the speed reached given initial speed, acceleration and distance */ diff --git a/Marlin/src/module/polargraph.cpp b/Marlin/src/module/polargraph.cpp index d55d36a6d654..ef6a4c0db463 100644 --- a/Marlin/src/module/polargraph.cpp +++ b/Marlin/src/module/polargraph.cpp @@ -43,7 +43,7 @@ xy_pos_t draw_area_min, draw_area_max; void inverse_kinematics(const xyz_pos_t &raw) { const float x1 = raw.x - draw_area_min.x, x2 = draw_area_max.x - raw.x, y = raw.y - draw_area_max.y; - delta.set(HYPOT(x1, y), HYPOT(x2, y), raw.z); + delta.set(HYPOT(x1, y), HYPOT(x2, y) OPTARG(HAS_Z_AXIS, raw.z)); } #endif // POLARGRAPH diff --git a/Marlin/src/module/printcounter.h b/Marlin/src/module/printcounter.h index 63cc1da158e8..ebf61a3a1ce0 100644 --- a/Marlin/src/module/printcounter.h +++ b/Marlin/src/module/printcounter.h @@ -54,7 +54,7 @@ struct printStatistics { // 16 bytes class PrintCounter: public Stopwatch { private: typedef Stopwatch super; - typedef IF::type eeprom_address_t; + typedef IF::type eeprom_address_t; static printStatistics data; diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index d4f25126b8c6..5373cef74d18 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -57,9 +57,9 @@ float largest_sensorless_adj = 0; #endif -#if EITHER(HAS_QUIET_PROBING, USE_SENSORLESS) +#if ANY(HAS_QUIET_PROBING, USE_SENSORLESS) #include "stepper/indirection.h" - #if BOTH(HAS_QUIET_PROBING, PROBING_ESTEPPERS_OFF) + #if ALL(HAS_QUIET_PROBING, PROBING_ESTEPPERS_OFF) #include "stepper.h" #endif #if USE_SENSORLESS @@ -196,35 +196,35 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() inline void run_deploy_moves() { #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_1 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE - #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE 0.0f #endif constexpr xyz_pos_t deploy_1 = Z_PROBE_ALLEN_KEY_DEPLOY_1; do_blocking_move_to(deploy_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_2 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE - #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE 0.0f #endif constexpr xyz_pos_t deploy_2 = Z_PROBE_ALLEN_KEY_DEPLOY_2; do_blocking_move_to(deploy_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_3 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE - #define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE 0.0f #endif constexpr xyz_pos_t deploy_3 = Z_PROBE_ALLEN_KEY_DEPLOY_3; do_blocking_move_to(deploy_3, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_4 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE - #define Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE 0.0f #endif constexpr xyz_pos_t deploy_4 = Z_PROBE_ALLEN_KEY_DEPLOY_4; do_blocking_move_to(deploy_4, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_5 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE - #define Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE 0.0f #endif constexpr xyz_pos_t deploy_5 = Z_PROBE_ALLEN_KEY_DEPLOY_5; do_blocking_move_to(deploy_5, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE)); @@ -234,35 +234,35 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() inline void run_stow_moves() { #ifdef Z_PROBE_ALLEN_KEY_STOW_1 #ifndef Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE - #define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE 0.0f #endif constexpr xyz_pos_t stow_1 = Z_PROBE_ALLEN_KEY_STOW_1; do_blocking_move_to(stow_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_STOW_2 #ifndef Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE - #define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE 0.0f #endif constexpr xyz_pos_t stow_2 = Z_PROBE_ALLEN_KEY_STOW_2; do_blocking_move_to(stow_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_STOW_3 #ifndef Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE - #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE 0.0f #endif constexpr xyz_pos_t stow_3 = Z_PROBE_ALLEN_KEY_STOW_3; do_blocking_move_to(stow_3, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_STOW_4 #ifndef Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE - #define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE 0.0f #endif constexpr xyz_pos_t stow_4 = Z_PROBE_ALLEN_KEY_STOW_4; do_blocking_move_to(stow_4, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_STOW_5 #ifndef Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE - #define Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE 0.0f #endif constexpr xyz_pos_t stow_5 = Z_PROBE_ALLEN_KEY_STOW_5; do_blocking_move_to(stow_5, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE)); @@ -413,6 +413,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #elif HAS_Z_SERVO_PROBE + // i.e., deploy ? DEPLOY_Z_SERVO() : STOW_Z_SERVO(); servo[Z_PROBE_SERVO_NR].move(servo_angles[Z_PROBE_SERVO_NR][deploy ? 0 : 1]); #elif ANY(TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY, MAG_MOUNTED_PROBE) @@ -430,7 +431,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #endif } -#if EITHER(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) +#if ANY(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) #if ENABLED(PREHEAT_BEFORE_PROBING) #ifndef PROBING_NOZZLE_TEMP @@ -491,7 +492,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { void Probe::probe_error_stop() { SERIAL_ERROR_START(); SERIAL_ECHOPGM(STR_STOP_PRE); - #if EITHER(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY) + #if ANY(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY) SERIAL_ECHOPGM(STR_STOP_UNHOMED); #elif ENABLED(BLTOUCH) SERIAL_ECHOPGM(STR_STOP_BLTOUCH); @@ -517,7 +518,7 @@ bool Probe::set_deployed(const bool deploy) { // Make room for probe to deploy (or stow) // Fix-mounted probe should only raise for deploy // unless PAUSE_BEFORE_DEPLOY_STOW is enabled - #if EITHER(FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE) && DISABLED(PAUSE_BEFORE_DEPLOY_STOW) + #if ANY(FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE) && DISABLED(PAUSE_BEFORE_DEPLOY_STOW) const bool z_raise_wanted = deploy; #else constexpr bool z_raise_wanted = true; @@ -526,14 +527,14 @@ bool Probe::set_deployed(const bool deploy) { if (z_raise_wanted) do_z_raise(_MAX(Z_CLEARANCE_BETWEEN_PROBES, Z_CLEARANCE_DEPLOY_PROBE)); - #if EITHER(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY) + #if ANY(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY) if (homing_needed_error(TERN_(Z_PROBE_SLED, _BV(X_AXIS)))) { probe_error_stop(); return true; } #endif - const xy_pos_t old_xy = current_position; + const xy_pos_t old_xy = current_position; // Remember location before probe deployment #if ENABLED(PROBE_TRIGGERED_WHEN_STOWED_TEST) @@ -560,6 +561,7 @@ bool Probe::set_deployed(const bool deploy) { #endif // If preheating is required before any probing... + // TODO: Consider skipping this for things like M401, G34, etc. TERN_(PREHEAT_BEFORE_PROBING, if (deploy) preheat_for_probing(PROBING_NOZZLE_TEMP, PROBING_BED_TEMP)); do_blocking_move_to(old_xy); @@ -585,13 +587,14 @@ bool Probe::set_deployed(const bool deploy) { bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { DEBUG_SECTION(log_probe, "Probe::probe_down_to_z", DEBUGGING(LEVELING)); - #if BOTH(HAS_HEATED_BED, WAIT_FOR_BED_HEATER) + #if ALL(HAS_HEATED_BED, WAIT_FOR_BED_HEATER) thermalManager.wait_for_bed_heating(); #endif - #if BOTH(HAS_TEMP_HOTEND, WAIT_FOR_HOTEND) + #if ALL(HAS_TEMP_HOTEND, WAIT_FOR_HOTEND) thermalManager.wait_for_hotend_heating(active_extruder); #endif + #if ENABLED(BLTOUCH) if (!bltouch.high_speed_mode && bltouch.deploy()) return true; // Deploy in LOW SPEED MODE on every probe action @@ -607,7 +610,7 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { if (test_sensitivity.z) stealth_states.z = tmc_enable_stallguard(stepperZ); // All machines will check Z-DIAG for stall endstops.set_homing_current(true); // The "homing" current also applies to probing endstops.enable(true); - #endif + #endif // SENSORLESS_PROBING TERN_(HAS_QUIET_PROBING, set_probing_paused(true)); @@ -615,17 +618,17 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { do_blocking_move_to_z(z, fr_mm_s); // Check to see if the probe was triggered - const bool probe_triggered = + const bool probe_triggered = ( #if HAS_DELTA_SENSORLESS_PROBING endstops.trigger_state() & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)) #else TEST(endstops.trigger_state(), Z_MIN_PROBE) #endif - ; + ); // Offset sensorless probing #if HAS_DELTA_SENSORLESS_PROBING - if (probe_triggered) probe.refresh_largest_sensorless_adj(); + if (probe_triggered) refresh_largest_sensorless_adj(); #endif TERN_(HAS_QUIET_PROBING, set_probing_paused(false)); @@ -677,14 +680,14 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { * @return TRUE if the tare cold not be completed */ bool Probe::tare() { - #if BOTH(PROBE_ACTIVATION_SWITCH, PROBE_TARE_ONLY_WHILE_INACTIVE) + #if ALL(PROBE_ACTIVATION_SWITCH, PROBE_TARE_ONLY_WHILE_INACTIVE) if (endstops.probe_switch_activated()) { - SERIAL_ECHOLNPGM("Cannot tare an active probe"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Cannot tare an active probe"); return true; } #endif - SERIAL_ECHOLNPGM("Taring probe"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Taring probe"); WRITE(PROBE_TARE_PIN, PROBE_TARE_STATE); delay(PROBE_TARE_TIME); WRITE(PROBE_TARE_PIN, !PROBE_TARE_STATE); @@ -741,8 +744,8 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { if (try_to_probe(PSTR("FAST"), z_probe_low_point, z_probe_fast_mm_s, sanity_check, Z_CLEARANCE_BETWEEN_PROBES) ) return NAN; - const float first_probe_z = DIFF_TERN(HAS_DELTA_SENSORLESS_PROBING, current_position.z, largest_sensorless_adj); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("1st Probe Z:", first_probe_z); + const float z1 = DIFF_TERN(HAS_DELTA_SENSORLESS_PROBING, current_position.z, largest_sensorless_adj); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("1st Probe Z:", z1); // Raise to give the probe clearance do_blocking_move_to_z(current_position.z + Z_CLEARANCE_MULTI_PROBE, z_probe_fast_mm_s); @@ -751,7 +754,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { // If the nozzle is well over the travel height then // move down quickly before doing the slow probe - const float z = Z_CLEARANCE_DEPLOY_PROBE + 5.0 + (offset.z < 0 ? -offset.z : 0); + const float z = (Z_CLEARANCE_DEPLOY_PROBE) + 5.0f + (offset.z < 0 ? -offset.z : 0); if (current_position.z > z) { // Probe down fast. If the probe never triggered, raise for probe clearance if (!probe_down_to_z(z, z_probe_fast_mm_s)) @@ -787,7 +790,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { #if EXTRA_PROBING > 0 // Insert Z measurement into probes[]. Keep it sorted ascending. - LOOP_LE_N(i, p) { // Iterate the saved Zs to insert the new Z + for (uint8_t i = 0; i <= p; ++i) { // Iterate the saved Zs to insert the new Z if (i == p || probes[i] > z) { // Last index or new Z is smaller than this Z for (int8_t m = p; --m >= i;) probes[m + 1] = probes[m]; // Shift items down after the insertion point probes[i] = z; // Insert the new Z measurement @@ -825,7 +828,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { max_avg_idx--; else min_avg_idx++; // Return the average value of all remaining probes. - LOOP_S_LE_N(i, min_avg_idx, max_avg_idx) + for (uint8_t i = min_avg_idx; i <= max_avg_idx; ++i) probes_z_sum += probes[i]; #endif @@ -836,10 +839,10 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { const float z2 = DIFF_TERN(HAS_DELTA_SENSORLESS_PROBING, current_position.z, largest_sensorless_adj); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("2nd Probe Z:", z2, " Discrepancy:", first_probe_z - z2); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("2nd Probe Z:", z2, " Discrepancy:", z1 - z2); // Return a weighted average of the fast and slow probes - const float measured_z = (z2 * 3.0 + first_probe_z * 2.0) * 0.2; + const float measured_z = (z2 * 3.0f + z1 * 2.0f) * 0.2f; #else @@ -885,7 +888,7 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai current_position.u, current_position.v, current_position.w ); if (!can_reach(npos, probe_relative)) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Position Not Reachable"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Not Reachable"); return NAN; } if (probe_relative) npos -= offset_xy; // Get the nozzle position @@ -904,9 +907,8 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai TERN_(X_AXIS_TWIST_COMPENSATION, measured_z += xatc.compensation(npos + offset_xy)); } if (!isnan(measured_z)) { - const bool big_raise = raise_after == PROBE_PT_BIG_RAISE; - if (big_raise || raise_after == PROBE_PT_RAISE) - do_blocking_move_to_z(current_position.z + (big_raise ? 25 : Z_CLEARANCE_BETWEEN_PROBES), z_probe_fast_mm_s); + if (raise_after == PROBE_PT_RAISE) + do_blocking_move_to_z(current_position.z + Z_CLEARANCE_BETWEEN_PROBES, z_probe_fast_mm_s); else if (raise_after == PROBE_PT_STOW || raise_after == PROBE_PT_LAST_STOW) if (stow()) measured_z = NAN; // Error on stow? @@ -959,15 +961,16 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai void Probe::refresh_largest_sensorless_adj() { DEBUG_SECTION(rso, "Probe::refresh_largest_sensorless_adj", true); largest_sensorless_adj = -3; // A reference away from any real probe height - if (TEST(endstops.state(), X_MAX)) { + const Endstops::endstop_mask_t state = endstops.state(); + if (TEST(state, X_MAX)) { NOLESS(largest_sensorless_adj, offset_sensorless_adj.a); DEBUG_ECHOLNPGM("Endstop_X: ", largest_sensorless_adj, " TowerX"); } - if (TEST(endstops.state(), Y_MAX)) { + if (TEST(state, Y_MAX)) { NOLESS(largest_sensorless_adj, offset_sensorless_adj.b); DEBUG_ECHOLNPGM("Endstop_Y: ", largest_sensorless_adj, " TowerY"); } - if (TEST(endstops.state(), Z_MAX)) { + if (TEST(state, Z_MAX)) { NOLESS(largest_sensorless_adj, offset_sensorless_adj.c); DEBUG_ECHOLNPGM("Endstop_Z: ", largest_sensorless_adj, " TowerZ"); } diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 5b1f7149f248..8abff81ea881 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -33,13 +33,15 @@ #include "../lcd/e3v2/proui/dwin.h" #endif +#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) +#include "../core/debug_out.h" + #if HAS_BED_PROBE enum ProbePtRaise : uint8_t { PROBE_PT_NONE, // No raise or stow after run_z_probe PROBE_PT_STOW, // Do a complete stow after run_z_probe PROBE_PT_LAST_STOW, // Stow for sure, even in BLTouch HS mode - PROBE_PT_RAISE, // Raise to "between" clearance after run_z_probe - PROBE_PT_BIG_RAISE // Raise to big clearance after run_z_probe + PROBE_PT_RAISE // Raise to "between" clearance after run_z_probe }; #endif @@ -76,9 +78,7 @@ class Probe { public: #if ENABLED(SENSORLESS_PROBING) - typedef struct { - bool x:1, y:1, z:1; - } sense_bool_t; + typedef struct { bool x:1, y:1, z:1; } sense_bool_t; static sense_bool_t test_sensitivity; #endif @@ -86,7 +86,7 @@ class Probe { static xyz_pos_t offset; - #if EITHER(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) + #if ANY(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) static void preheat_for_probing(const celsius_t hotend_temp, const celsius_t bed_temp, const bool early=false); #endif @@ -116,7 +116,7 @@ class Probe { } #endif - #else + #else // !IS_KINEMATIC /** * Return whether the given position is within the bed, and whether the nozzle @@ -138,9 +138,10 @@ class Probe { } } - #endif + #endif // !IS_KINEMATIC static void move_z_after_probing() { + DEBUG_SECTION(mzah, "move_z_after_probing", DEBUGGING(LEVELING)); #ifdef Z_AFTER_PROBING do_z_clearance(Z_AFTER_PROBING, true); // Move down still permitted #endif @@ -150,17 +151,18 @@ class Probe { return probe_at_point(pos.x, pos.y, raise_after, verbose_level, probe_relative, sanity_check); } - #else + #else // !HAS_BED_PROBE static constexpr xyz_pos_t offset = xyz_pos_t(NUM_AXIS_ARRAY_1(0)); // See #16767 static bool set_deployed(const bool) { return false; } - static bool can_reach(const_float_t rx, const_float_t ry, const bool=true) { 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(TERN_(HAS_X_AXIS, rx) OPTARG(HAS_Y_AXIS, ry)); } - #endif + #endif // !HAS_BED_PROBE static void move_z_after_homing() { + DEBUG_SECTION(mzah, "move_z_after_homing", DEBUGGING(LEVELING)); #if ALL(DWIN_LCD_PROUI, INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) || defined(Z_AFTER_HOMING) do_z_clearance(Z_POST_CLEARANCE, true); #elif HAS_BED_PROBE diff --git a/Marlin/src/module/scara.cpp b/Marlin/src/module/scara.cpp index 4c42ace884de..0f00ab564338 100644 --- a/Marlin/src/module/scara.cpp +++ b/Marlin/src/module/scara.cpp @@ -39,7 +39,7 @@ float segments_per_second = DEFAULT_SEGMENTS_PER_SECOND; -#if EITHER(MORGAN_SCARA, MP_SCARA) +#if ANY(MORGAN_SCARA, MP_SCARA) static constexpr xy_pos_t scara_offset = { SCARA_OFFSET_X, SCARA_OFFSET_Y }; @@ -229,9 +229,7 @@ float segments_per_second = DEFAULT_SEGMENTS_PER_SECOND; // Move all carriages together linearly until an endstop is hit. //do_blocking_move_to_xy_z(pos, mlz, homing_feedrate(Z_AXIS)); - current_position.x = 0 ; - current_position.y = 0 ; - current_position.z = max_length(Z_AXIS) ; + current_position.set(0, 0, max_length(Z_AXIS)); line_to_current_position(homing_feedrate(Z_AXIS)); planner.synchronize(); diff --git a/Marlin/src/module/servo.cpp b/Marlin/src/module/servo.cpp index 2782be1f2bd9..6ce12c9abecf 100644 --- a/Marlin/src/module/servo.cpp +++ b/Marlin/src/module/servo.cpp @@ -37,22 +37,30 @@ hal_servo_t servo[NUM_SERVOS]; #endif void servo_init() { - #if NUM_SERVOS >= 1 && HAS_SERVO_0 + #if HAS_SERVO_0 servo[0].attach(SERVO0_PIN); servo[0].detach(); // Just set up the pin. We don't have a position yet. Don't move to a random position. #endif - #if NUM_SERVOS >= 2 && HAS_SERVO_1 + #if HAS_SERVO_1 servo[1].attach(SERVO1_PIN); servo[1].detach(); #endif - #if NUM_SERVOS >= 3 && HAS_SERVO_2 + #if HAS_SERVO_2 servo[2].attach(SERVO2_PIN); servo[2].detach(); #endif - #if NUM_SERVOS >= 4 && HAS_SERVO_3 + #if HAS_SERVO_3 servo[3].attach(SERVO3_PIN); servo[3].detach(); #endif + #if HAS_SERVO_4 + servo[4].attach(SERVO4_PIN); + servo[4].detach(); + #endif + #if HAS_SERVO_5 + servo[5].attach(SERVO5_PIN); + servo[5].detach(); + #endif } #endif // HAS_SERVOS diff --git a/Marlin/src/module/servo.h b/Marlin/src/module/servo.h index 2ed992aa03f7..0286fe905bda 100644 --- a/Marlin/src/module/servo.h +++ b/Marlin/src/module/servo.h @@ -44,8 +44,13 @@ #endif #if ENABLED(SWITCHING_NOZZLE) - constexpr uint16_t sasn[] = SWITCHING_NOZZLE_SERVO_ANGLES; - static_assert(COUNT(sasn) == 2, "SWITCHING_NOZZLE_SERVO_ANGLES needs 2 angles."); + #if SWITCHING_NOZZLE_TWO_SERVOS + constexpr uint16_t sasn[][2] = SWITCHING_NOZZLE_SERVO_ANGLES; + static_assert(COUNT(sasn) == 2, "SWITCHING_NOZZLE_SERVO_ANGLES (with SWITCHING_NOZZLE_E1_SERVO_NR) needs 2 sets of angles: { { lower, raise }, { lower, raise } }."); + #else + constexpr uint16_t sasn[] = SWITCHING_NOZZLE_SERVO_ANGLES; + static_assert(COUNT(sasn) == 2, "SWITCHING_NOZZLE_SERVO_ANGLES needs two angles: { E0, E1 }."); + #endif #else constexpr uint16_t sasn[2] = { 0 }; #endif @@ -75,12 +80,15 @@ #define Z_PROBE_SERVO_NR -1 #endif - #define ASRC(N,I) ( \ - N == SWITCHING_EXTRUDER_SERVO_NR ? sase[I] \ - : N == SWITCHING_EXTRUDER_E23_SERVO_NR ? sase[I+2] \ - : N == SWITCHING_NOZZLE_SERVO_NR ? sasn[I] \ - : N == Z_PROBE_SERVO_NR ? sazp[I] \ - : 0 ) + #define SASN(J,I) TERN(SWITCHING_NOZZLE_TWO_SERVOS, sasn[J][I], sasn[I]) + + #define ASRC(N,I) ( \ + N == SWITCHING_EXTRUDER_SERVO_NR ? sase[I] \ + : N == SWITCHING_EXTRUDER_E23_SERVO_NR ? sase[I+2] \ + : N == SWITCHING_NOZZLE_SERVO_NR ? SASN(0,I) \ + TERN_(SWITCHING_NOZZLE_TWO_SERVOS, : N == SWITCHING_NOZZLE_E1_SERVO_NR ? SASN(1,I)) \ + : N == Z_PROBE_SERVO_NR ? sazp[I] \ + : 0 ) #if ENABLED(EDITABLE_SERVO_ANGLES) extern uint16_t servo_angles[NUM_SERVOS][2]; @@ -97,6 +105,12 @@ , { ASRC(2,0), ASRC(2,1) } #if NUM_SERVOS > 3 , { ASRC(3,0), ASRC(3,1) } + #if NUM_SERVOS > 4 + , { ASRC(4,0), ASRC(4,1) } + #if NUM_SERVOS > 5 + , { ASRC(5,0), ASRC(5,1) } + #endif + #endif #endif #endif #endif diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index e01bd9ae600a..e76f6b43122f 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -56,7 +56,7 @@ #include "../gcode/gcode.h" #include "../MarlinCore.h" -#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) +#if ANY(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) #include "../HAL/shared/eeprom_api.h" #endif @@ -90,12 +90,6 @@ #include "servo.h" #endif -#if HAS_SERVOS && HAS_SERVO_ANGLES - #define EEPROM_NUM_SERVOS NUM_SERVOS -#else - #define EEPROM_NUM_SERVOS NUM_SERVO_PLUGS -#endif - #include "../feature/fwretract.h" #if ENABLED(POWER_LOSS_RECOVERY) @@ -182,10 +176,10 @@ #define _EN_ITEM(N) , E##N #define _EN1_ITEM(N) , E##N:1 -typedef struct { uint16_t MAIN_AXIS_NAMES, X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } per_stepper_uint16_t; -typedef struct { uint32_t MAIN_AXIS_NAMES, X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } per_stepper_uint32_t; -typedef struct { int16_t MAIN_AXIS_NAMES, X2, Y2, Z2, Z3, Z4; } mot_stepper_int16_t; -typedef struct { bool NUM_AXIS_LIST(X:1, Y:1, Z:1, I:1, J:1, K:1, U:1, V:1, W:1), X2:1, Y2:1, Z2:1, Z3:1, Z4:1 REPEAT(E_STEPPERS, _EN1_ITEM); } per_stepper_bool_t; +typedef struct { uint16_t MAIN_AXIS_NAMES_ X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } per_stepper_uint16_t; +typedef struct { uint32_t MAIN_AXIS_NAMES_ X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } per_stepper_uint32_t; +typedef struct { int16_t MAIN_AXIS_NAMES_ X2, Y2, Z2, Z3, Z4; } mot_stepper_int16_t; +typedef struct { bool NUM_AXIS_LIST_(X:1, Y:1, Z:1, I:1, J:1, K:1, U:1, V:1, W:1) X2:1, Y2:1, Z2:1, Z3:1, Z4:1 REPEAT(E_STEPPERS, _EN1_ITEM); } per_stepper_bool_t; #undef _EN_ITEM @@ -227,7 +221,9 @@ typedef struct SettingsDataStruct { // // Home Offset // - xyz_pos_t home_offset; // M206 XYZ / M665 TPZ + #if NUM_AXES + xyz_pos_t home_offset; // M206 XYZ / M665 TPZ + #endif // // Hotend Offset @@ -259,8 +255,9 @@ typedef struct SettingsDataStruct { // // HAS_BED_PROBE // - - xyz_pos_t probe_offset; // M851 X Y Z + #if NUM_AXES + xyz_pos_t probe_offset; // M851 X Y Z + #endif // // ABL_PLANAR @@ -297,7 +294,9 @@ typedef struct SettingsDataStruct { // // SERVO_ANGLES // - uint16_t servo_angles[EEPROM_NUM_SERVOS][2]; // M281 P L U + #if HAS_SERVO_ANGLES + uint16_t servo_angles[NUM_SERVOS][2]; // M281 P L U + #endif // // Temperature first layer compensation values @@ -471,12 +470,16 @@ typedef struct SettingsDataStruct { // // CNC_COORDINATE_SYSTEMS // - xyz_pos_t coordinate_system[MAX_COORDINATE_SYSTEMS]; // G54-G59.3 + #if NUM_AXES + xyz_pos_t coordinate_system[MAX_COORDINATE_SYSTEMS]; // G54-G59.3 + #endif // // SKEW_CORRECTION // - skew_factor_t planner_skew_factor; // M852 I J K + #if ENABLED(SKEW_CORRECTION) + skew_factor_t planner_skew_factor; // M852 I J K + #endif // // ADVANCED_PAUSE_FEATURE @@ -495,9 +498,11 @@ typedef struct SettingsDataStruct { // // BACKLASH_COMPENSATION // - xyz_float_t backlash_distance_mm; // M425 X Y Z - uint8_t backlash_correction; // M425 F - float backlash_smoothing_mm; // M425 S + #if NUM_AXES + xyz_float_t backlash_distance_mm; // M425 X Y Z + uint8_t backlash_correction; // M425 F + float backlash_smoothing_mm; // M425 S + #endif // // EXTENSIBLE_UI @@ -585,12 +590,12 @@ typedef struct SettingsDataStruct { // Input Shaping // #if ENABLED(INPUT_SHAPING_X) - float shaping_x_frequency, // M593 X F - shaping_x_zeta; // M593 X D + float shaping_x_frequency, // M593 X F + shaping_x_zeta; // M593 X D #endif #if ENABLED(INPUT_SHAPING_Y) - float shaping_y_frequency, // M593 Y F - shaping_y_zeta; // M593 Y D + float shaping_y_frequency, // M593 Y F + shaping_y_zeta; // M593 Y D #endif } SettingsData; @@ -656,18 +661,14 @@ void MarlinSettings::postprocess() { if (oldpos != current_position) report_current_position(); - // Moved as last update due to interference with Neopixel init + // Moved as last update due to interference with NeoPixel init TERN_(HAS_LCD_CONTRAST, ui.refresh_contrast()); TERN_(HAS_LCD_BRIGHTNESS, ui.refresh_brightness()); - - #if LCD_BACKLIGHT_TIMEOUT_MINS - ui.refresh_backlight_timeout(); - #elif HAS_DISPLAY_SLEEP - ui.refresh_screen_timeout(); - #endif + TERN_(HAS_BACKLIGHT_TIMEOUT, ui.refresh_backlight_timeout()); + TERN_(HAS_DISPLAY_SLEEP, ui.refresh_screen_timeout()); } -#if BOTH(PRINTCOUNTER, EEPROM_SETTINGS) +#if ALL(PRINTCOUNTER, EEPROM_SETTINGS) #include "printcounter.h" static_assert( !WITHIN(STATS_EEPROM_ADDRESS, EEPROM_OFFSET, EEPROM_OFFSET + sizeof(SettingsData)) && @@ -687,7 +688,8 @@ void MarlinSettings::postprocess() { bool MarlinSettings::sd_update_status() { uint8_t val; - persistentStore.read_data(SD_FIRMWARE_UPDATE_EEPROM_ADDR, &val); + int pos = SD_FIRMWARE_UPDATE_EEPROM_ADDR; + persistentStore.read_data(pos, &val); return (val == SD_FIRMWARE_UPDATE_ACTIVE_VALUE); } @@ -711,10 +713,10 @@ void MarlinSettings::postprocess() { // This file simply uses the DEBUG_ECHO macros to implement EEPROM_CHITCHAT. // For deeper debugging of EEPROM issues enable DEBUG_EEPROM_READWRITE. // -#define DEBUG_OUT EITHER(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) +#define DEBUG_OUT ANY(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" -#if BOTH(EEPROM_CHITCHAT, HOST_PROMPT_SUPPORT) +#if ALL(EEPROM_CHITCHAT, HOST_PROMPT_SUPPORT) #define HOST_EEPROM_CHITCHAT 1 #endif @@ -825,6 +827,7 @@ void MarlinSettings::postprocess() { // // Home Offset // + #if NUM_AXES { _FIELD_TEST(home_offset); @@ -837,6 +840,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(home_offset); #endif } + #endif // NUM_AXES // // Hotend Offsets, if any @@ -844,7 +848,7 @@ void MarlinSettings::postprocess() { { #if HAS_HOTEND_OFFSET // Skip hotend 0 which must be 0 - LOOP_S_L_N(e, 1, HOTENDS) + for (uint8_t e = 1; e < HOTENDS; ++e) EEPROM_WRITE(hotend_offset[e]); #endif } @@ -883,7 +887,7 @@ void MarlinSettings::postprocess() { { #if ENABLED(MESH_BED_LEVELING) static_assert( - sizeof(bedlevel.z_values) == (GRID_MAX_POINTS) * sizeof(bedlevel.z_values[0][0]), + sizeof(bedlevel.z_values) == GRID_MAX_POINTS * sizeof(bedlevel.z_values[0][0]), "MBL Z array is the wrong size." ); #else @@ -911,6 +915,7 @@ void MarlinSettings::postprocess() { // // Probe XYZ Offsets // + #if NUM_AXES { _FIELD_TEST(probe_offset); #if HAS_BED_PROBE @@ -920,6 +925,7 @@ void MarlinSettings::postprocess() { #endif EEPROM_WRITE(zpo); } + #endif // // Planar Bed Leveling matrix @@ -939,7 +945,7 @@ void MarlinSettings::postprocess() { { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) static_assert( - sizeof(bedlevel.z_values) == (GRID_MAX_POINTS) * sizeof(bedlevel.z_values[0][0]), + sizeof(bedlevel.z_values) == GRID_MAX_POINTS * sizeof(bedlevel.z_values[0][0]), "Bilinear Z array is the wrong size." ); #endif @@ -994,13 +1000,12 @@ void MarlinSettings::postprocess() { // // Servo Angles // + #if HAS_SERVO_ANGLES { _FIELD_TEST(servo_angles); - #if !HAS_SERVO_ANGLES - uint16_t servo_angles[EEPROM_NUM_SERVOS][2] = { { 0, 0 } }; - #endif EEPROM_WRITE(servo_angles); } + #endif // // Thermal first layer compensation values @@ -1375,7 +1380,7 @@ void MarlinSettings::postprocess() { #else #define _EN_ITEM(N) , .E##N = 30 const per_stepper_uint32_t tmc_hybrid_threshold = { - NUM_AXIS_LIST(.X = 100, .Y = 100, .Z = 3, .I = 3, .J = 3, .K = 3, .U = 3, .V = 3, .W = 3), + NUM_AXIS_LIST_(.X = 100, .Y = 100, .Z = 3, .I = 3, .J = 3, .K = 3, .U = 3, .V = 3, .W = 3) .X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3 REPEAT(E_STEPPERS, _EN_ITEM) }; @@ -1473,19 +1478,21 @@ void MarlinSettings::postprocess() { // // CNC Coordinate Systems // - - _FIELD_TEST(coordinate_system); - - #if DISABLED(CNC_COORDINATE_SYSTEMS) - const xyz_pos_t coordinate_system[MAX_COORDINATE_SYSTEMS] = { { 0 } }; + #if NUM_AXES + _FIELD_TEST(coordinate_system); + #if DISABLED(CNC_COORDINATE_SYSTEMS) + const xyz_pos_t coordinate_system[MAX_COORDINATE_SYSTEMS] = { { 0 } }; + #endif + EEPROM_WRITE(TERN(CNC_COORDINATE_SYSTEMS, gcode.coordinate_system, coordinate_system)); #endif - EEPROM_WRITE(TERN(CNC_COORDINATE_SYSTEMS, gcode.coordinate_system, coordinate_system)); // // Skew correction factors // - _FIELD_TEST(planner_skew_factor); - EEPROM_WRITE(planner.skew_factor); + #if ENABLED(SKEW_CORRECTION) + _FIELD_TEST(planner_skew_factor); + EEPROM_WRITE(planner.skew_factor); + #endif // // Advanced Pause filament load & unload lengths @@ -1512,6 +1519,7 @@ void MarlinSettings::postprocess() { // // Backlash Compensation // + #if NUM_AXES { #if ENABLED(BACKLASH_GCODE) xyz_float_t backlash_distance_mm; @@ -1531,6 +1539,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(backlash_correction); EEPROM_WRITE(backlash_smoothing_mm); } + #endif // NUM_AXES // // Extensible UI User Data @@ -1642,13 +1651,13 @@ void MarlinSettings::postprocess() { // #if ENABLED(MPCTEMP) HOTEND_LOOP() - EEPROM_WRITE(thermalManager.temp_hotend[e].constants); + EEPROM_WRITE(thermalManager.temp_hotend[e].mpc); #endif // // Input Shaping - /// - #if HAS_SHAPING + // + #if HAS_ZV_SHAPING #if ENABLED(INPUT_SHAPING_X) EEPROM_WRITE(stepper.get_shaping_frequency(X_AXIS)); EEPROM_WRITE(stepper.get_shaping_damping_ratio(X_AXIS)); @@ -1811,6 +1820,7 @@ void MarlinSettings::postprocess() { // // Home Offset (M206 / M665) // + #if NUM_AXES { _FIELD_TEST(home_offset); @@ -1823,6 +1833,7 @@ void MarlinSettings::postprocess() { EEPROM_READ(home_offset); #endif } + #endif // NUM_AXES // // Hotend Offsets, if any @@ -1830,7 +1841,7 @@ void MarlinSettings::postprocess() { { #if HAS_HOTEND_OFFSET // Skip hotend 0 which must be 0 - LOOP_S_L_N(e, 1, HOTENDS) + for (uint8_t e = 1; e < HOTENDS; ++e) EEPROM_READ(hotend_offset[e]); #endif } @@ -1901,6 +1912,7 @@ void MarlinSettings::postprocess() { // // Probe Z Offset // + #if NUM_AXES { _FIELD_TEST(probe_offset); #if HAS_BED_PROBE @@ -1910,6 +1922,7 @@ void MarlinSettings::postprocess() { #endif EEPROM_READ(zpo); } + #endif // // Planar Bed Leveling matrix @@ -1945,7 +1958,7 @@ void MarlinSettings::postprocess() { if (grid_max_x == (GRID_MAX_POINTS_X) && grid_max_y == (GRID_MAX_POINTS_Y)) { if (!validating) set_bed_leveling_enabled(false); bedlevel.set_grid(spacing, start); - EEPROM_READ(bedlevel.z_values); // 9 to 256 floats + EEPROM_READ(bedlevel.z_values); // 9 to 256 floats } else if (grid_max_x > (GRID_MAX_POINTS_X) || grid_max_y > (GRID_MAX_POINTS_Y)) { eeprom_error = ERR_EEPROM_CORRUPT; @@ -1988,15 +2001,17 @@ void MarlinSettings::postprocess() { // // SERVO_ANGLES // + #if HAS_SERVO_ANGLES { _FIELD_TEST(servo_angles); #if ENABLED(EDITABLE_SERVO_ANGLES) - uint16_t (&servo_angles_arr)[EEPROM_NUM_SERVOS][2] = servo_angles; + uint16_t (&servo_angles_arr)[NUM_SERVOS][2] = servo_angles; #else - uint16_t servo_angles_arr[EEPROM_NUM_SERVOS][2]; + uint16_t servo_angles_arr[NUM_SERVOS][2]; #endif EEPROM_READ(servo_angles_arr); } + #endif // // Thermal first layer compensation values @@ -2491,6 +2506,7 @@ void MarlinSettings::postprocess() { // // CNC Coordinate System // + #if NUM_AXES { _FIELD_TEST(coordinate_system); #if ENABLED(CNC_COORDINATE_SYSTEMS) @@ -2501,10 +2517,12 @@ void MarlinSettings::postprocess() { EEPROM_READ(coordinate_system); #endif } + #endif // // Skew correction factors // + #if ENABLED(SKEW_CORRECTION) { skew_factor_t skew_factor; _FIELD_TEST(planner_skew_factor); @@ -2519,6 +2537,7 @@ void MarlinSettings::postprocess() { } #endif } + #endif // // Advanced Pause filament load & unload lengths @@ -2544,6 +2563,7 @@ void MarlinSettings::postprocess() { // // Backlash Compensation // + #if NUM_AXES { xyz_float_t backlash_distance_mm; uint8_t backlash_correction; @@ -2562,6 +2582,7 @@ void MarlinSettings::postprocess() { #endif #endif } + #endif // NUM_AXES // // Extensible UI User Data @@ -2677,7 +2698,7 @@ void MarlinSettings::postprocess() { #if ENABLED(MPCTEMP) { HOTEND_LOOP() - EEPROM_READ(thermalManager.temp_hotend[e].constants); + EEPROM_READ(thermalManager.temp_hotend[e].mpc); } #endif @@ -2726,14 +2747,14 @@ void MarlinSettings::postprocess() { bedlevel.report_state(); if (!bedlevel.sanity_check()) { - #if BOTH(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) + #if ALL(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) bedlevel.echo_name(); DEBUG_ECHOLNPGM(" initialized.\n"); #endif } else { eeprom_error = ERR_EEPROM_CORRUPT; - #if BOTH(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) + #if ALL(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) DEBUG_ECHOPGM("?Can't enable "); bedlevel.echo_name(); DEBUG_ECHOLNPGM("."); @@ -2811,7 +2832,7 @@ void MarlinSettings::postprocess() { return success; } reset(); - #if EITHER(EEPROM_AUTO_INIT, EEPROM_INIT_NOW) + #if ANY(EEPROM_AUTO_INIT, EEPROM_INIT_NOW) (void)save(); SERIAL_ECHO_MSG("EEPROM Initialized"); #endif @@ -2971,7 +2992,7 @@ void MarlinSettings::reset() { planner.settings.min_travel_feedrate_mm_s = feedRate_t(DEFAULT_MINTRAVELFEEDRATE); #if HAS_CLASSIC_JERK - #ifndef DEFAULT_XJERK + #if HAS_X_AXIS && !defined(DEFAULT_XJERK) #define DEFAULT_XJERK 0 #endif #if HAS_Y_AXIS && !defined(DEFAULT_YJERK) @@ -3134,9 +3155,7 @@ void MarlinSettings::reset() { // // BLTouch // - #ifdef BLTOUCH_HS_MODE - bltouch.high_speed_mode = ENABLED(BLTOUCH_HS_MODE); - #endif + TERN_(HAS_BLTOUCH_HS_MODE, bltouch.high_speed_mode = BLTOUCH_HS_MODE); // // Kinematic Settings (Delta, SCARA, TPARA, Polargraph...) @@ -3210,7 +3229,7 @@ void MarlinSettings::reset() { #if HAS_FAN constexpr uint8_t fpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, FAN_SPEED) }; #endif - LOOP_L_N(i, PREHEAT_COUNT) { + for (uint8_t i = 0; i < PREHEAT_COUNT; ++i) { TERN_(HAS_HOTEND, ui.material_preset[i].hotend_temp = hpre[i]); TERN_(HAS_HEATED_BED, ui.material_preset[i].bed_temp = bpre[i]); TERN_(HAS_FAN, ui.material_preset[i].fan_speed = fpre[i]); @@ -3288,7 +3307,6 @@ void MarlinSettings::reset() { // // Heated Bed PID // - #if ENABLED(PIDTEMPBED) thermalManager.temp_bed.pid.set(DEFAULT_bedKp, DEFAULT_bedKi, DEFAULT_bedKd); #endif @@ -3296,7 +3314,6 @@ void MarlinSettings::reset() { // // Heated Chamber PID // - #if ENABLED(PIDTEMPCHAMBER) thermalManager.temp_chamber.pid.set(DEFAULT_chamberKp, DEFAULT_chamberKi, DEFAULT_chamberKd); #endif @@ -3348,13 +3365,12 @@ void MarlinSettings::reset() { // // Volumetric & Filament Size // - #if DISABLED(NO_VOLUMETRICS) parser.volumetric_enabled = ENABLED(VOLUMETRIC_DEFAULT_ON); - LOOP_L_N(q, COUNT(planner.filament_size)) + for (uint8_t q = 0; q < COUNT(planner.filament_size); ++q) planner.filament_size[q] = DEFAULT_NOMINAL_FILAMENT_DIA; #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) - LOOP_L_N(q, COUNT(planner.volumetric_extruder_limit)) + for (uint8_t q = 0; q < COUNT(planner.volumetric_extruder_limit); ++q) planner.volumetric_extruder_limit[q] = DEFAULT_VOLUMETRIC_EXTRUDER_LIMIT; #endif #endif @@ -3385,7 +3401,7 @@ void MarlinSettings::reset() { #if HAS_MOTOR_CURRENT_PWM constexpr uint32_t tmp_motor_current_setting[MOTOR_CURRENT_COUNT] = PWM_MOTOR_CURRENT; - LOOP_L_N(q, MOTOR_CURRENT_COUNT) + for (uint8_t q = 0; q < MOTOR_CURRENT_COUNT; ++q) stepper.set_digipot_current(q, (stepper.motor_current_setting[q] = tmp_motor_current_setting[q])); #endif @@ -3395,7 +3411,7 @@ void MarlinSettings::reset() { #if HAS_MOTOR_CURRENT_SPI static constexpr uint32_t tmp_motor_current_setting[] = DIGIPOT_MOTOR_CURRENT; DEBUG_ECHOLNPGM("Writing Digipot"); - LOOP_L_N(q, COUNT(tmp_motor_current_setting)) + for (uint8_t q = 0; q < COUNT(tmp_motor_current_setting); ++q) stepper.set_digipot_current(q, tmp_motor_current_setting[q]); DEBUG_ECHOLNPGM("Digipot Written"); #endif @@ -3473,22 +3489,22 @@ void MarlinSettings::reset() { static_assert(COUNT(_filament_heat_capacity_permm) == HOTENDS, "FILAMENT_HEAT_CAPACITY_PERMM must have HOTENDS items."); HOTEND_LOOP() { - MPC_t &constants = thermalManager.temp_hotend[e].constants; - constants.heater_power = _mpc_heater_power[e]; - constants.block_heat_capacity = _mpc_block_heat_capacity[e]; - constants.sensor_responsiveness = _mpc_sensor_responsiveness[e]; - constants.ambient_xfer_coeff_fan0 = _mpc_ambient_xfer_coeff[e]; + MPC_t &mpc = thermalManager.temp_hotend[e].mpc; + mpc.heater_power = _mpc_heater_power[e]; + mpc.block_heat_capacity = _mpc_block_heat_capacity[e]; + mpc.sensor_responsiveness = _mpc_sensor_responsiveness[e]; + mpc.ambient_xfer_coeff_fan0 = _mpc_ambient_xfer_coeff[e]; #if ENABLED(MPC_INCLUDE_FAN) - constants.fan255_adjustment = _mpc_ambient_xfer_coeff_fan255[e] - _mpc_ambient_xfer_coeff[e]; + mpc.fan255_adjustment = _mpc_ambient_xfer_coeff_fan255[e] - _mpc_ambient_xfer_coeff[e]; #endif - constants.filament_heat_capacity_permm = _filament_heat_capacity_permm[e]; + mpc.filament_heat_capacity_permm = _filament_heat_capacity_permm[e]; } #endif // // Input Shaping // - #if HAS_SHAPING + #if HAS_ZV_SHAPING #if ENABLED(INPUT_SHAPING_X) stepper.set_shaping_frequency(X_AXIS, SHAPING_FREQ_X); stepper.set_shaping_damping_ratio(X_AXIS, SHAPING_ZETA_X); @@ -3501,7 +3517,7 @@ void MarlinSettings::reset() { postprocess(); - #if EITHER(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) + #if ANY(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) FSTR_P const hdsl = F("Hardcoded Default Settings Loaded"); TERN_(HOST_EEPROM_CHITCHAT, hostui.notify(hdsl)); DEBUG_ECHO_START(); DEBUG_ECHOLNF(hdsl); @@ -3597,8 +3613,8 @@ void MarlinSettings::reset() { #if ENABLED(MESH_BED_LEVELING) if (leveling_is_valid()) { - LOOP_L_N(py, GRID_MAX_POINTS_Y) { - LOOP_L_N(px, GRID_MAX_POINTS_X) { + for (uint8_t py = 0; py < GRID_MAX_POINTS_Y; ++py) { + for (uint8_t px = 0; px < GRID_MAX_POINTS_X; ++px) { CONFIG_ECHO_START(); SERIAL_ECHOPGM(" G29 S3 I", px, " J", py); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(bedlevel.z_values[px][py]), 5); @@ -3623,8 +3639,8 @@ void MarlinSettings::reset() { #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) if (leveling_is_valid()) { - LOOP_L_N(py, GRID_MAX_POINTS_Y) { - LOOP_L_N(px, GRID_MAX_POINTS_X) { + for (uint8_t py = 0; py < GRID_MAX_POINTS_Y; ++py) { + for (uint8_t px = 0; px < GRID_MAX_POINTS_X; ++px) { CONFIG_ECHO_START(); SERIAL_ECHOPGM(" G29 W I", px, " J", py); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(bedlevel.z_values[px][py]), 5); @@ -3654,7 +3670,7 @@ void MarlinSettings::reset() { // // M666 Endstops Adjustment // - #if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) + #if ANY(DELTA, HAS_EXTRA_ENDSTOPS) gcode.M666_report(forReplay); #endif @@ -3676,7 +3692,7 @@ void MarlinSettings::reset() { TERN_(PIDTEMPCHAMBER, gcode.M309_report(forReplay)); #if HAS_USER_THERMISTORS - LOOP_L_N(i, USER_THERMISTORS) + for (uint8_t i = 0; i < USER_THERMISTORS; ++i) thermalManager.M305_report(i, forReplay); #endif @@ -3749,7 +3765,7 @@ void MarlinSettings::reset() { // // Input Shaping // - TERN_(HAS_SHAPING, gcode.M593_report(forReplay)); + TERN_(HAS_ZV_SHAPING, gcode.M593_report(forReplay)); // // Linear Advance diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 1705c60daa20..ede23b037695 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -143,7 +143,7 @@ Stepper stepper; // Singleton // public: -#if EITHER(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) +#if ANY(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) bool Stepper::separate_multi_axis = false; #endif @@ -177,7 +177,7 @@ bool Stepper::abort_current_block; bool Stepper::locked_Y_motor = false, Stepper::locked_Y2_motor = false; #endif -#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) +#if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) bool Stepper::locked_Z_motor = false, Stepper::locked_Z2_motor = false #if NUM_Z_STEPPERS >= 3 , Stepper::locked_Z3_motor = false @@ -206,7 +206,7 @@ uint32_t Stepper::advance_divisor = 0, Stepper::decelerate_after, // The count at which to start decelerating Stepper::step_event_count; // The total event count for the current block -#if EITHER(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) +#if ANY(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) uint8_t Stepper::stepper_extruder; #else constexpr uint8_t Stepper::stepper_extruder; @@ -232,7 +232,7 @@ uint32_t Stepper::advance_divisor = 0, Stepper::la_advance_steps = 0; #endif -#if HAS_SHAPING +#if HAS_ZV_SHAPING shaping_time_t ShapingQueue::now = 0; shaping_time_t ShapingQueue::times[shaping_echoes]; shaping_echo_axis_t ShapingQueue::echo_axes[shaping_echoes]; @@ -596,7 +596,7 @@ void Stepper::disable_all_steppers() { * COREXZ: X_AXIS=A_AXIS and Z_AXIS=C_AXIS * COREYZ: Y_AXIS=B_AXIS and Z_AXIS=C_AXIS */ -void Stepper::set_directions() { +void Stepper::apply_directions() { DIR_WAIT_BEFORE(); @@ -1487,7 +1487,7 @@ void Stepper::isr() { // Enable ISRs to reduce USART processing latency hal.isr_on(); - TERN_(HAS_SHAPING, shaping_isr()); // Do Shaper stepping, if needed + TERN_(HAS_ZV_SHAPING, shaping_isr()); // Do Shaper stepping, if needed if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses @@ -1535,7 +1535,7 @@ void Stepper::isr() { // nextMainISR -= interval; - TERN_(HAS_SHAPING, ShapingQueue::decrement_delays(interval)); + TERN_(HAS_ZV_SHAPING, ShapingQueue::decrement_delays(interval)); TERN_(LIN_ADVANCE, if (nextAdvanceISR != LA_ADV_NEVER) nextAdvanceISR -= interval); TERN_(INTEGRATED_BABYSTEPPING, if (nextBabystepISR != BABYSTEP_NEVER) nextBabystepISR -= interval); @@ -1628,7 +1628,7 @@ void Stepper::pulse_phase_isr() { abort_current_block = false; if (current_block) { discard_current_block(); - #if HAS_SHAPING + #if HAS_ZV_SHAPING ShapingQueue::purge(); #if ENABLED(INPUT_SHAPING_X) shaping_x.delta_error = 0; @@ -1864,7 +1864,7 @@ void Stepper::pulse_phase_isr() { PULSE_PREP(W); #endif - #if EITHER(HAS_E0_STEP, MIXING_EXTRUDER) + #if ANY(HAS_E0_STEP, MIXING_EXTRUDER) PULSE_PREP(E); #if ENABLED(LIN_ADVANCE) @@ -1877,7 +1877,7 @@ void Stepper::pulse_phase_isr() { #endif #endif - #if HAS_SHAPING + #if HAS_ZV_SHAPING // record an echo if a step is needed in the primary bresenham const bool x_step = TERN0(INPUT_SHAPING_X, shaping_x.enabled && step_needed[X_AXIS]), y_step = TERN0(INPUT_SHAPING_Y, shaping_y.enabled && step_needed[Y_AXIS]); @@ -1991,7 +1991,7 @@ void Stepper::pulse_phase_isr() { } while (--events_to_do); } -#if HAS_SHAPING +#if HAS_ZV_SHAPING void Stepper::shaping_isr() { xy_bool_t step_needed{0}; @@ -2043,7 +2043,7 @@ void Stepper::pulse_phase_isr() { } } -#endif // HAS_SHAPING +#endif // HAS_ZV_SHAPING // Calculate timer interval, with all limits applied. uint32_t Stepper::calc_timer_interval(uint32_t step_rate) { @@ -2269,7 +2269,7 @@ uint32_t Stepper::block_phase_isr() { } #endif // LIN_ADVANCE - /* + /** * Adjust Laser Power - Decelerating * trap_ramp_entry_decr - holds the precalculated value to decrease the current power per decel step. */ @@ -2422,7 +2422,7 @@ uint32_t Stepper::block_phase_isr() { * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Y or Z, handled below) * If DeltaA == DeltaB, the movement is only in the 1st axis (X) */ - #if EITHER(COREXY, COREXZ) + #if ANY(COREXY, COREXZ) #define X_CMP(A,B) ((A)==(B)) #else #define X_CMP(A,B) ((A)!=(B)) @@ -2442,7 +2442,7 @@ uint32_t Stepper::block_phase_isr() { * If DeltaA == DeltaB, the movement is only in the 1st axis (X or Y) * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Y or Z) */ - #if EITHER(COREYX, COREYZ) + #if ANY(COREYX, COREYZ) #define Y_CMP(A,B) ((A)==(B)) #else #define Y_CMP(A,B) ((A)!=(B)) @@ -2462,7 +2462,7 @@ uint32_t Stepper::block_phase_isr() { * If DeltaA == DeltaB, the movement is only in the 1st axis (X or Y, already handled above) * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Z) */ - #if EITHER(COREZX, COREZY) + #if ANY(COREZX, COREZY) #define Z_CMP(A,B) ((A)==(B)) #else #define Z_CMP(A,B) ((A)!=(B)) @@ -2705,7 +2705,7 @@ void Stepper::init() { #if MB(ALLIGATOR) const float motor_current[] = MOTOR_CURRENT; unsigned int digipot_motor = 0; - LOOP_L_N(i, 3 + EXTRUDERS) { + for (uint8_t i = 0; i < 3 + EXTRUDERS; ++i) { digipot_motor = 255 * (motor_current[i] / 2.5); dac084s085::setValue(i, digipot_motor); } @@ -2719,7 +2719,7 @@ void Stepper::init() { TERN_(HAS_X2_DIR, X2_DIR_INIT()); #if HAS_Y_DIR Y_DIR_INIT(); - #if BOTH(HAS_DUAL_Y_STEPPERS, HAS_Y2_DIR) + #if ALL(HAS_DUAL_Y_STEPPERS, HAS_Y2_DIR) Y2_DIR_INIT(); #endif #endif @@ -2785,7 +2785,7 @@ void Stepper::init() { #endif X_ENABLE_INIT(); if (X_ENABLE_INIT_STATE) X_ENABLE_WRITE(X_ENABLE_INIT_STATE); - #if BOTH(HAS_X2_STEPPER, HAS_X2_ENABLE) + #if ALL(HAS_X2_STEPPER, HAS_X2_ENABLE) X2_ENABLE_INIT(); if (X_ENABLE_INIT_STATE) X2_ENABLE_WRITE(X_ENABLE_INIT_STATE); #endif @@ -2796,7 +2796,7 @@ void Stepper::init() { #endif Y_ENABLE_INIT(); if (Y_ENABLE_INIT_STATE) Y_ENABLE_WRITE(Y_ENABLE_INIT_STATE); - #if BOTH(HAS_DUAL_Y_STEPPERS, HAS_Y2_ENABLE) + #if ALL(HAS_DUAL_Y_STEPPERS, HAS_Y2_ENABLE) Y2_ENABLE_INIT(); if (Y_ENABLE_INIT_STATE) Y2_ENABLE_WRITE(Y_ENABLE_INIT_STATE); #endif @@ -3018,7 +3018,7 @@ void Stepper::init() { #endif } -#if HAS_SHAPING +#if HAS_ZV_SHAPING /** * Calculate a fixed point factor to apply to the signal and its echo @@ -3089,7 +3089,7 @@ void Stepper::init() { return -1; } -#endif // HAS_SHAPING +#endif // HAS_ZV_SHAPING /** * Set the stepper positions directly in steps @@ -3607,7 +3607,7 @@ void Stepper::report_positions() { void Stepper::refresh_motor_power() { if (!initialized) return; - LOOP_L_N(i, COUNT(motor_current_setting)) { + for (uint8_t i = 0; i < COUNT(motor_current_setting); ++i) { switch (i) { #if ANY_PIN(MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_I, MOTOR_CURRENT_PWM_J, MOTOR_CURRENT_PWM_K, MOTOR_CURRENT_PWM_U, MOTOR_CURRENT_PWM_V, MOTOR_CURRENT_PWM_W) case 0: @@ -3703,7 +3703,7 @@ void Stepper::report_positions() { SPI.begin(); SET_OUTPUT(DIGIPOTSS_PIN); - LOOP_L_N(i, COUNT(motor_current_setting)) + for (uint8_t i = 0; i < COUNT(motor_current_setting); ++i) set_digipot_current(i, motor_current_setting[i]); #elif HAS_MOTOR_CURRENT_PWM diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index dcb9babde7d9..6def38a25e9c 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -97,7 +97,7 @@ #endif // Input shaping base time - #if HAS_SHAPING + #if HAS_ZV_SHAPING #define ISR_SHAPING_BASE_CYCLES 180UL #else #define ISR_SHAPING_BASE_CYCLES 0UL @@ -131,7 +131,7 @@ #endif // Input shaping base time - #if HAS_SHAPING + #if HAS_ZV_SHAPING #define ISR_SHAPING_BASE_CYCLES 290UL #else #define ISR_SHAPING_BASE_CYCLES 0UL @@ -220,7 +220,7 @@ #define ISR_LOOP_CYCLES(R) ((ISR_LOOP_BASE_CYCLES + MIN_ISR_LOOP_CYCLES + MIN_STEPPER_PULSE_CYCLES) * (R - 1) + _MAX(MIN_ISR_LOOP_CYCLES, MIN_STEPPER_PULSE_CYCLES)) // Model input shaping as an extra loop call -#define ISR_SHAPING_LOOP_CYCLES(R) TERN0(HAS_SHAPING, (R) * ((ISR_LOOP_BASE_CYCLES) + TERN0(INPUT_SHAPING_X, ISR_X_STEPPER_CYCLES) + TERN0(INPUT_SHAPING_Y, ISR_Y_STEPPER_CYCLES))) +#define ISR_SHAPING_LOOP_CYCLES(R) TERN0(HAS_ZV_SHAPING, (R) * ((ISR_LOOP_BASE_CYCLES) + TERN0(INPUT_SHAPING_X, ISR_X_STEPPER_CYCLES) + TERN0(INPUT_SHAPING_Y, ISR_Y_STEPPER_CYCLES))) // If linear advance is enabled, then it is handled separately #if ENABLED(LIN_ADVANCE) @@ -262,29 +262,42 @@ // Perhaps DISABLE_MULTI_STEPPING should be required with ADAPTIVE_STEP_SMOOTHING. #define MIN_STEP_ISR_FREQUENCY (MAX_STEP_ISR_FREQUENCY_1X / 2) -#define ENABLE_COUNT (NUM_AXES + E_STEPPERS) -#if ENABLE_COUNT > 16 - typedef uint32_t ena_mask_t; +// TODO: Review and ensure proper handling for special E axes with commands like M17/M18, stepper timeout, etc. +#if ENABLED(MIXING_EXTRUDER) + #define E_STATES EXTRUDERS // All steppers are set together for each mixer. (Currently limited to 1.) +#elif ENABLED(SWITCHING_EXTRUDER) + #define E_STATES E_STEPPERS // One stepper for every two EXTRUDERS. The last extruder can be non-switching. +#elif HAS_PRUSA_MMU2 + #define E_STATES E_STEPPERS // One E stepper shared with all EXTRUDERS, so setting any only sets one. #else - typedef IF<(ENABLE_COUNT > 8), uint16_t, uint8_t>::type ena_mask_t; + #define E_STATES E_STEPPERS // One stepper for each extruder, so each can be disabled individually. #endif +// Number of axes that could be enabled/disabled. Dual/multiple steppers are combined. +#define ENABLE_COUNT (NUM_AXES + E_STATES) +typedef bits_t(ENABLE_COUNT) ena_mask_t; + // Axis flags type, for enabled state or other simple state typedef struct { union { ena_mask_t bits; struct { - bool NUM_AXIS_LIST(X:1, Y:1, Z:1, I:1, J:1, K:1, U:1, V:1, W:1); - #if HAS_EXTRUDERS - bool LIST_N(EXTRUDERS, E0:1, E1:1, E2:1, E3:1, E4:1, E5:1, E6:1, E7:1); + #if NUM_AXES + bool NUM_AXIS_LIST(X:1, Y:1, Z:1, I:1, J:1, K:1, U:1, V:1, W:1); + #endif + #if E_STATES + bool LIST_N(E_STATES, E0:1, E1:1, E2:1, E3:1, E4:1, E5:1, E6:1, E7:1); #endif }; }; } stepper_flags_t; +typedef bits_t(NUM_AXES + E_STATES) e_axis_bits_t; +constexpr e_axis_bits_t e_axis_mask = (_BV(E_STATES) - 1) << NUM_AXES; + // All the stepper enable pins constexpr pin_t ena_pins[] = { - NUM_AXIS_LIST(X_ENABLE_PIN, Y_ENABLE_PIN, Z_ENABLE_PIN, I_ENABLE_PIN, J_ENABLE_PIN, K_ENABLE_PIN, U_ENABLE_PIN, V_ENABLE_PIN, W_ENABLE_PIN), + NUM_AXIS_LIST_(X_ENABLE_PIN, Y_ENABLE_PIN, Z_ENABLE_PIN, I_ENABLE_PIN, J_ENABLE_PIN, K_ENABLE_PIN, U_ENABLE_PIN, V_ENABLE_PIN, W_ENABLE_PIN) LIST_N(E_STEPPERS, E0_ENABLE_PIN, E1_ENABLE_PIN, E2_ENABLE_PIN, E3_ENABLE_PIN, E4_ENABLE_PIN, E5_ENABLE_PIN, E6_ENABLE_PIN, E7_ENABLE_PIN) }; @@ -329,7 +342,7 @@ constexpr ena_mask_t enable_overlap[] = { //static_assert(!any_enable_overlap(), "There is some overlap."); -#if HAS_SHAPING +#if HAS_ZV_SHAPING #ifdef SHAPING_MAX_STEPRATE constexpr float max_step_rate = SHAPING_MAX_STEPRATE; @@ -449,27 +462,25 @@ constexpr ena_mask_t enable_overlap[] = { struct ShapeParams { float frequency; float zeta; - bool enabled; + bool enabled : 1; + bool forward : 1; int16_t delta_error = 0; // delta_error for seconday bresenham mod 128 uint8_t factor1; uint8_t factor2; - bool forward; int32_t last_block_end_pos = 0; }; -#endif // HAS_SHAPING +#endif // HAS_ZV_SHAPING // // Stepper class definition // class Stepper { - friend class KinematicSystem; - friend class DeltaKinematicSystem; friend void stepperTask(void *); public: - #if EITHER(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) + #if ANY(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) static bool separate_multi_axis; #endif @@ -516,7 +527,7 @@ class Stepper { #if ENABLED(Y_DUAL_ENDSTOPS) static bool locked_Y_motor, locked_Y2_motor; #endif - #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) + #if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) static bool locked_Z_motor, locked_Z2_motor #if NUM_Z_STEPPERS >= 3 , locked_Z3_motor @@ -545,7 +556,7 @@ class Stepper { decelerate_after, // The point from where we need to start decelerating step_event_count; // The total event count for the current block - #if EITHER(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) + #if ANY(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) static uint8_t stepper_extruder; #else static constexpr uint8_t stepper_extruder = 0; @@ -563,7 +574,7 @@ class Stepper { static bool bezier_2nd_half; // If Bézier curve has been initialized or not #endif - #if HAS_SHAPING + #if HAS_ZV_SHAPING #if ENABLED(INPUT_SHAPING_X) static ShapeParams shaping_x; #endif @@ -631,7 +642,7 @@ class Stepper { // The stepper block processing ISR phase static uint32_t block_phase_isr(); - #if HAS_SHAPING + #if HAS_ZV_SHAPING static void shaping_isr(); #endif @@ -654,7 +665,7 @@ class Stepper { // Check if the given block is busy or not - Must not be called from ISR contexts static bool is_block_busy(const block_t * const block); - #if HAS_SHAPING + #if HAS_ZV_SHAPING // Check whether the stepper is processing any input shaping echoes static bool input_shaping_busy() { const bool was_on = hal.isr_state(); @@ -716,7 +727,7 @@ class Stepper { static void microstep_readings(); #endif - #if EITHER(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) + #if ANY(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) FORCE_INLINE static void set_separate_multi_axis(const bool state) { separate_multi_axis = state; } #endif #if ENABLED(X_DUAL_ENDSTOPS) @@ -727,7 +738,7 @@ class Stepper { FORCE_INLINE static void set_y_lock(const bool state) { locked_Y_motor = state; } FORCE_INLINE static void set_y2_lock(const bool state) { locked_Y2_motor = state; } #endif - #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) + #if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) FORCE_INLINE static void set_z1_lock(const bool state) { locked_Z_motor = state; } FORCE_INLINE static void set_z2_lock(const bool state) { locked_Z2_motor = state; } #if NUM_Z_STEPPERS >= 3 @@ -794,15 +805,15 @@ class Stepper { static void disable_all_steppers(); // Update direction states for all steppers - static void set_directions(); + static void apply_directions(); // Set direction bits and update all stepper DIR states static void set_directions(const axis_bits_t bits) { last_direction_bits = bits; - set_directions(); + apply_directions(); } - #if HAS_SHAPING + #if HAS_ZV_SHAPING static void set_shaping_damping_ratio(const AxisEnum axis, const_float_t zeta); static float get_shaping_damping_ratio(const AxisEnum axis); static void set_shaping_frequency(const AxisEnum axis, const_float_t freq); diff --git a/Marlin/src/module/stepper/indirection.cpp b/Marlin/src/module/stepper/indirection.cpp index 427fd71cbe7d..0290d8135d9b 100644 --- a/Marlin/src/module/stepper/indirection.cpp +++ b/Marlin/src/module/stepper/indirection.cpp @@ -42,6 +42,6 @@ void reset_stepper_drivers() { } #if ENABLED(SOFTWARE_DRIVER_ENABLE) - // Flags to optimize XYZ Enabled state + // Flags to optimize axis enabled state xyz_bool_t axis_sw_enabled; // = { false, false, false } #endif diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index e9a9aa7de90c..a683409afb2f 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -22,14 +22,51 @@ #pragma once /** - * stepper/indirection.h + * stepper/indirection.h - Stepper Indirection Macros * - * Stepper motor driver indirection to allow some stepper functions to - * be done via SPI/I2c instead of direct pin manipulation. + * Each axis in a machine may have between 1 and 4 stepper motors. + * Currently X and Y allow for 1 or 2 steppers. Z can have up to 4. + * Extruders usually have one E stepper per nozzle. + * + * XYZ Special Cases + * - Delta: 3 steppers contribute to X, Y, and Z. + * - SCARA: A and B steppers contribute to X and Y by angular transformation. + * - CoreXY: A and B steppers contribute to X and Y in combination. + * - CoreXZ: A and B steppers contribute to X and Z in combination. + * - CoreYZ: A and B steppers contribute to Y and Z in combination. + * + * E Special Cases + * - SINGLENOZZLE: All Extruders have a single nozzle so there is one heater and no XYZ offset. + * - Switching Extruder: One stepper is used for each pair of nozzles with a switching mechanism. + * - Duplication Mode: Two or more steppers move in sync when `extruder_duplication_enabled` is set. + * With MULTI_NOZZLE_DUPLICATION a `duplication_e_mask` is also used. + * - Průša MMU1: One stepper is used with a switching mechanism. Odd numbered E indexes are reversed. + * - Průša MMU2: One stepper is used with a switching mechanism. + * - E_DUAL_STEPPER_DRIVERS: Two steppers always move in sync, possibly with opposite DIR states. + * + * Direct Stepper Control + * Where "Q" represents X Y Z I J K U V W / X2 Y2 Z2 Z3 Z4 / E0 E1 E2 E3 E4 E5 E6 E7 + * Here each E index corresponds to a single E stepper driver. + * + * Q_ENABLE_INIT() Q_ENABLE_WRITE(S) Q_ENABLE_READ() + * Q_DIR_INIT() Q_DIR_WRITE(S) Q_DIR_READ() + * Q_STEP_INIT() Q_STEP_WRITE(S) Q_STEP_READ() + * + * Steppers may not have an enable state or may be enabled by other methods + * beyond a single pin (SOFTWARE_DRIVER_ENABLE) so these can be overriden: + * ENABLE_STEPPER_Q() DISABLE_STEPPER_Q() + * + * Axis Stepper Control (X Y Z I J K U V W) + * SOFTWARE_DRIVER_ENABLE gives all axes a status flag, so these macros will + * skip sending commands to steppers that are already in the desired state: + * ENABLE_AXIS_Q() DISABLE_AXIS_Q() + * + * E-Axis Stepper Control (0..n) + * For these macros the E index indicates a logical extruder (e.g., active_extruder). + * + * E_STEP_WRITE(E,V) FWD_E_DIR(E) REV_E_DIR(E) * - * Copyright (c) 2015 Dominik Wenger */ - #include "../../inc/MarlinConfig.h" #if HAS_TMC26X @@ -44,21 +81,23 @@ void restore_stepper_drivers(); // Called by powerManager.power_on() void reset_stepper_drivers(); // Called by settings.load / settings.reset // X Stepper -#ifndef X_ENABLE_INIT - #define X_ENABLE_INIT() SET_OUTPUT(X_ENABLE_PIN) - #define X_ENABLE_WRITE(STATE) WRITE(X_ENABLE_PIN,STATE) - #define X_ENABLE_READ() bool(READ(X_ENABLE_PIN)) -#endif -#ifndef X_DIR_INIT - #define X_DIR_INIT() SET_OUTPUT(X_DIR_PIN) - #define X_DIR_WRITE(STATE) WRITE(X_DIR_PIN,STATE) - #define X_DIR_READ() bool(READ(X_DIR_PIN)) -#endif -#define X_STEP_INIT() SET_OUTPUT(X_STEP_PIN) -#ifndef X_STEP_WRITE - #define X_STEP_WRITE(STATE) WRITE(X_STEP_PIN,STATE) +#if HAS_X_AXIS + #ifndef X_ENABLE_INIT + #define X_ENABLE_INIT() SET_OUTPUT(X_ENABLE_PIN) + #define X_ENABLE_WRITE(STATE) WRITE(X_ENABLE_PIN,STATE) + #define X_ENABLE_READ() bool(READ(X_ENABLE_PIN)) + #endif + #ifndef X_DIR_INIT + #define X_DIR_INIT() SET_OUTPUT(X_DIR_PIN) + #define X_DIR_WRITE(STATE) WRITE(X_DIR_PIN,STATE) + #define X_DIR_READ() bool(READ(X_DIR_PIN)) + #endif + #define X_STEP_INIT() SET_OUTPUT(X_STEP_PIN) + #ifndef X_STEP_WRITE + #define X_STEP_WRITE(STATE) WRITE(X_STEP_PIN,STATE) + #endif + #define X_STEP_READ() bool(READ(X_STEP_PIN)) #endif -#define X_STEP_READ() bool(READ(X_STEP_PIN)) // Y Stepper #if HAS_Y_AXIS @@ -968,8 +1007,13 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define AFTER_CHANGE(N,TF) NOOP #endif -#define ENABLE_AXIS_X() if (SHOULD_ENABLE(x)) { ENABLE_STEPPER_X(); ENABLE_STEPPER_X2(); AFTER_CHANGE(x, true); } -#define DISABLE_AXIS_X() if (SHOULD_DISABLE(x)) { DISABLE_STEPPER_X(); DISABLE_STEPPER_X2(); AFTER_CHANGE(x, false); set_axis_untrusted(X_AXIS); } +#if HAS_X_AXIS + #define ENABLE_AXIS_X() if (SHOULD_ENABLE(x)) { ENABLE_STEPPER_X(); ENABLE_STEPPER_X2(); AFTER_CHANGE(x, true); } + #define DISABLE_AXIS_X() if (SHOULD_DISABLE(x)) { DISABLE_STEPPER_X(); DISABLE_STEPPER_X2(); AFTER_CHANGE(x, false); set_axis_untrusted(X_AXIS); } +#else + #define ENABLE_AXIS_X() NOOP + #define DISABLE_AXIS_X() NOOP +#endif #if HAS_Y_AXIS #define ENABLE_AXIS_Y() if (SHOULD_ENABLE(y)) { ENABLE_STEPPER_Y(); ENABLE_STEPPER_Y2(); AFTER_CHANGE(y, true); } diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 48ce020d3dca..52b9701bab6c 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -46,7 +46,7 @@ enum StealthIndex : uint8_t { // AI = Axis Enum Index // SWHW = SW/SH UART selection #if ENABLED(TMC_USE_SW_SPI) - #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SW_MOSI, TMC_SW_MISO, TMC_SW_SCK, ST##_CHAIN_POS) + #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS) #else #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), ST##_CHAIN_POS) #endif @@ -493,7 +493,7 @@ enum StealthIndex : uint8_t { #endif #define _EN_ITEM(N) , E##N - enum TMCAxis : uint8_t { MAIN_AXIS_NAMES, X2, Y2, Z2, Z3, Z4 REPEAT(EXTRUDERS, _EN_ITEM), TOTAL }; + enum TMCAxis : uint8_t { MAIN_AXIS_NAMES_ X2, Y2, Z2, Z3, Z4 REPEAT(EXTRUDERS, _EN_ITEM), TOTAL }; #undef _EN_ITEM void tmc_serial_begin() { @@ -501,7 +501,7 @@ enum StealthIndex : uint8_t { struct { const void *ptr[TMCAxis::TOTAL]; bool began(const TMCAxis a, const void * const p) { - LOOP_L_N(i, a) if (p == ptr[i]) return true; + for (uint8_t i = 0; i < a; ++i) if (p == ptr[i]) return true; ptr[a] = p; return false; }; } sp_helper; @@ -514,154 +514,154 @@ enum StealthIndex : uint8_t { #ifdef X_HARDWARE_SERIAL HW_SERIAL_BEGIN(X); #else - stepperX.beginSerial(TMC_BAUD_RATE); + stepperX.beginSerial(TMC_X_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(X2) #ifdef X2_HARDWARE_SERIAL HW_SERIAL_BEGIN(X2); #else - stepperX2.beginSerial(TMC_BAUD_RATE); + stepperX2.beginSerial(TMC_X2_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Y) #ifdef Y_HARDWARE_SERIAL HW_SERIAL_BEGIN(Y); #else - stepperY.beginSerial(TMC_BAUD_RATE); + stepperY.beginSerial(TMC_Y_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Y2) #ifdef Y2_HARDWARE_SERIAL HW_SERIAL_BEGIN(Y2); #else - stepperY2.beginSerial(TMC_BAUD_RATE); + stepperY2.beginSerial(TMC_Y2_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z) #ifdef Z_HARDWARE_SERIAL HW_SERIAL_BEGIN(Z); #else - stepperZ.beginSerial(TMC_BAUD_RATE); + stepperZ.beginSerial(TMC_Z_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z2) #ifdef Z2_HARDWARE_SERIAL HW_SERIAL_BEGIN(Z2); #else - stepperZ2.beginSerial(TMC_BAUD_RATE); + stepperZ2.beginSerial(TMC_Z2_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z3) #ifdef Z3_HARDWARE_SERIAL HW_SERIAL_BEGIN(Z3); #else - stepperZ3.beginSerial(TMC_BAUD_RATE); + stepperZ3.beginSerial(TMC_Z3_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z4) #ifdef Z4_HARDWARE_SERIAL HW_SERIAL_BEGIN(Z4); #else - stepperZ4.beginSerial(TMC_BAUD_RATE); + stepperZ4.beginSerial(TMC_Z4_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(I) #ifdef I_HARDWARE_SERIAL HW_SERIAL_BEGIN(I); #else - stepperI.beginSerial(TMC_BAUD_RATE); + stepperI.beginSerial(TMC_I_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(J) #ifdef J_HARDWARE_SERIAL HW_SERIAL_BEGIN(J); #else - stepperJ.beginSerial(TMC_BAUD_RATE); + stepperJ.beginSerial(TMC_J_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(K) #ifdef K_HARDWARE_SERIAL HW_SERIAL_BEGIN(K); #else - stepperK.beginSerial(TMC_BAUD_RATE); + stepperK.beginSerial(TMC_K_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(U) #ifdef U_HARDWARE_SERIAL HW_SERIAL_BEGIN(U); #else - stepperU.beginSerial(TMC_BAUD_RATE); + stepperU.beginSerial(TMC_U_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(V) #ifdef V_HARDWARE_SERIAL HW_SERIAL_BEGIN(V); #else - stepperV.beginSerial(TMC_BAUD_RATE); + stepperV.beginSerial(TMC_V_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(W) #ifdef W_HARDWARE_SERIAL HW_SERIAL_BEGIN(W); #else - stepperW.beginSerial(TMC_BAUD_RATE); + stepperW.beginSerial(TMC_W_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E0) #ifdef E0_HARDWARE_SERIAL HW_SERIAL_BEGIN(E0); #else - stepperE0.beginSerial(TMC_BAUD_RATE); + stepperE0.beginSerial(TMC_E0_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E1) #ifdef E1_HARDWARE_SERIAL HW_SERIAL_BEGIN(E1); #else - stepperE1.beginSerial(TMC_BAUD_RATE); + stepperE1.beginSerial(TMC_E1_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E2) #ifdef E2_HARDWARE_SERIAL HW_SERIAL_BEGIN(E2); #else - stepperE2.beginSerial(TMC_BAUD_RATE); + stepperE2.beginSerial(TMC_E2_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E3) #ifdef E3_HARDWARE_SERIAL HW_SERIAL_BEGIN(E3); #else - stepperE3.beginSerial(TMC_BAUD_RATE); + stepperE3.beginSerial(TMC_E3_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E4) #ifdef E4_HARDWARE_SERIAL HW_SERIAL_BEGIN(E4); #else - stepperE4.beginSerial(TMC_BAUD_RATE); + stepperE4.beginSerial(TMC_E4_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E5) #ifdef E5_HARDWARE_SERIAL HW_SERIAL_BEGIN(E5); #else - stepperE5.beginSerial(TMC_BAUD_RATE); + stepperE5.beginSerial(TMC_E5_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E6) #ifdef E6_HARDWARE_SERIAL HW_SERIAL_BEGIN(E6); #else - stepperE6.beginSerial(TMC_BAUD_RATE); + stepperE6.beginSerial(TMC_E6_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E7) #ifdef E7_HARDWARE_SERIAL HW_SERIAL_BEGIN(E7); #else - stepperE7.beginSerial(TMC_BAUD_RATE); + stepperE7.beginSerial(TMC_E7_BAUD_RATE); #endif #endif } @@ -991,13 +991,13 @@ void reset_trinamic_drivers() { #if USE_SENSORLESS TERN_(X_SENSORLESS, stepperX.homing_threshold(X_STALL_SENSITIVITY)); - TERN_(X2_SENSORLESS, stepperX2.homing_threshold(CAT(TERN(X2_SENSORLESS, X2, X), _STALL_SENSITIVITY))); + TERN_(X2_SENSORLESS, stepperX2.homing_threshold(X2_STALL_SENSITIVITY)); TERN_(Y_SENSORLESS, stepperY.homing_threshold(Y_STALL_SENSITIVITY)); - TERN_(Y2_SENSORLESS, stepperY2.homing_threshold(CAT(TERN(Y2_SENSORLESS, Y2, Y), _STALL_SENSITIVITY))); + TERN_(Y2_SENSORLESS, stepperY2.homing_threshold(Y2_STALL_SENSITIVITY)); TERN_(Z_SENSORLESS, stepperZ.homing_threshold(Z_STALL_SENSITIVITY)); - TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(CAT(TERN(Z2_SENSORLESS, Z2, Z), _STALL_SENSITIVITY))); - TERN_(Z3_SENSORLESS, stepperZ3.homing_threshold(CAT(TERN(Z3_SENSORLESS, Z3, Z), _STALL_SENSITIVITY))); - TERN_(Z4_SENSORLESS, stepperZ4.homing_threshold(CAT(TERN(Z4_SENSORLESS, Z4, Z), _STALL_SENSITIVITY))); + TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(Z2_STALL_SENSITIVITY)); + TERN_(Z3_SENSORLESS, stepperZ3.homing_threshold(Z3_STALL_SENSITIVITY)); + TERN_(Z4_SENSORLESS, stepperZ4.homing_threshold(Z4_STALL_SENSITIVITY)); TERN_(I_SENSORLESS, stepperI.homing_threshold(I_STALL_SENSITIVITY)); TERN_(J_SENSORLESS, stepperJ.homing_threshold(J_STALL_SENSITIVITY)); TERN_(K_SENSORLESS, stepperK.homing_threshold(K_STALL_SENSITIVITY)); @@ -1010,7 +1010,7 @@ void reset_trinamic_drivers() { TMC_ADV() #endif - stepper.set_directions(); + stepper.apply_directions(); } // TMC Slave Address Conflict Detection diff --git a/Marlin/src/module/stepper/trinamic.h b/Marlin/src/module/stepper/trinamic.h index 95bab7652c1a..39e8f39cfae1 100644 --- a/Marlin/src/module/stepper/trinamic.h +++ b/Marlin/src/module/stepper/trinamic.h @@ -77,7 +77,7 @@ #define TMC_CLASS_E(N) TMC_CLASS(E##N, E) #endif -#ifndef CHOPPER_TIMING_X +#if HAS_X_AXIS && !defined(CHOPPER_TIMING_X) #define CHOPPER_TIMING_X CHOPPER_TIMING #endif #if HAS_Y_AXIS && !defined(CHOPPER_TIMING_Y) @@ -115,7 +115,7 @@ void restore_trinamic_drivers(); void reset_trinamic_drivers(); -#define AXIS_HAS_SQUARE_WAVE(A) (AXIS_IS_TMC(A) && ENABLED(SQUARE_WAVE_STEPPING)) +#define AXIS_HAS_DEDGE(A) (AXIS_IS_TMC(A) && ENABLED(SQUARE_WAVE_STEPPING)) // X Stepper #if AXIS_IS_TMC(X) @@ -126,7 +126,7 @@ void reset_trinamic_drivers(); #define X_ENABLE_WRITE(STATE) stepperX.toff((STATE)==X_ENABLE_ON ? chopper_timing_X.toff : 0) #define X_ENABLE_READ() stepperX.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(X) + #if AXIS_HAS_DEDGE(X) #define X_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(X_STEP_PIN); }while(0) #endif #endif @@ -140,7 +140,7 @@ void reset_trinamic_drivers(); #define Y_ENABLE_WRITE(STATE) stepperY.toff((STATE)==Y_ENABLE_ON ? chopper_timing_Y.toff : 0) #define Y_ENABLE_READ() stepperY.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(Y) + #if AXIS_HAS_DEDGE(Y) #define Y_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(Y_STEP_PIN); }while(0) #endif #endif @@ -154,7 +154,7 @@ void reset_trinamic_drivers(); #define Z_ENABLE_WRITE(STATE) stepperZ.toff((STATE)==Z_ENABLE_ON ? chopper_timing_Z.toff : 0) #define Z_ENABLE_READ() stepperZ.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(Z) + #if AXIS_HAS_DEDGE(Z) #define Z_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(Z_STEP_PIN); }while(0) #endif #endif @@ -171,7 +171,7 @@ void reset_trinamic_drivers(); #define X2_ENABLE_WRITE(STATE) stepperX2.toff((STATE)==X_ENABLE_ON ? chopper_timing_X2.toff : 0) #define X2_ENABLE_READ() stepperX2.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(X2) + #if AXIS_HAS_DEDGE(X2) #define X2_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(X2_STEP_PIN); }while(0) #endif #endif @@ -188,7 +188,7 @@ void reset_trinamic_drivers(); #define Y2_ENABLE_WRITE(STATE) stepperY2.toff((STATE)==Y_ENABLE_ON ? chopper_timing_Y2.toff : 0) #define Y2_ENABLE_READ() stepperY2.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(Y2) + #if AXIS_HAS_DEDGE(Y2) #define Y2_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(Y2_STEP_PIN); }while(0) #endif #endif @@ -205,7 +205,7 @@ void reset_trinamic_drivers(); #define Z2_ENABLE_WRITE(STATE) stepperZ2.toff((STATE)==Z_ENABLE_ON ? chopper_timing_Z2.toff : 0) #define Z2_ENABLE_READ() stepperZ2.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(Z2) + #if AXIS_HAS_DEDGE(Z2) #define Z2_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(Z2_STEP_PIN); }while(0) #endif #endif @@ -222,7 +222,7 @@ void reset_trinamic_drivers(); #define Z3_ENABLE_WRITE(STATE) stepperZ3.toff((STATE)==Z_ENABLE_ON ? chopper_timing_Z3.toff : 0) #define Z3_ENABLE_READ() stepperZ3.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(Z3) + #if AXIS_HAS_DEDGE(Z3) #define Z3_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(Z3_STEP_PIN); }while(0) #endif #endif @@ -239,7 +239,7 @@ void reset_trinamic_drivers(); #define Z4_ENABLE_WRITE(STATE) stepperZ4.toff((STATE)==Z_ENABLE_ON ? chopper_timing_Z4.toff : 0) #define Z4_ENABLE_READ() stepperZ4.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(Z4) + #if AXIS_HAS_DEDGE(Z4) #define Z4_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(Z4_STEP_PIN); }while(0) #endif #endif @@ -250,10 +250,10 @@ void reset_trinamic_drivers(); static constexpr chopper_timing_t chopper_timing_I = CHOPPER_TIMING_I; #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define I_ENABLE_INIT() NOOP - #define I_ENABLE_WRITE(STATE) stepperI.toff((STATE)==I_ENABLE_ON ? chopper_timing.toff : 0) + #define I_ENABLE_WRITE(STATE) stepperI.toff((STATE)==I_ENABLE_ON ? chopper_timing_I.toff : 0) #define I_ENABLE_READ() stepperI.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(I) + #if AXIS_HAS_DEDGE(I) #define I_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(I_STEP_PIN); }while(0) #endif #endif @@ -264,10 +264,10 @@ void reset_trinamic_drivers(); static constexpr chopper_timing_t chopper_timing_J = CHOPPER_TIMING_J; #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define J_ENABLE_INIT() NOOP - #define J_ENABLE_WRITE(STATE) stepperJ.toff((STATE)==J_ENABLE_ON ? chopper_timing.toff : 0) + #define J_ENABLE_WRITE(STATE) stepperJ.toff((STATE)==J_ENABLE_ON ? chopper_timing_J.toff : 0) #define J_ENABLE_READ() stepperJ.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(J) + #if AXIS_HAS_DEDGE(J) #define J_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(J_STEP_PIN); }while(0) #endif #endif @@ -278,10 +278,10 @@ void reset_trinamic_drivers(); static constexpr chopper_timing_t chopper_timing_K = CHOPPER_TIMING_K; #if ENABLED(SOFTWARE_DRIVER_ENABLE) #define K_ENABLE_INIT() NOOP - #define K_ENABLE_WRITE(STATE) stepperK.toff((STATE)==K_ENABLE_ON ? chopper_timing.toff : 0) + #define K_ENABLE_WRITE(STATE) stepperK.toff((STATE)==K_ENABLE_ON ? chopper_timing_K.toff : 0) #define K_ENABLE_READ() stepperK.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(K) + #if AXIS_HAS_DEDGE(K) #define K_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(K_STEP_PIN); }while(0) #endif #endif @@ -295,8 +295,8 @@ void reset_trinamic_drivers(); #define U_ENABLE_WRITE(STATE) stepperU.toff((STATE)==U_ENABLE_ON ? chopper_timing_U.toff : 0) #define U_ENABLE_READ() stepperU.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(U) - #define U_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(U_STEP_PIN); }while(0) + #if AXIS_HAS_DEDGE(U) + #define U_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(U_STEP_PIN); }while(0) #endif #endif @@ -309,8 +309,8 @@ void reset_trinamic_drivers(); #define V_ENABLE_WRITE(STATE) stepperV.toff((STATE)==V_ENABLE_ON ? chopper_timing_V.toff : 0) #define V_ENABLE_READ() stepperV.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(V) - #define V_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(V_STEP_PIN); }while(0) + #if AXIS_HAS_DEDGE(V) + #define V_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(V_STEP_PIN); }while(0) #endif #endif @@ -323,8 +323,8 @@ void reset_trinamic_drivers(); #define W_ENABLE_WRITE(STATE) stepperW.toff((STATE)==W_ENABLE_ON ? chopper_timing_W.toff : 0) #define W_ENABLE_READ() stepperW.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(W) - #define W_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(W_STEP_PIN); }while(0) + #if AXIS_HAS_DEDGE(W) + #define W_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(W_STEP_PIN); }while(0) #endif #endif @@ -340,7 +340,7 @@ void reset_trinamic_drivers(); #define E0_ENABLE_WRITE(STATE) stepperE0.toff((STATE)==E_ENABLE_ON ? chopper_timing_E0.toff : 0) #define E0_ENABLE_READ() stepperE0.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(E0) + #if AXIS_HAS_DEDGE(E0) #define E0_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E0_STEP_PIN); }while(0) #endif #endif @@ -357,7 +357,7 @@ void reset_trinamic_drivers(); #define E1_ENABLE_WRITE(STATE) stepperE1.toff((STATE)==E_ENABLE_ON ? chopper_timing_E1.toff : 0) #define E1_ENABLE_READ() stepperE1.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(E1) + #if AXIS_HAS_DEDGE(E1) #define E1_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E1_STEP_PIN); }while(0) #endif #endif @@ -374,7 +374,7 @@ void reset_trinamic_drivers(); #define E2_ENABLE_WRITE(STATE) stepperE2.toff((STATE)==E_ENABLE_ON ? chopper_timing_E2.toff : 0) #define E2_ENABLE_READ() stepperE2.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(E2) + #if AXIS_HAS_DEDGE(E2) #define E2_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E2_STEP_PIN); }while(0) #endif #endif @@ -391,7 +391,7 @@ void reset_trinamic_drivers(); #define E3_ENABLE_WRITE(STATE) stepperE3.toff((STATE)==E_ENABLE_ON ? chopper_timing_E3.toff : 0) #define E3_ENABLE_READ() stepperE3.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(E3) + #if AXIS_HAS_DEDGE(E3) #define E3_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E3_STEP_PIN); }while(0) #endif #endif @@ -408,7 +408,7 @@ void reset_trinamic_drivers(); #define E4_ENABLE_WRITE(STATE) stepperE4.toff((STATE)==E_ENABLE_ON ? chopper_timing_E4.toff : 0) #define E4_ENABLE_READ() stepperE4.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(E4) + #if AXIS_HAS_DEDGE(E4) #define E4_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E4_STEP_PIN); }while(0) #endif #endif @@ -425,7 +425,7 @@ void reset_trinamic_drivers(); #define E5_ENABLE_WRITE(STATE) stepperE5.toff((STATE)==E_ENABLE_ON ? chopper_timing_E5.toff : 0) #define E5_ENABLE_READ() stepperE5.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(E5) + #if AXIS_HAS_DEDGE(E5) #define E5_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E5_STEP_PIN); }while(0) #endif #endif @@ -442,7 +442,7 @@ void reset_trinamic_drivers(); #define E6_ENABLE_WRITE(STATE) stepperE6.toff((STATE)==E_ENABLE_ON ? chopper_timing_E6.toff : 0) #define E6_ENABLE_READ() stepperE6.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(E6) + #if AXIS_HAS_DEDGE(E6) #define E6_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E6_STEP_PIN); }while(0) #endif #endif @@ -459,7 +459,7 @@ void reset_trinamic_drivers(); #define E7_ENABLE_WRITE(STATE) stepperE7.toff((STATE)==E_ENABLE_ON ? chopper_timing_E7.toff : 0) #define E7_ENABLE_READ() stepperE7.isEnabled() #endif - #if AXIS_HAS_SQUARE_WAVE(E7) + #if AXIS_HAS_DEDGE(E7) #define E7_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(E7_STEP_PIN); }while(0) #endif #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index b3c5934b43ea..cfcfed5dcdf0 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -37,7 +37,7 @@ #include "planner.h" #include "printcounter.h" -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "../feature/cooler.h" #include "../feature/spindle_laser.h" #endif @@ -74,7 +74,6 @@ // 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) (TEMP_SENSOR_IS_MAX_TC(n) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) // LIB_MAX6675 can be added to the build_flags in platformio.ini to use a user-defined library // If LIB_MAX6675 is not on the build_flags then raw SPI reads will be used. @@ -121,6 +120,9 @@ #if TEMP_SENSOR_IS_ANY_MAX_TC(2) && TEMP_SENSOR_2_HAS_SPI_PINS && DISABLED(TEMP_SENSOR_FORCE_HW_SPI) #define TEMP_SENSOR_2_USES_SW_SPI 1 #endif +#if TEMP_SENSOR_IS_ANY_MAX_TC(BED) && TEMP_SENSOR_0_HAS_SPI_PINS && DISABLED(TEMP_SENSOR_FORCE_HW_SPI) + #define TEMP_SENSOR_BED_USES_SW_SPI 1 +#endif #if (TEMP_SENSOR_0_USES_SW_SPI || TEMP_SENSOR_1_USES_SW_SPI || TEMP_SENSOR_2_USES_SW_SPI) && !HAS_MAXTC_LIBRARIES #include "../libs/private_spi.h" @@ -156,7 +158,7 @@ #include "probe.h" #endif -#if EITHER(MPCTEMP, PID_EXTRUSION_SCALING) +#if ANY(MPCTEMP, PID_EXTRUSION_SCALING) #include "stepper.h" #endif @@ -214,29 +216,6 @@ 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); -/** - * Macros to include the heater id in temp errors. The compiler's dead-code - * elimination should (hopefully) optimize out the unused strings. - */ - -#if HAS_HEATED_BED - #define _BED_FSTR(h) (h) == H_BED ? GET_TEXT_F(MSG_BED) : -#else - #define _BED_FSTR(h) -#endif -#if HAS_HEATED_CHAMBER - #define _CHAMBER_FSTR(h) (h) == H_CHAMBER ? GET_TEXT_F(MSG_CHAMBER) : -#else - #define _CHAMBER_FSTR(h) -#endif -#if HAS_COOLER - #define _COOLER_FSTR(h) (h) == H_COOLER ? GET_TEXT_F(MSG_COOLER) : -#else - #define _COOLER_FSTR(h) -#endif -#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 // @@ -287,6 +266,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #define _MAX31865_0_SW TEMP_SENSOR_0_USES_SW_SPI #define _MAX31865_1_SW TEMP_SENSOR_1_USES_SW_SPI #define _MAX31865_2_SW TEMP_SENSOR_2_USES_SW_SPI + #define _MAX31865_BED_SW TEMP_SENSOR_BED_USES_SW_SPI #if TEMP_SENSOR_IS_MAX(0, 31865) MAXTC_INIT(0, 31865); @@ -297,10 +277,14 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #if TEMP_SENSOR_IS_MAX(2, 31865) MAXTC_INIT(2, 31865); #endif + #if TEMP_SENSOR_IS_MAX(BED, 31865) + MAXTC_INIT(BED, 31865); + #endif #undef _MAX31865_0_SW #undef _MAX31865_1_SW #undef _MAX31865_2_SW + #undef _MAX31865_BED_SW #endif #undef MAXTC_INIT @@ -321,13 +305,13 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); // Sanity-check max readable temperatures #define CHECK_MAXTEMP_(N,M,S) static_assert( \ - S >= 998 || M <= _MAX(TT_NAME(S)[0].celsius, TT_NAME(S)[COUNT(TT_NAME(S)) - 1].celsius) - HOTEND_OVERSHOOT, \ + S >= 998 || M <= _MAX(TT_NAME(S)[0].celsius, TT_NAME(S)[COUNT(TT_NAME(S)) - 1].celsius) - (HOTEND_OVERSHOOT), \ "HEATER_" STRINGIFY(N) "_MAXTEMP (" STRINGIFY(M) ") is too high for thermistor_" STRINGIFY(S) ".h with HOTEND_OVERSHOOT=" STRINGIFY(HOTEND_OVERSHOOT) "."); #define CHECK_MAXTEMP(N) TERN(TEMP_SENSOR_##N##_IS_THERMISTOR, CHECK_MAXTEMP_, CODE_0)(N, HEATER_##N##_MAXTEMP, TEMP_SENSOR_##N) REPEAT(HOTENDS, CHECK_MAXTEMP) #if HAS_PREHEAT - #define CHECK_PREHEAT__(N,P,T,M) static_assert(T <= M - HOTEND_OVERSHOOT, "PREHEAT_" STRINGIFY(P) "_TEMP_HOTEND (" STRINGIFY(T) ") must be less than HEATER_" STRINGIFY(N) "_MAXTEMP (" STRINGIFY(M) ") - " STRINGIFY(HOTEND_OVERSHOOT) "."); + #define CHECK_PREHEAT__(N,P,T,M) static_assert(T <= (M) - (HOTEND_OVERSHOOT), "PREHEAT_" STRINGIFY(P) "_TEMP_HOTEND (" STRINGIFY(T) ") must be less than HEATER_" STRINGIFY(N) "_MAXTEMP (" STRINGIFY(M) ") - " STRINGIFY(HOTEND_OVERSHOOT) "."); #define CHECK_PREHEAT_(N,P) CHECK_PREHEAT__(N, P, PREHEAT_##P##_TEMP_HOTEND, HEATER_##N##_MAXTEMP) #define CHECK_PREHEAT(P) REPEAT2(HOTENDS, CHECK_PREHEAT_, P) #if PREHEAT_COUNT >= 1 @@ -368,7 +352,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); redundant_info_t Temperature::temp_redundant; #endif -#if EITHER(AUTO_POWER_E_FANS, HAS_FANCHECK) +#if ANY(AUTO_POWER_E_FANS, HAS_FANCHECK) uint8_t Temperature::autofan_speed[HOTENDS] = ARRAY_N_1(HOTENDS, FAN_OFF_PWM); #endif @@ -380,15 +364,11 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); uint8_t Temperature::coolerfan_speed = FAN_OFF_PWM; #endif -#if BOTH(FAN_SOFT_PWM, USE_CONTROLLER_FAN) - uint8_t Temperature::soft_pwm_controller_speed = FAN_OFF_PWM; -#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) + #define _INIT_SOFT_FAN(P) OUT_WRITE_OD(P, ENABLED(FAN_INVERTING) ? LOW : HIGH) #else - #define _INIT_SOFT_FAN(P) OUT_WRITE(P, FAN_INVERTING ? LOW : HIGH) + #define _INIT_SOFT_FAN(P) OUT_WRITE(P, ENABLED(FAN_INVERTING) ? LOW : HIGH) #endif #if ENABLED(FAN_SOFT_PWM) #define _INIT_FAN_PIN(P) _INIT_SOFT_FAN(P) @@ -434,7 +414,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #endif - #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) + #if ANY(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) bool Temperature::fans_paused; // = false; uint8_t Temperature::saved_fan_speed[FAN_COUNT] = ARRAY_N_1(FAN_COUNT, FAN_OFF_PWM); #endif @@ -480,7 +460,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); } #endif - #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) + #if ANY(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) void Temperature::set_fans_paused(const bool p) { if (p != fans_paused) { @@ -519,7 +499,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #if HAS_TEMP_CHAMBER chamber_info_t Temperature::temp_chamber; // = { 0 } #if HAS_HEATED_CHAMBER - millis_t next_cool_check_ms_2 = 0; + millis_t next_cool_check_ms = 0; celsius_float_t old_temp = 9999; raw_adc_t Temperature::mintemp_raw_CHAMBER = TEMP_SENSOR_CHAMBER_RAW_LO_TEMP, Temperature::maxtemp_raw_CHAMBER = TEMP_SENSOR_CHAMBER_RAW_HI_TEMP; @@ -541,7 +521,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); raw_adc_t Temperature::mintemp_raw_COOLER = TEMP_SENSOR_COOLER_RAW_LO_TEMP, Temperature::maxtemp_raw_COOLER = TEMP_SENSOR_COOLER_RAW_HI_TEMP; #if WATCH_COOLER - cooler_watch_t Temperature::watch_cooler{0}; + cooler_watch_t Temperature::watch_cooler; // = { 0 } #endif millis_t Temperature::next_cooler_check_ms, Temperature::cooler_fan_flush_ms; #endif @@ -559,7 +539,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #endif #endif -#if BOTH(HAS_MARLINUI_MENU, PREVENT_COLD_EXTRUSION) && E_MANUAL > 0 +#if ALL(HAS_MARLINUI_MENU, PREVENT_COLD_EXTRUSION) && E_MANUAL > 0 bool Temperature::allow_cold_extrude_override = false; #else constexpr bool Temperature::allow_cold_extrude_override; @@ -568,6 +548,9 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #if ENABLED(PREVENT_COLD_EXTRUSION) bool Temperature::allow_cold_extrude = false; celsius_t Temperature::extrude_min_temp = EXTRUDE_MINTEMP; +#else + constexpr bool Temperature::allow_cold_extrude; + constexpr celsius_t Temperature::extrude_min_temp; #endif #if HAS_ADC_BUTTONS @@ -585,7 +568,6 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); volatile bool Temperature::raw_temps_ready = false; - #if ENABLED(MPCTEMP) int32_t Temperature::mpc_e_position; // = 0 #endif @@ -609,11 +591,14 @@ volatile bool Temperature::raw_temps_ready = false; #if MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED > 1 #define MULTI_MAX_CONSECUTIVE_LOW_TEMP_ERR 1 - uint8_t Temperature::consecutive_low_temperature_error[HOTENDS] = { 0 }; + uint8_t Temperature::consecutive_low_temperature_error[HOTENDS]; // = { 0 } #endif #if MILLISECONDS_PREHEAT_TIME > 0 - millis_t Temperature::preheat_end_time[HOTENDS] = { 0 }; + millis_t Temperature::preheat_end_ms_hotend[HOTENDS]; // = { 0 }; +#endif +#if HAS_HEATED_BED && PREHEAT_TIME_BED_MS > 0 + millis_t Temperature::preheat_end_ms_bed = 0; #endif #if HAS_FAN_LOGIC @@ -683,15 +668,15 @@ volatile bool Temperature::raw_temps_ready = false; #define ONHEATINGSTART() C_TERN(ischamber, printerEventLEDs.onChamberHeatingStart(), B_TERN(isbed, printerEventLEDs.onBedHeatingStart(), printerEventLEDs.onHotendHeatingStart())) #define ONHEATING(S,C,T) C_TERN(ischamber, printerEventLEDs.onChamberHeating(S,C,T), B_TERN(isbed, printerEventLEDs.onBedHeating(S,C,T), printerEventLEDs.onHotendHeating(S,C,T))) - #define WATCH_PID DISABLED(NO_WATCH_PID_TUNING) && (BOTH(WATCH_CHAMBER, PIDTEMPCHAMBER) || BOTH(WATCH_BED, PIDTEMPBED) || BOTH(WATCH_HOTENDS, PIDTEMP)) + #define WATCH_PID DISABLED(NO_WATCH_PID_TUNING) && (ALL(WATCH_CHAMBER, PIDTEMPCHAMBER) || ALL(WATCH_BED, PIDTEMPBED) || ALL(WATCH_HOTENDS, PIDTEMP)) #if WATCH_PID - #if BOTH(THERMAL_PROTECTION_CHAMBER, PIDTEMPCHAMBER) + #if ALL(THERMAL_PROTECTION_CHAMBER, PIDTEMPCHAMBER) #define C_GTV(T,A,B) ((T) ? (A) : (B)) #else #define C_GTV(T,A,B) (B) #endif - #if BOTH(THERMAL_PROTECTION_BED, PIDTEMPBED) + #if ALL(THERMAL_PROTECTION_BED, PIDTEMPBED) #define B_GTV(T,A,B) ((T) ? (A) : (B)) #else #define B_GTV(T,A,B) (B) @@ -711,16 +696,14 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(isbed ? PIDTEMPBED_START : PIDTEMP_START)); if (target > GHV(CHAMBER_MAX_TARGET, BED_MAX_TARGET, temp_range[heater_id].maxtemp - (HOTEND_OVERSHOOT))) { - SERIAL_ECHOPGM(STR_PID_AUTOTUNE); - SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); + SERIAL_ECHOPGM(STR_PID_AUTOTUNE); SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(PID_TEMP_TOO_HIGH)); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH))); return; } - SERIAL_ECHOPGM(STR_PID_AUTOTUNE); - SERIAL_ECHOLNPGM(STR_PID_AUTOTUNE_START); + SERIAL_ECHOPGM(STR_PID_AUTOTUNE); SERIAL_ECHOLNPGM(STR_PID_AUTOTUNE_START); disable_all_heaters(); TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); @@ -805,8 +788,7 @@ volatile bool Temperature::raw_temps_ready = false; #define MAX_OVERSHOOT_PID_AUTOTUNE 30 #endif if (current_temp > target + MAX_OVERSHOOT_PID_AUTOTUNE) { - SERIAL_ECHOPGM(STR_PID_AUTOTUNE); - SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); + SERIAL_ECHOPGM(STR_PID_AUTOTUNE); SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(PID_TEMP_TOO_HIGH)); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH))); @@ -823,7 +805,7 @@ volatile bool Temperature::raw_temps_ready = false; // Make sure heating is actually working #if WATCH_PID - if (BOTH(WATCH_BED, WATCH_HOTENDS) || isbed == DISABLED(WATCH_HOTENDS) || ischamber == DISABLED(WATCH_HOTENDS)) { + if (ALL(WATCH_BED, WATCH_HOTENDS) || isbed == DISABLED(WATCH_HOTENDS) || ischamber == DISABLED(WATCH_HOTENDS)) { if (!heated) { // If not yet reached target... if (current_temp > next_watch_temp) { // Over the watch temp? next_watch_temp = current_temp + watch_temp_increase; // - set the next temp to watch for @@ -848,17 +830,15 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(PID_TUNING_TIMEOUT)); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT)); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_TIMEOUT))); - SERIAL_ECHOPGM(STR_PID_AUTOTUNE); - SERIAL_ECHOLNPGM(STR_PID_TIMEOUT); + SERIAL_ECHOPGM(STR_PID_AUTOTUNE); SERIAL_ECHOLNPGM(STR_PID_TIMEOUT); break; } if (cycles > ncycles && cycles > 2) { - SERIAL_ECHOPGM(STR_PID_AUTOTUNE); - SERIAL_ECHOLNPGM(STR_PID_AUTOTUNE_FINISHED); + SERIAL_ECHOPGM(STR_PID_AUTOTUNE); SERIAL_ECHOLNPGM(STR_PID_AUTOTUNE_FINISHED); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE))); - #if EITHER(PIDTEMPBED, PIDTEMPCHAMBER) + #if ANY(PIDTEMPBED, PIDTEMPCHAMBER) FSTR_P const estring = GHV(F("chamber"), F("bed"), FPSTR(NUL_STR)); say_default_(); SERIAL_ECHOF(estring); SERIAL_ECHOLNPGM("Kp ", tune_pid.p); say_default_(); SERIAL_ECHOF(estring); SERIAL_ECHOLNPGM("Ki ", tune_pid.i); @@ -966,7 +946,7 @@ volatile bool Temperature::raw_temps_ready = false; temp_hotend[active_extruder].target = 0.0f; temp_hotend[active_extruder].soft_pwm_amount = 0; #if HAS_FAN - set_fan_speed(EITHER(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 0); + set_fan_speed(ANY(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 0); planner.sync_fan_speeds(fan_speed); #endif @@ -977,14 +957,14 @@ volatile bool Temperature::raw_temps_ready = false; SERIAL_ECHOPGM(STR_MPC_AUTOTUNE); SERIAL_ECHOLNPGM(STR_MPC_AUTOTUNE_START, active_extruder); MPCHeaterInfo &hotend = temp_hotend[active_extruder]; - MPC_t &constants = hotend.constants; + MPC_t &mpc = hotend.mpc; // Move to center of bed, just above bed height and cool with max fan gcode.home_all_axes(true); disable_all_heaters(); #if HAS_FAN zero_fan_speeds(); - set_fan_speed(EITHER(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 255); + set_fan_speed(ANY(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 255); planner.sync_fan_speeds(fan_speed); #endif const xyz_pos_t tuningpos = MPC_TUNING_POS; @@ -1011,7 +991,7 @@ volatile bool Temperature::raw_temps_ready = false; } #if HAS_FAN - set_fan_speed(EITHER(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 0); + set_fan_speed(ANY(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 0); planner.sync_fan_speeds(fan_speed); #endif @@ -1060,10 +1040,10 @@ volatile bool Temperature::raw_temps_ready = false; float asymp_temp = (t2 * t2 - t1 * t3) / (2 * t2 - t1 - t3), block_responsiveness = -log((t2 - asymp_temp) / (t1 - asymp_temp)) / (sample_distance * (sample_count >> 1)); - constants.ambient_xfer_coeff_fan0 = constants.heater_power * (MPC_MAX) / 255 / (asymp_temp - ambient_temp); - constants.fan255_adjustment = 0.0f; - constants.block_heat_capacity = constants.ambient_xfer_coeff_fan0 / block_responsiveness; - constants.sensor_responsiveness = block_responsiveness / (1.0f - (ambient_temp - asymp_temp) * exp(-block_responsiveness * t1_time) / (t1 - asymp_temp)); + mpc.ambient_xfer_coeff_fan0 = mpc.heater_power * (MPC_MAX) / 255 / (asymp_temp - ambient_temp); + mpc.fan255_adjustment = 0.0f; + mpc.block_heat_capacity = mpc.ambient_xfer_coeff_fan0 / block_responsiveness; + mpc.sensor_responsiveness = block_responsiveness / (1.0f - (ambient_temp - asymp_temp) * exp(-block_responsiveness * t1_time) / (t1 - asymp_temp)); hotend.modeled_block_temp = asymp_temp + (ambient_temp - asymp_temp) * exp(-block_responsiveness * (ms - heat_start_time) / 1000.0f); hotend.modeled_sensor_temp = current_temp; @@ -1090,17 +1070,17 @@ volatile bool Temperature::raw_temps_ready = false; hotend.soft_pwm_amount = (int)get_pid_output_hotend(active_extruder) >> 1; if (ELAPSED(ms, settle_end_ms) && !ELAPSED(ms, test_end_ms) && TERN1(HAS_FAN, !fan0_done)) - total_energy_fan0 += constants.heater_power * hotend.soft_pwm_amount / 127 * MPC_dT + (last_temp - current_temp) * constants.block_heat_capacity; + total_energy_fan0 += mpc.heater_power * hotend.soft_pwm_amount / 127 * MPC_dT + (last_temp - current_temp) * mpc.block_heat_capacity; #if HAS_FAN else if (ELAPSED(ms, test_end_ms) && !fan0_done) { - set_fan_speed(EITHER(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 255); + set_fan_speed(ANY(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) ? 0 : active_extruder, 255); planner.sync_fan_speeds(fan_speed); settle_end_ms = ms + settle_time; test_end_ms = settle_end_ms + test_duration; fan0_done = true; } else if (ELAPSED(ms, settle_end_ms) && !ELAPSED(ms, test_end_ms)) - total_energy_fan255 += constants.heater_power * hotend.soft_pwm_amount / 127 * MPC_dT + (last_temp - current_temp) * constants.block_heat_capacity; + total_energy_fan255 += mpc.heater_power * hotend.soft_pwm_amount / 127 * MPC_dT + (last_temp - current_temp) * mpc.block_heat_capacity; #endif else if (ELAPSED(ms, test_end_ms)) break; @@ -1115,19 +1095,19 @@ volatile bool Temperature::raw_temps_ready = false; } const float power_fan0 = total_energy_fan0 * 1000 / test_duration; - constants.ambient_xfer_coeff_fan0 = power_fan0 / (hotend.target - ambient_temp); + mpc.ambient_xfer_coeff_fan0 = power_fan0 / (hotend.target - ambient_temp); #if HAS_FAN const float power_fan255 = total_energy_fan255 * 1000 / test_duration, ambient_xfer_coeff_fan255 = power_fan255 / (hotend.target - ambient_temp); - constants.fan255_adjustment = ambient_xfer_coeff_fan255 - constants.ambient_xfer_coeff_fan0; + mpc.fan255_adjustment = ambient_xfer_coeff_fan255 - mpc.ambient_xfer_coeff_fan0; #endif - // Calculate a new and better asymptotic temperature and re-evaluate the other constants - asymp_temp = ambient_temp + constants.heater_power * (MPC_MAX) / 255 / constants.ambient_xfer_coeff_fan0; + // Calculate a new and better asymptotic temperature and re-evaluate the other mpc + asymp_temp = ambient_temp + mpc.heater_power * (MPC_MAX) / 255 / mpc.ambient_xfer_coeff_fan0; block_responsiveness = -log((t2 - asymp_temp) / (t1 - asymp_temp)) / (sample_distance * (sample_count >> 1)); - constants.block_heat_capacity = constants.ambient_xfer_coeff_fan0 / block_responsiveness; - constants.sensor_responsiveness = block_responsiveness / (1.0f - (ambient_temp - asymp_temp) * exp(-block_responsiveness * t1_time) / (t1 - asymp_temp)); + mpc.block_heat_capacity = mpc.ambient_xfer_coeff_fan0 / block_responsiveness; + mpc.sensor_responsiveness = block_responsiveness / (1.0f - (ambient_temp - asymp_temp) * exp(-block_responsiveness * t1_time) / (t1 - asymp_temp)); SERIAL_ECHOPGM(STR_MPC_AUTOTUNE); SERIAL_ECHOLNPGM(STR_MPC_AUTOTUNE_FINISHED); @@ -1142,9 +1122,9 @@ volatile bool Temperature::raw_temps_ready = false; SERIAL_ECHOLNPGM("asymp_temp ", asymp_temp); SERIAL_ECHOLNPAIR_F("block_responsiveness ", block_responsiveness, 4); //*/ - SERIAL_ECHOLNPGM("MPC_BLOCK_HEAT_CAPACITY ", constants.block_heat_capacity); - SERIAL_ECHOLNPAIR_F("MPC_SENSOR_RESPONSIVENESS ", constants.sensor_responsiveness, 4); - SERIAL_ECHOLNPAIR_F("MPC_AMBIENT_XFER_COEFF ", constants.ambient_xfer_coeff_fan0, 4); + SERIAL_ECHOLNPGM("MPC_BLOCK_HEAT_CAPACITY ", mpc.block_heat_capacity); + SERIAL_ECHOLNPAIR_F("MPC_SENSOR_RESPONSIVENESS ", mpc.sensor_responsiveness, 4); + SERIAL_ECHOLNPAIR_F("MPC_AMBIENT_XFER_COEFF ", mpc.ambient_xfer_coeff_fan0, 4); TERN_(HAS_FAN, SERIAL_ECHOLNPAIR_F("MPC_AMBIENT_XFER_COEFF_FAN255 ", ambient_xfer_coeff_fan255, 4)); } @@ -1235,7 +1215,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { }while(0) uint8_t fanDone = 0; - LOOP_L_N(f, COUNT(fanBit)) { + for (uint8_t f = 0; f < COUNT(fanBit); ++f) { const uint8_t realFan = pgm_read_byte(&fanBit[f]); if (TEST(fanDone, realFan)) continue; const bool fan_on = TEST(fanState, realFan); @@ -1251,13 +1231,13 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { break; #endif default: - #if EITHER(AUTO_POWER_E_FANS, HAS_FANCHECK) + #if ANY(AUTO_POWER_E_FANS, HAS_FANCHECK) autofan_speed[realFan] = fan_on ? EXTRUDER_AUTO_FAN_SPEED : 0; #endif break; } - #if BOTH(HAS_FANCHECK, HAS_PWMFANCHECK) + #if ALL(HAS_FANCHECK, HAS_PWMFANCHECK) #define _AUTOFAN_SPEED() fan_check.is_measuring() ? 255 : EXTRUDER_AUTO_FAN_SPEED #else #define _AUTOFAN_SPEED() EXTRUDER_AUTO_FAN_SPEED @@ -1267,7 +1247,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #define AUTOFAN_CASE(N) TERN(HAS_AUTO_FAN_##N, _AUTOFAN_CASE, _AUTOFAN_NOT)(N) switch (f) { - REPEAT(8, AUTOFAN_CASE) + REPEAT(HOTENDS, AUTOFAN_CASE) #if HAS_AUTO_CHAMBER_FAN && !AUTO_CHAMBER_IS_E case CHAMBER_FAN_INDEX: _UPDATE_AUTO_FAN(CHAMBER, fan_on, CHAMBER_AUTO_FAN_SPEED); break; #endif @@ -1303,6 +1283,15 @@ inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) { planner.synchronize(); } #endif + + #define _FSTR_BED(h) TERN(HAS_HEATED_BED, (h) == H_BED ? GET_TEXT_F(MSG_BED) :,) + #define _FSTR_CHAMBER(h) TERN(HAS_HEATED_CHAMBER, (h) == H_CHAMBER ? GET_TEXT_F(MSG_CHAMBER) :,) + #define _FSTR_COOLER(h) TERN(HAS_COOLER, (h) == H_COOLER ? GET_TEXT_F(MSG_COOLER) :,) + #define _FSTR_E(h,N) TERN(HAS_HOTEND, ((h) == N && (HOTENDS) > N) ? F(STR_E##N) :,) + #define HEATER_FSTR(h) _FSTR_BED(h) _FSTR_CHAMBER(h) _FSTR_COOLER(h) \ + _FSTR_E(h,1) _FSTR_E(h,2) _FSTR_E(h,3) _FSTR_E(h,4) \ + _FSTR_E(h,5) _FSTR_E(h,6) _FSTR_E(h,7) F(STR_E0) + kill(lcd_msg, HEATER_FSTR(heater_id)); } @@ -1331,8 +1320,7 @@ void Temperature::_temp_error(const heater_id_t heater_id, FSTR_P const serial_m OPTCODE(HAS_TEMP_CHAMBER, case H_CHAMBER: SERIAL_ECHOPGM(STR_HEATER_CHAMBER); break) OPTCODE(HAS_TEMP_BED, case H_BED: SERIAL_ECHOPGM(STR_HEATER_BED); break) default: - if (real_heater_id >= 0) - SERIAL_ECHOLNPGM("E", real_heater_id); + if (real_heater_id >= 0) SERIAL_ECHOLNPGM("E", real_heater_id); } SERIAL_EOL(); } @@ -1459,7 +1447,7 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { #elif ENABLED(MPCTEMP) MPCHeaterInfo &hotend = temp_hotend[ee]; - MPC_t &constants = hotend.constants; + MPC_t &mpc = hotend.mpc; // At startup, initialize modeled temperatures if (isnan(hotend.modeled_block_temp)) { @@ -1473,11 +1461,11 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { const bool this_hotend = (ee == active_extruder); #endif - float ambient_xfer_coeff = constants.ambient_xfer_coeff_fan0; + float ambient_xfer_coeff = mpc.ambient_xfer_coeff_fan0; #if ENABLED(MPC_INCLUDE_FAN) - const uint8_t fan_index = EITHER(MPC_FAN_0_ACTIVE_HOTEND, MPC_FAN_0_ALL_HOTENDS) ? 0 : ee; + const uint8_t fan_index = ANY(MPC_FAN_0_ACTIVE_HOTEND, MPC_FAN_0_ALL_HOTENDS) ? 0 : ee; const float fan_fraction = TERN_(MPC_FAN_0_ACTIVE_HOTEND, !this_hotend ? 0.0f : ) fan_speed[fan_index] * RECIPROCAL(255); - ambient_xfer_coeff += fan_fraction * constants.fan255_adjustment; + ambient_xfer_coeff += fan_fraction * mpc.fan255_adjustment; #endif if (this_hotend) { @@ -1488,17 +1476,17 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { if (fabs(e_speed) > planner.settings.max_feedrate_mm_s[E_AXIS]) mpc_e_position = e_position; else if (e_speed > 0.0f) { // Ignore retract/recover moves - ambient_xfer_coeff += e_speed * constants.filament_heat_capacity_permm; + ambient_xfer_coeff += e_speed * mpc.filament_heat_capacity_permm; mpc_e_position = e_position; } } // Update the modeled temperatures - float blocktempdelta = hotend.soft_pwm_amount * constants.heater_power * (MPC_dT / 127) / constants.block_heat_capacity; - blocktempdelta += (hotend.modeled_ambient_temp - hotend.modeled_block_temp) * ambient_xfer_coeff * MPC_dT / constants.block_heat_capacity; + float blocktempdelta = hotend.soft_pwm_amount * mpc.heater_power * (MPC_dT / 127) / mpc.block_heat_capacity; + blocktempdelta += (hotend.modeled_ambient_temp - hotend.modeled_block_temp) * ambient_xfer_coeff * MPC_dT / mpc.block_heat_capacity; hotend.modeled_block_temp += blocktempdelta; - const float sensortempdelta = (hotend.modeled_block_temp - hotend.modeled_sensor_temp) * (constants.sensor_responsiveness * MPC_dT); + const float sensortempdelta = (hotend.modeled_block_temp - hotend.modeled_sensor_temp) * (mpc.sensor_responsiveness * MPC_dT); hotend.modeled_sensor_temp += sensortempdelta; // Any delta between hotend.modeled_sensor_temp and hotend.celsius is either model @@ -1514,11 +1502,11 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { float power = 0.0; if (hotend.target != 0 && !is_idling) { // Plan power level to get to target temperature in 2 seconds - power = (hotend.target - hotend.modeled_block_temp) * constants.block_heat_capacity / 2.0f; + power = (hotend.target - hotend.modeled_block_temp) * mpc.block_heat_capacity / 2.0f; power -= (hotend.modeled_ambient_temp - hotend.modeled_block_temp) * ambient_xfer_coeff; } - float pid_output = power * 254.0f / constants.heater_power + 1.0f; // Ensure correct quantization into a range of 0 to 127 + float pid_output = power * 254.0f / mpc.heater_power + 1.0f; // Ensure correct quantization into a range of 0 to 127 pid_output = constrain(pid_output, 0, MPC_MAX); /* <-- add a slash to enable @@ -1623,7 +1611,7 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { } #endif // WATCH_BED - #if BOTH(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING) + #if ALL(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING) #define PAUSE_CHANGE_REQD 1 #endif @@ -1693,7 +1681,7 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { #endif #if ENABLED(THERMAL_PROTECTION_CHAMBER) - if (degChamber() > (CHAMBER_MAXTEMP)) maxtemp_error(H_CHAMBER); + if (degChamber() > CHAMBER_MAXTEMP) maxtemp_error(H_CHAMBER); #endif #if WATCH_CHAMBER @@ -1706,11 +1694,11 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { } #endif - #if EITHER(CHAMBER_FAN, CHAMBER_VENT) || DISABLED(PIDTEMPCHAMBER) + #if ANY(CHAMBER_FAN, CHAMBER_VENT) || DISABLED(PIDTEMPCHAMBER) static bool flag_chamber_excess_heat; // = false; #endif - #if EITHER(CHAMBER_FAN, CHAMBER_VENT) + #if ANY(CHAMBER_FAN, CHAMBER_VENT) static bool flag_chamber_off; // = false if (temp_chamber.target > CHAMBER_MINTEMP) { @@ -1739,21 +1727,21 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { #ifndef MIN_COOLING_SLOPE_DEG_CHAMBER_VENT #define MIN_COOLING_SLOPE_DEG_CHAMBER_VENT 1.5 #endif - if (!flag_chamber_excess_heat && temp_chamber.is_above_target((HIGH_EXCESS_HEAT_LIMIT) - 1)) { + if (!flag_chamber_excess_heat && temp_chamber.is_above_target(HIGH_EXCESS_HEAT_LIMIT)) { // Open vent after MIN_COOLING_SLOPE_TIME_CHAMBER_VENT seconds if the // temperature didn't drop at least MIN_COOLING_SLOPE_DEG_CHAMBER_VENT - if (next_cool_check_ms_2 == 0 || ELAPSED(ms, next_cool_check_ms_2)) { + if (next_cool_check_ms == 0 || ELAPSED(ms, next_cool_check_ms)) { if (temp_chamber.celsius - old_temp > MIN_COOLING_SLOPE_DEG_CHAMBER_VENT) flag_chamber_excess_heat = true; // the bed is heating the chamber too much - next_cool_check_ms_2 = ms + SEC_TO_MS(MIN_COOLING_SLOPE_TIME_CHAMBER_VENT); + next_cool_check_ms = ms + SEC_TO_MS(MIN_COOLING_SLOPE_TIME_CHAMBER_VENT); old_temp = temp_chamber.celsius; } } else { - next_cool_check_ms_2 = 0; + next_cool_check_ms = 0; old_temp = 9999; } - if (flag_chamber_excess_heat && temp_chamber.is_above_target((LOW_EXCESS_HEAT_LIMIT) - 1)) + if (flag_chamber_excess_heat && temp_chamber.is_above_target(LOW_EXCESS_HEAT_LIMIT)) flag_chamber_excess_heat = false; #endif } @@ -1785,9 +1773,9 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { } else { #if ENABLED(CHAMBER_LIMIT_SWITCHING) - if (temp_chamber.is_above_target((TEMP_CHAMBER_HYSTERESIS) - 1)) + if (temp_chamber.is_above_target(TEMP_CHAMBER_HYSTERESIS)) temp_chamber.soft_pwm_amount = 0; - else if (temp_chamber.is_below_target((TEMP_CHAMBER_HYSTERESIS) - 1)) + else if (temp_chamber.is_below_target(TEMP_CHAMBER_HYSTERESIS)) temp_chamber.soft_pwm_amount = (MAX_CHAMBER_POWER) >> 1; #else temp_chamber.soft_pwm_amount = temp_chamber.is_below_target() ? (MAX_CHAMBER_POWER) >> 1 : 0; @@ -1828,7 +1816,7 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { if (degCooler() > watch_cooler.target) // Failed to decrease enough? _temp_error(H_COOLER, GET_TEXT_F(MSG_COOLING_FAILED), GET_TEXT_F(MSG_COOLING_FAILED)); else - start_watching_cooler(); // Start again if the target is still far off + start_watching_cooler(); // Start again if the target is still far off } #endif @@ -1896,7 +1884,7 @@ void Temperature::task() { quickstop_stepper(); } - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA if (emergency_parser.sd_abort_by_M524) { // abort SD print immediately emergency_parser.sd_abort_by_M524 = false; card.flag.abort_sd_printing = true; @@ -1909,20 +1897,24 @@ void Temperature::task() { #if DISABLED(IGNORE_THERMOCOUPLE_ERRORS) #if TEMP_SENSOR_IS_MAX_TC(0) - if (degHotend(0) > _MIN(HEATER_0_MAXTEMP, TEMP_SENSOR_0_MAX_TC_TMAX - 1.0)) maxtemp_error(H_E0); - if (degHotend(0) < _MAX(HEATER_0_MINTEMP, TEMP_SENSOR_0_MAX_TC_TMIN + .01)) mintemp_error(H_E0); + if (degHotend(0) > _MIN(HEATER_0_MAXTEMP, TEMP_SENSOR_0_MAX_TC_TMAX - 1.00f)) maxtemp_error(H_E0); + if (degHotend(0) < _MAX(HEATER_0_MINTEMP, TEMP_SENSOR_0_MAX_TC_TMIN + 0.01f)) mintemp_error(H_E0); #endif #if TEMP_SENSOR_IS_MAX_TC(1) - if (degHotend(1) > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.0)) maxtemp_error(H_E1); - if (degHotend(1) < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + .01)) mintemp_error(H_E1); + if (degHotend(1) > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.00f)) maxtemp_error(H_E1); + if (degHotend(1) < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + 0.01f)) mintemp_error(H_E1); #endif #if TEMP_SENSOR_IS_MAX_TC(2) - if (degHotend(2) > _MIN(HEATER_2_MAXTEMP, TEMP_SENSOR_2_MAX_TC_TMAX - 1.0)) maxtemp_error(H_E2); - if (degHotend(2) < _MAX(HEATER_2_MINTEMP, TEMP_SENSOR_2_MAX_TC_TMIN + .01)) mintemp_error(H_E2); + if (degHotend(2) > _MIN(HEATER_2_MAXTEMP, TEMP_SENSOR_2_MAX_TC_TMAX - 1.00f)) maxtemp_error(H_E2); + if (degHotend(2) < _MAX(HEATER_2_MINTEMP, TEMP_SENSOR_2_MAX_TC_TMIN + 0.01f)) mintemp_error(H_E2); #endif #if TEMP_SENSOR_IS_MAX_TC(REDUNDANT) - if (degRedundant() > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.0) maxtemp_error(H_REDUNDANT); - if (degRedundant() < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + .01) mintemp_error(H_REDUNDANT); + if (degRedundant() > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.00f) maxtemp_error(H_REDUNDANT); + if (degRedundant() < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + 0.01f) mintemp_error(H_REDUNDANT); + #endif + #if TEMP_SENSOR_IS_MAX_TC(BED) + if (degBed() > _MIN(BED_MAXTEMP, TEMP_SENSOR_BED_MAX_TC_TMAX - 1.00f)) maxtemp_error(H_BED); + if (degBed() < _MAX(BED_MINTEMP, TEMP_SENSOR_BED_MAX_TC_TMIN + 0.01f)) mintemp_error(H_BED); #endif #else #warning "Safety Alert! Disable IGNORE_THERMOCOUPLE_ERRORS for the final build!" @@ -2135,7 +2127,7 @@ void Temperature::task() { max31865_0.temperature(MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0) ); #else - return (int16_t)raw * 0.25; + return (int16_t)raw * 0.25f; #endif #elif TEMP_SENSOR_0_IS_AD595 return TEMP_AD595(raw); @@ -2154,7 +2146,7 @@ void Temperature::task() { max31865_1.temperature(MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1) ); #else - return (int16_t)raw * 0.25; + return (int16_t)raw * 0.25f; #endif #elif TEMP_SENSOR_1_IS_AD595 return TEMP_AD595(raw); @@ -2173,7 +2165,7 @@ void Temperature::task() { max31865_2.temperature(MAX31865_SENSOR_OHMS_2, MAX31865_CALIBRATION_OHMS_2) ); #else - return (int16_t)raw * 0.25; + return (int16_t)raw * 0.25f; #endif #elif TEMP_SENSOR_2_IS_AD595 return TEMP_AD595(raw); @@ -2250,6 +2242,15 @@ void Temperature::task() { celsius_float_t Temperature::analog_to_celsius_bed(const raw_adc_t raw) { #if TEMP_SENSOR_BED_IS_CUSTOM return user_thermistor_to_deg_c(CTI_BED, raw); + #elif TEMP_SENSOR_IS_MAX_TC(BED) + #if TEMP_SENSOR_BED_IS_MAX31865 + return TERN(LIB_INTERNAL_MAX31865, + max31865_BED.temperature(raw), + max31865_BED.temperature(MAX31865_SENSOR_OHMS_BED, MAX31865_CALIBRATION_OHMS_BED) + ); + #else + return (int16_t)raw * 0.25f; + #endif #elif TEMP_SENSOR_BED_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_BED, TEMPTABLE_BED_LEN); #elif TEMP_SENSOR_BED_IS_AD595 @@ -2341,11 +2342,11 @@ void Temperature::task() { #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM return user_thermistor_to_deg_c(CTI_REDUNDANT, raw); #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E0) - return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature(raw), (int16_t)raw * 0.25); + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature(raw), (int16_t)raw * 0.25f); #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1) - return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature(raw), (int16_t)raw * 0.25); + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature(raw), (int16_t)raw * 0.25f); #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E2) - return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_2.temperature(raw), (int16_t)raw * 0.25); + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_2.temperature(raw), (int16_t)raw * 0.25f); #elif TEMP_SENSOR_REDUNDANT_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_REDUNDANT, TEMPTABLE_REDUNDANT_LEN); #elif TEMP_SENSOR_REDUNDANT_IS_AD595 @@ -2387,6 +2388,9 @@ void Temperature::updateTemperaturesFromRawValues() { #if TEMP_SENSOR_IS_MAX_TC(REDUNDANT) temp_redundant.setraw(READ_MAX_TC(HEATER_ID(TEMP_SENSOR_REDUNDANT_SOURCE))); #endif + #if TEMP_SENSOR_IS_MAX_TC(BED) + temp_bed.setraw(read_max_tc_bed()); + #endif #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].celsius = analog_to_celsius_hotend(temp_hotend[e].getraw(), e); @@ -2460,17 +2464,17 @@ void Temperature::updateTemperaturesFromRawValues() { if (temp_bed.target > 0 && TP_CMP(BED, mintemp_raw_BED, temp_bed.getraw())) mintemp_error(H_BED); #endif - #if BOTH(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) + #if ALL(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) if (TP_CMP(CHAMBER, temp_chamber.getraw(), maxtemp_raw_CHAMBER)) maxtemp_error(H_CHAMBER); if (temp_chamber.target > 0 && TP_CMP(CHAMBER, mintemp_raw_CHAMBER, temp_chamber.getraw())) mintemp_error(H_CHAMBER); #endif - #if BOTH(HAS_COOLER, THERMAL_PROTECTION_COOLER) + #if ALL(HAS_COOLER, THERMAL_PROTECTION_COOLER) if (cutter.unitPower > 0 && TP_CMP(COOLER, temp_cooler.getraw(), maxtemp_raw_COOLER)) maxtemp_error(H_COOLER); if (TP_CMP(COOLER, mintemp_raw_COOLER, temp_cooler.getraw())) mintemp_error(H_COOLER); #endif - #if BOTH(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) + #if ALL(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) if (TP_CMP(BOARD, temp_board.getraw(), maxtemp_raw_BOARD)) maxtemp_error(H_BOARD); if (TP_CMP(BOARD, mintemp_raw_BOARD, temp_board.getraw())) mintemp_error(H_BOARD); #endif @@ -2500,7 +2504,6 @@ void Temperature::init() { TERN_(PROBING_HEATERS_OFF, paused_for_probing = false); - // Init (and disable) SPI thermocouples #if TEMP_SENSOR_IS_ANY_MAX_TC(0) && PIN_EXISTS(TEMP_0_CS) OUT_WRITE(TEMP_0_CS_PIN, HIGH); @@ -2550,6 +2553,17 @@ void Temperature::init() { ); #endif + #if TEMP_SENSOR_IS_MAX(BED, 6675) && HAS_MAX6675_LIBRARY + max6675_BED.begin(); + #elif TEMP_SENSOR_IS_MAX(BED, 31855) && HAS_MAX31855_LIBRARY + max31855_BED.begin(); + #elif TEMP_SENSOR_IS_MAX(BED, 31865) + max31865_BED.begin( + MAX31865_WIRES(MAX31865_SENSOR_WIRES_BED) // MAX31865_BEDWIRE, MAX31865_3WIRE, MAX31865_4WIRE + OPTARG(LIB_INTERNAL_MAX31865, MAX31865_SENSOR_OHMS_BED, MAX31865_CALIBRATION_OHMS_BED, MAX31865_WIRE_OHMS_BED) + ); + #endif + #undef MAX31865_WIRES #undef _MAX31865_WIRES #endif @@ -2598,51 +2612,51 @@ void Temperature::init() { #if HAS_HEATER_0 #ifdef BOARD_OPENDRAIN_MOSFETS - OUT_WRITE_OD(HEATER_0_PIN, HEATER_0_INVERTING); + OUT_WRITE_OD(HEATER_0_PIN, ENABLED(HEATER_0_INVERTING)); #else - OUT_WRITE(HEATER_0_PIN, HEATER_0_INVERTING); + OUT_WRITE(HEATER_0_PIN, ENABLED(HEATER_0_INVERTING)); #endif #endif #if HAS_HEATER_1 - OUT_WRITE(HEATER_1_PIN, HEATER_1_INVERTING); + OUT_WRITE(HEATER_1_PIN, ENABLED(HEATER_1_INVERTING)); #endif #if HAS_HEATER_2 - OUT_WRITE(HEATER_2_PIN, HEATER_2_INVERTING); + OUT_WRITE(HEATER_2_PIN, ENABLED(HEATER_2_INVERTING)); #endif #if HAS_HEATER_3 - OUT_WRITE(HEATER_3_PIN, HEATER_3_INVERTING); + OUT_WRITE(HEATER_3_PIN, ENABLED(HEATER_3_INVERTING)); #endif #if HAS_HEATER_4 - OUT_WRITE(HEATER_4_PIN, HEATER_4_INVERTING); + OUT_WRITE(HEATER_4_PIN, ENABLED(HEATER_4_INVERTING)); #endif #if HAS_HEATER_5 - OUT_WRITE(HEATER_5_PIN, HEATER_5_INVERTING); + OUT_WRITE(HEATER_5_PIN, ENABLED(HEATER_5_INVERTING)); #endif #if HAS_HEATER_6 - OUT_WRITE(HEATER_6_PIN, HEATER_6_INVERTING); + OUT_WRITE(HEATER_6_PIN, ENABLED(HEATER_6_INVERTING)); #endif #if HAS_HEATER_7 - OUT_WRITE(HEATER_7_PIN, HEATER_7_INVERTING); + OUT_WRITE(HEATER_7_PIN, ENABLED(HEATER_7_INVERTING)); #endif #if HAS_HEATED_BED #ifdef BOARD_OPENDRAIN_MOSFETS - OUT_WRITE_OD(HEATER_BED_PIN, HEATER_BED_INVERTING); + OUT_WRITE_OD(HEATER_BED_PIN, ENABLED(HEATER_BED_INVERTING)); #else - OUT_WRITE(HEATER_BED_PIN, HEATER_BED_INVERTING); + OUT_WRITE(HEATER_BED_PIN, ENABLED(HEATER_BED_INVERTING)); #endif #endif #if HAS_HEATED_CHAMBER - OUT_WRITE(HEATER_CHAMBER_PIN, HEATER_CHAMBER_INVERTING); + OUT_WRITE(HEATER_CHAMBER_PIN, ENABLED(HEATER_CHAMBER_INVERTING)); #endif #if HAS_COOLER - OUT_WRITE(COOLER_PIN, COOLER_INVERTING); + OUT_WRITE(COOLER_PIN, ENABLED(COOLER_INVERTING)); #endif #if HAS_FAN0 - INIT_FAN_PIN(FAN_PIN); + INIT_FAN_PIN(FAN0_PIN); #endif #if HAS_FAN1 INIT_FAN_PIN(FAN1_PIN); @@ -2752,7 +2766,7 @@ void Temperature::init() { temp_range[NR].raw_max -= TEMPDIR(NR) * (OVERSAMPLENR); \ }while(0) - #define _MINMAX_TEST(N,M) (HOTENDS > N && TEMP_SENSOR(N) > 0 && TEMP_SENSOR(N) != 998 && TEMP_SENSOR(N) != 999 && defined(HEATER_##N##_##M##TEMP)) + #define _MINMAX_TEST(N,M) (!TEMP_SENSOR_##N##_IS_DUMMY && HOTENDS > (N) && TEMP_SENSOR_##N##_IS_THERMISTOR && defined(HEATER_##N##_##M##TEMP)) #if _MINMAX_TEST(0, MIN) _TEMP_MIN_E(0); @@ -2820,7 +2834,7 @@ void Temperature::init() { while (analog_to_celsius_cooler(maxtemp_raw_COOLER) < COOLER_MAXTEMP) maxtemp_raw_COOLER -= TEMPDIR(COOLER) * (OVERSAMPLENR); #endif - #if BOTH(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) + #if ALL(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) while (analog_to_celsius_board(mintemp_raw_BOARD) < BOARD_MINTEMP) mintemp_raw_BOARD += TEMPDIR(BOARD) * (OVERSAMPLENR); while (analog_to_celsius_board(maxtemp_raw_BOARD) > BOARD_MAXTEMP) maxtemp_raw_BOARD -= TEMPDIR(BOARD) * (OVERSAMPLENR); #endif @@ -2847,7 +2861,9 @@ void Temperature::init() { #if HAS_THERMAL_PROTECTION #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wimplicit-fallthrough" + #if __has_cpp_attribute(fallthrough) + #pragma GCC diagnostic ignored "-Wimplicit-fallthrough" + #endif Temperature::tr_state_machine_t Temperature::tr_state_machine[NR_HEATER_RUNAWAY]; // = { { TRInactive, 0 } }; @@ -3064,7 +3080,7 @@ void Temperature::disable_all_heaters() { #endif // PROBING_HEATERS_OFF -#if EITHER(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) +#if ANY(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) void Temperature::singlenozzle_change(const uint8_t old_tool, const uint8_t new_tool) { #if ENABLED(SINGLENOZZLE_STANDBY_FAN) @@ -3086,6 +3102,8 @@ void Temperature::disable_all_heaters() { #if HAS_MAX_TC + typedef TERN(HAS_MAX31855, uint32_t, uint16_t) max_tc_temp_t; + #ifndef THERMOCOUPLE_MAX_ERRORS #define THERMOCOUPLE_MAX_ERRORS 15 #endif @@ -3185,12 +3203,10 @@ void Temperature::disable_all_heaters() { MAX6675 &max6675ref = THERMO_SEL(max6675_0, max6675_1, max6675_2); max_tc_temp = max6675ref.readRaw16(); #endif - #if HAS_MAX31855_LIBRARY MAX31855 &max855ref = THERMO_SEL(max31855_0, max31855_1, max31855_2); max_tc_temp = max855ref.readRaw32(); #endif - #if HAS_MAX31865 MAX31865 &max865ref = THERMO_SEL(max31865_0, max31865_1, max31865_2); max_tc_temp = TERN(LIB_INTERNAL_MAX31865, max865ref.readRaw(), max865ref.readRTD_with_Fault()); @@ -3207,30 +3223,21 @@ void Temperature::disable_all_heaters() { SERIAL_ECHOPGM("Temp measurement error! "); #if HAS_MAX31855 SERIAL_ECHOPGM("MAX31855 Fault: (", max_tc_temp & 0x7, ") >> "); - if (max_tc_temp & 0x1) - SERIAL_ECHOLNPGM("Open Circuit"); - else if (max_tc_temp & 0x2) - SERIAL_ECHOLNPGM("Short to GND"); - else if (max_tc_temp & 0x4) - SERIAL_ECHOLNPGM("Short to VCC"); + if (max_tc_temp & 0x1) SERIAL_ECHOLNPGM("Open Circuit"); + else if (max_tc_temp & 0x2) SERIAL_ECHOLNPGM("Short to GND"); + else if (max_tc_temp & 0x4) SERIAL_ECHOLNPGM("Short to VCC"); #elif HAS_MAX31865 const uint8_t fault_31865 = max865ref.readFault(); max865ref.clearFault(); if (fault_31865) { SERIAL_EOL(); SERIAL_ECHOLNPGM("\nMAX31865 Fault: (", fault_31865, ") >>"); - if (fault_31865 & MAX31865_FAULT_HIGHTHRESH) - SERIAL_ECHOLNPGM("RTD High Threshold"); - if (fault_31865 & MAX31865_FAULT_LOWTHRESH) - SERIAL_ECHOLNPGM("RTD Low Threshold"); - if (fault_31865 & MAX31865_FAULT_REFINLOW) - SERIAL_ECHOLNPGM("REFIN- > 0.85 x V bias"); - if (fault_31865 & MAX31865_FAULT_REFINHIGH) - SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); - if (fault_31865 & MAX31865_FAULT_RTDINLOW) - SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); - if (fault_31865 & MAX31865_FAULT_OVUV) - SERIAL_ECHOLNPGM("Under/Over voltage"); + if (fault_31865 & MAX31865_FAULT_HIGHTHRESH) SERIAL_ECHOLNPGM("RTD High Threshold"); + if (fault_31865 & MAX31865_FAULT_LOWTHRESH) SERIAL_ECHOLNPGM("RTD Low Threshold"); + if (fault_31865 & MAX31865_FAULT_REFINLOW) SERIAL_ECHOLNPGM("REFIN- > 0.85 x V bias"); + if (fault_31865 & MAX31865_FAULT_REFINHIGH) SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); + if (fault_31865 & MAX31865_FAULT_RTDINLOW) SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); + if (fault_31865 & MAX31865_FAULT_OVUV) SERIAL_ECHOLNPGM("Under/Over voltage"); } #else // MAX6675 SERIAL_ECHOLNPGM("MAX6675 Fault: Open Circuit"); @@ -3258,6 +3265,124 @@ void Temperature::disable_all_heaters() { #endif // HAS_MAX_TC +#if TEMP_SENSOR_IS_MAX_TC(BED) + /** + * @brief Read MAX Thermocouple temperature. + * + * Reads the thermocouple board via HW or SW SPI, using a library (LIB_USR_x) or raw SPI reads. + * Doesn't strictly return a temperature; returns an "ADC Value" (i.e. raw register content). + * + * @return integer representing the board's buffer, to be converted later if needed + */ + raw_adc_t Temperature::read_max_tc_bed() { + #define MAXTC_HEAT_INTERVAL 250UL + + #if TEMP_SENSOR_BED_IS_MAX31855 + #define BED_MAX_TC_ERROR_MASK 7 // D2-0: SCV, SCG, OC + #define BED_MAX_TC_DISCARD_BITS 18 // Data D31-18; sign bit D31 + #define BED_MAX_TC_SPEED_BITS 3 // ~1MHz + #elif TEMP_SENSOR_BED_IS_MAX31865 + #define BED_MAX_TC_ERROR_MASK 1 // D0 Bit on fault only + #define BED_MAX_TC_DISCARD_BITS 1 // Data is in D15-D1 + #define BED_MAX_TC_SPEED_BITS 3 // ~1MHz + #else // MAX6675 + #define BED_MAX_TC_ERROR_MASK 3 // D2 only; 1 = open circuit + #define BED_MAX_TC_DISCARD_BITS 3 // Data D15-D1 + #define BED_MAX_TC_SPEED_BITS 2 // ~2MHz + #endif + + static max_tc_temp_t max_tc_temp = TEMP_SENSOR_BED_MAX_TC_TMAX; + + static uint8_t max_tc_errors = 0; + static millis_t next_max_tc_ms = 0; + + // Return last-read value between readings + const millis_t ms = millis(); + if (PENDING(ms, next_max_tc_ms)) return max_tc_temp; + next_max_tc_ms = ms + MAXTC_HEAT_INTERVAL; + + #if !HAS_MAXTC_LIBRARIES + max_tc_temp = 0; + + #if !HAS_MAXTC_SW_SPI + // Initialize SPI using the default Hardware SPI bus. + // FIXME: spiBegin, spiRec and spiInit doesn't work when soft spi is used. + spiBegin(); + spiInit(BED_MAX_TC_SPEED_BITS); + #endif + + WRITE(TEMP_BED_CS_PIN, LOW); // Enable MAXTC + DELAY_NS(100); // Ensure 100ns delay + + // Read a big-endian temperature value without using a library + for (uint8_t i = sizeof(max_tc_temp); i--;) { + max_tc_temp |= TERN(HAS_MAXTC_SW_SPI, max_tc_spi.receive(), spiRec()); + if (i > 0) max_tc_temp <<= 8; // shift left if not the last byte + } + + WRITE(TEMP_BED_CS_PIN, HIGH); // Disable MAXTC + + #elif ALL(TEMP_SENSOR_BED_IS_MAX6675, HAS_MAX6675_LIBRARY) + MAX6675 &max6675ref = max6675_BED; + max_tc_temp = max6675ref.readRaw16(); + #elif ALL(TEMP_SENSOR_BED_IS_MAX31855, HAS_MAX31855_LIBRARY) + MAX31855 &max855ref = max31855_BED; + max_tc_temp = max855ref.readRaw32(); + #elif TEMP_SENSOR_BED_IS_MAX31865 + MAX31865 &max865ref = max31865_BED; + max_tc_temp = TERN(LIB_INTERNAL_MAX31865, max865ref.readRaw(), max865ref.readRTD_with_Fault()); + #endif + + // Handle an error. If there have been more than THERMOCOUPLE_MAX_ERRORS, send an error over serial. + // Either way, return the TMAX for the thermocouple to trigger a maxtemp_error() + if (max_tc_temp & BED_MAX_TC_ERROR_MASK) { + max_tc_errors++; + + if (max_tc_errors > THERMOCOUPLE_MAX_ERRORS) { + SERIAL_ERROR_START(); + SERIAL_ECHOPGM("Bed temp measurement error! "); + #if TEMP_SENSOR_BED_IS_MAX31855 + SERIAL_ECHOPGM("MAX31855 Fault: (", max_tc_temp & 0x7, ") >> "); + if (max_tc_temp & 0x1) SERIAL_ECHOLNPGM("Open Circuit"); + else if (max_tc_temp & 0x2) SERIAL_ECHOLNPGM("Short to GND"); + else if (max_tc_temp & 0x4) SERIAL_ECHOLNPGM("Short to VCC"); + #elif TEMP_SENSOR_BED_IS_MAX31865 + const uint8_t fault_31865 = max865ref.readFault(); + max865ref.clearFault(); + if (fault_31865) { + SERIAL_EOL(); + SERIAL_ECHOLNPGM("\nMAX31865 Fault: (", fault_31865, ") >>"); + if (fault_31865 & MAX31865_FAULT_HIGHTHRESH) SERIAL_ECHOLNPGM("RTD High Threshold"); + if (fault_31865 & MAX31865_FAULT_LOWTHRESH) SERIAL_ECHOLNPGM("RTD Low Threshold"); + if (fault_31865 & MAX31865_FAULT_REFINLOW) SERIAL_ECHOLNPGM("REFIN- > 0.85 x V bias"); + if (fault_31865 & MAX31865_FAULT_REFINHIGH) SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); + if (fault_31865 & MAX31865_FAULT_RTDINLOW) SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); + if (fault_31865 & MAX31865_FAULT_OVUV) SERIAL_ECHOLNPGM("Under/Over voltage"); + } + #else // MAX6675 + SERIAL_ECHOLNPGM("MAX6675 Fault: Open Circuit"); + #endif + + // Set thermocouple above max temperature (TMAX) + max_tc_temp = TEMP_SENSOR_BED_MAX_TC_TMAX << (BED_MAX_TC_DISCARD_BITS + 1); + } + } + else { + max_tc_errors = 0; // No error bit, reset error count + } + + max_tc_temp >>= BED_MAX_TC_DISCARD_BITS; + + #if TEMP_SENSOR_BED_IS_MAX31855 + // Support negative temperature for MAX38155 + if (max_tc_temp & 0x00002000) max_tc_temp |= 0xFFFFC000; + #endif + + return max_tc_temp; + } + +#endif // TEMP_SENSOR_IS_MAX_TC(BED) + /** * Update raw temperatures * @@ -3283,13 +3408,16 @@ void Temperature::update_raw_temperatures() { temp_redundant.update(); #endif + #if HAS_TEMP_ADC_BED && !TEMP_SENSOR_IS_MAX_TC(BED) + temp_bed.update(); + #endif + TERN_(HAS_TEMP_ADC_2, temp_hotend[2].update()); TERN_(HAS_TEMP_ADC_3, temp_hotend[3].update()); TERN_(HAS_TEMP_ADC_4, temp_hotend[4].update()); TERN_(HAS_TEMP_ADC_5, temp_hotend[5].update()); TERN_(HAS_TEMP_ADC_6, temp_hotend[6].update()); TERN_(HAS_TEMP_ADC_7, temp_hotend[7].update()); - TERN_(HAS_TEMP_ADC_BED, temp_bed.update()); TERN_(HAS_TEMP_ADC_CHAMBER, temp_chamber.update()); TERN_(HAS_TEMP_ADC_PROBE, temp_probe.update()); TERN_(HAS_TEMP_ADC_COOLER, temp_cooler.update()); @@ -3431,11 +3559,11 @@ void Temperature::isr() { static SoftPWM soft_pwm_cooler; #endif - #if BOTH(FAN_SOFT_PWM, USE_CONTROLLER_FAN) + #if ALL(FAN_SOFT_PWM, USE_CONTROLLER_FAN) static SoftPWM soft_pwm_controller; #endif - #define WRITE_FAN(n, v) WRITE(FAN##n##_PIN, (v) ^ FAN_INVERTING) + #define WRITE_FAN(n, v) WRITE(FAN##n##_PIN, (v) ^ ENABLED(FAN_INVERTING)) #if DISABLED(SLOW_PWM_HEATERS) @@ -3473,7 +3601,7 @@ void Temperature::isr() { #if ENABLED(FAN_SOFT_PWM) #if ENABLED(USE_CONTROLLER_FAN) - WRITE(CONTROLLER_FAN_PIN, soft_pwm_controller.add(pwm_mask, soft_pwm_controller_speed)); + WRITE(CONTROLLER_FAN_PIN, soft_pwm_controller.add(pwm_mask, controllerFan.soft_pwm_speed)); #endif #define _FAN_PWM(N) do{ \ @@ -3728,7 +3856,9 @@ void Temperature::isr() { switch (adc_sensor_state) { #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wimplicit-fallthrough" + #if __has_cpp_attribute(fallthrough) + #pragma GCC diagnostic ignored "-Wimplicit-fallthrough" + #endif case SensorsReady: { // All sensors have been read. Stay in this state for a few @@ -4093,7 +4223,7 @@ void Temperature::isr() { bool wants_to_cool = false; celsius_float_t target_temp = -1.0, old_temp = 9999.0; - millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; + millis_t now, next_temp_ms = 0, cool_check_ms = 0; wait_for_heatup = true; do { // Target temperature might be changed during the loop @@ -4151,9 +4281,9 @@ void Temperature::isr() { if (wants_to_cool) { // Break after MIN_COOLING_SLOPE_TIME seconds // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG - if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) { + if (!cool_check_ms || ELAPSED(now, cool_check_ms)) { if (old_temp - temp < float(MIN_COOLING_SLOPE_DEG)) break; - next_cool_check_ms = now + SEC_TO_MS(MIN_COOLING_SLOPE_TIME); + cool_check_ms = now + SEC_TO_MS(MIN_COOLING_SLOPE_TIME); old_temp = temp; } } @@ -4167,6 +4297,7 @@ void Temperature::isr() { } while (wait_for_heatup && TEMP_CONDITIONS); + // If wait_for_heatup is set, temperature was reached, no cancel if (wait_for_heatup) { wait_for_heatup = false; #if HAS_DWIN_E3V2_BASIC @@ -4229,7 +4360,7 @@ void Temperature::isr() { bool wants_to_cool = false; celsius_float_t target_temp = -1, old_temp = 9999; - millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; + millis_t now, next_temp_ms = 0, cool_check_ms = 0; wait_for_heatup = true; do { // Target temperature might be changed during the loop @@ -4285,9 +4416,9 @@ void Temperature::isr() { if (wants_to_cool) { // Break after MIN_COOLING_SLOPE_TIME_BED seconds // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG_BED - if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) { + if (!cool_check_ms || ELAPSED(now, cool_check_ms)) { if (old_temp - temp < float(MIN_COOLING_SLOPE_DEG_BED)) break; - next_cool_check_ms = now + SEC_TO_MS(MIN_COOLING_SLOPE_TIME_BED); + cool_check_ms = now + SEC_TO_MS(MIN_COOLING_SLOPE_TIME_BED); old_temp = temp; } } @@ -4305,6 +4436,7 @@ void Temperature::isr() { } while (wait_for_heatup && TEMP_BED_CONDITIONS); + // If wait_for_heatup is set, temperature was reached, no cancel if (wait_for_heatup) { wait_for_heatup = false; ui.reset_status(); @@ -4383,6 +4515,7 @@ void Temperature::isr() { } } + // If wait_for_heatup is set, temperature was reached, no cancel if (wait_for_heatup) { wait_for_heatup = false; ui.reset_status(); @@ -4422,7 +4555,7 @@ void Temperature::isr() { bool wants_to_cool = false; float target_temp = -1, old_temp = 9999; - millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; + millis_t now, next_temp_ms = 0, cool_check_ms = 0; wait_for_heatup = true; do { // Target temperature might be changed during the loop @@ -4474,14 +4607,15 @@ void Temperature::isr() { if (wants_to_cool) { // Break after MIN_COOLING_SLOPE_TIME_CHAMBER seconds // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG_CHAMBER - if (!next_cool_check_ms || ELAPSED(now, next_cool_check_ms)) { + if (!cool_check_ms || ELAPSED(now, cool_check_ms)) { if (old_temp - temp < float(MIN_COOLING_SLOPE_DEG_CHAMBER)) break; - next_cool_check_ms = now + SEC_TO_MS(MIN_COOLING_SLOPE_TIME_CHAMBER); + cool_check_ms = now + SEC_TO_MS(MIN_COOLING_SLOPE_TIME_CHAMBER); old_temp = temp; } } } while (wait_for_heatup && TEMP_CHAMBER_CONDITIONS); + // If wait_for_heatup is set, temperature was reached, no cancel if (wait_for_heatup) { wait_for_heatup = false; ui.reset_status(); @@ -4568,6 +4702,7 @@ void Temperature::isr() { first_loop = false; #endif // TEMP_COOLER_RESIDENCY_TIME > 0 + // Prevent a wait-forever situation if R is misused i.e. M191 R0 if (wants_to_cool) { // Break after MIN_COOLING_SLOPE_TIME_CHAMBER seconds // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG_CHAMBER @@ -4580,7 +4715,7 @@ void Temperature::isr() { } while (wait_for_heatup && TEMP_COOLER_CONDITIONS); - // Prevent a wait-forever situation if R is misused i.e. M191 R0 + // If wait_for_heatup is set, temperature was reached, no cancel if (wait_for_heatup) { wait_for_heatup = false; ui.reset_status(); diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index bd67785383b0..10bb12f8b54c 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -146,7 +146,7 @@ typedef struct { float p, i, d, c, f; } raw_pidcf_t; #if HAS_PID_HEATING - #define PID_K2 (1-float(PID_K1)) + #define PID_K2 (1.0f - float(PID_K1)) #define PID_dT ((OVERSAMPLENR * float(ACTUAL_ADC_SAMPLES)) / (TEMP_TIMER_FREQUENCY)) // Apply the scale factors to the PID values @@ -162,125 +162,125 @@ typedef struct { float p, i, d, c, f; } raw_pidcf_t; /// PID classes that implement these features are expected to override these methods /// Since the finally used PID class is typedef-d, there is no need to use virtual functions template - struct PID_t{ - protected: - bool pid_reset = true; - float temp_iState = 0.0f, temp_dState = 0.0f; - float work_p = 0, work_i = 0, work_d = 0; - - public: - float Kp = 0, Ki = 0, Kd = 0; - float p() const { return Kp; } - float i() const { return unscalePID_i(Ki); } - float d() const { return unscalePID_d(Kd); } - float c() const { return 1; } - float f() const { return 0; } - float pTerm() const { return work_p; } - float iTerm() const { return work_i; } - float dTerm() const { return work_d; } - float cTerm() const { return 0; } - float fTerm() const { return 0; } - void set_Kp(float p) { Kp = p; } - void set_Ki(float i) { Ki = scalePID_i(i); } - void set_Kd(float d) { Kd = scalePID_d(d); } - void set_Kc(float) {} - void set_Kf(float) {} - int low() const { return MIN_POW; } - int high() const { return MAX_POW; } - void reset() { pid_reset = true; } - void set(float p, float i, float d, float c=1, float f=0) { set_Kp(p); set_Ki(i); set_Kd(d); set_Kc(c); set_Kf(f); } - void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } - void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } - - float get_fan_scale_output(const uint8_t) { return 0; } - - float get_extrusion_scale_output(const bool, const int32_t, const float, const int16_t) { return 0; } - - float get_pid_output(const float target, const float current) { - const float pid_error = target - current; - if (!target || pid_error < -(PID_FUNCTIONAL_RANGE)) { - pid_reset = true; - return 0; - } - else if (pid_error > PID_FUNCTIONAL_RANGE) { - pid_reset = true; - return MAX_POW; - } + struct PID_t { + protected: + bool pid_reset = true; + float temp_iState = 0.0f, temp_dState = 0.0f; + float work_p = 0, work_i = 0, work_d = 0; + + public: + float Kp = 0, Ki = 0, Kd = 0; + float p() const { return Kp; } + float i() const { return unscalePID_i(Ki); } + float d() const { return unscalePID_d(Kd); } + float c() const { return 1; } + float f() const { return 0; } + float pTerm() const { return work_p; } + float iTerm() const { return work_i; } + float dTerm() const { return work_d; } + float cTerm() const { return 0; } + float fTerm() const { return 0; } + void set_Kp(float p) { Kp = p; } + void set_Ki(float i) { Ki = scalePID_i(i); } + void set_Kd(float d) { Kd = scalePID_d(d); } + void set_Kc(float) {} + void set_Kf(float) {} + int low() const { return MIN_POW; } + int high() const { return MAX_POW; } + void reset() { pid_reset = true; } + void set(float p, float i, float d, float c=1, float f=0) { set_Kp(p); set_Ki(i); set_Kd(d); set_Kc(c); set_Kf(f); } + void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } + void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } + + float get_fan_scale_output(const uint8_t) { return 0; } + + float get_extrusion_scale_output(const bool, const int32_t, const float, const int16_t) { return 0; } + + float get_pid_output(const float target, const float current) { + const float pid_error = target - current; + if (!target || pid_error < -(PID_FUNCTIONAL_RANGE)) { + pid_reset = true; + return 0; + } + else if (pid_error > PID_FUNCTIONAL_RANGE) { + pid_reset = true; + return MAX_POW; + } - if (pid_reset) { - pid_reset = false; - temp_iState = 0.0; - work_d = 0.0; - } + if (pid_reset) { + pid_reset = false; + temp_iState = 0.0; + work_d = 0.0; + } - const float max_power_over_i_gain = float(MAX_POW) / Ki - float(MIN_POW); - temp_iState = constrain(temp_iState + pid_error, 0, max_power_over_i_gain); + const float max_power_over_i_gain = float(MAX_POW) / Ki - float(MIN_POW); + temp_iState = constrain(temp_iState + pid_error, 0, max_power_over_i_gain); - work_p = Kp * pid_error; - work_i = Ki * temp_iState; - work_d = work_d + PID_K2 * (Kd * (temp_dState - current) - work_d); + work_p = Kp * pid_error; + work_i = Ki * temp_iState; + work_d = work_d + PID_K2 * (Kd * (temp_dState - current) - work_d); - temp_dState = current; + temp_dState = current; - return constrain(work_p + work_i + work_d + float(MIN_POW), 0, MAX_POW); - } + return constrain(work_p + work_i + work_d + float(MIN_POW), 0, MAX_POW); + } }; -#endif +#endif // HAS_PID_HEATING #if ENABLED(PIDTEMP) /// @brief Extrusion scaled PID class template struct PIDC_t : public PID_t { - private: - using base = PID_t; - float work_c = 0; - float prev_e_pos = 0; - int32_t lpq[LPQ_ARR_SZ] = {}; - int16_t lpq_ptr = 0; - public: - float Kc = 0; - float c() const { return Kc; } - void set_Kc(float c) { Kc = c; } - float cTerm() const { return work_c; } - void set(float p, float i, float d, float c=1, float f=0) { - base::set_Kp(p); - base::set_Ki(i); - base::set_Kd(d); - set_Kc(c); - base::set_Kf(f); - } - void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } - void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } - void reset() { - base::reset(); - prev_e_pos = 0; - lpq_ptr = 0; - LOOP_L_N(i, LPQ_ARR_SZ) lpq[i] = 0; - } + private: + using base = PID_t; + float work_c = 0; + float prev_e_pos = 0; + int32_t lpq[LPQ_ARR_SZ] = {}; + int16_t lpq_ptr = 0; + public: + float Kc = 0; + float c() const { return Kc; } + void set_Kc(float c) { Kc = c; } + float cTerm() const { return work_c; } + void set(float p, float i, float d, float c=1, float f=0) { + base::set_Kp(p); + base::set_Ki(i); + base::set_Kd(d); + set_Kc(c); + base::set_Kf(f); + } + void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } + void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } + void reset() { + base::reset(); + prev_e_pos = 0; + lpq_ptr = 0; + for (uint8_t i = 0; i < LPQ_ARR_SZ; ++i) lpq[i] = 0; + } - float get_extrusion_scale_output(const bool is_active, const int32_t e_position, const float e_mm_per_step, const int16_t lpq_len) { - work_c = 0; - if (!is_active) return work_c; + float get_extrusion_scale_output(const bool is_active, const int32_t e_position, const float e_mm_per_step, const int16_t lpq_len) { + work_c = 0; + if (!is_active) return work_c; - if (e_position > prev_e_pos) { - lpq[lpq_ptr] = e_position - prev_e_pos; - prev_e_pos = e_position; - } - else - lpq[lpq_ptr] = 0; + if (e_position > prev_e_pos) { + lpq[lpq_ptr] = e_position - prev_e_pos; + prev_e_pos = e_position; + } + else + lpq[lpq_ptr] = 0; - ++lpq_ptr; + ++lpq_ptr; - if (lpq_ptr >= LPQ_ARR_SZ || lpq_ptr >= lpq_len) - lpq_ptr = 0; + if (lpq_ptr >= LPQ_ARR_SZ || lpq_ptr >= lpq_len) + lpq_ptr = 0; - work_c = (lpq[lpq_ptr] * e_mm_per_step) * Kc; + work_c = (lpq[lpq_ptr] * e_mm_per_step) * Kc; - return work_c; - } + return work_c; + } }; /// @brief Fan scaled PID, this class implements the get_fan_scale_output() method @@ -290,71 +290,71 @@ typedef struct { float p, i, d, c, f; } raw_pidcf_t; /// @tparam SCALE_LIN_FACTOR parameter from Configuration_adv.h template struct PIDF_t : public PID_t { - private: - using base = PID_t; - float work_f = 0; - public: - float Kf = 0; - float f() const { return Kf; } - void set_Kf(float f) { Kf = f; } - float fTerm() const { return work_f; } - void set(float p, float i, float d, float c=1, float f=0) { - base::set_Kp(p); - base::set_Ki(i); - base::set_Kd(d); - base::set_Kc(c); - set_Kf(f); - } - void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } - void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } + private: + using base = PID_t; + float work_f = 0; + public: + float Kf = 0; + float f() const { return Kf; } + void set_Kf(float f) { Kf = f; } + float fTerm() const { return work_f; } + void set(float p, float i, float d, float c=1, float f=0) { + base::set_Kp(p); + base::set_Ki(i); + base::set_Kd(d); + base::set_Kc(c); + set_Kf(f); + } + void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } + void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } - float get_fan_scale_output(const uint8_t fan_speed) { - work_f = 0; - if (fan_speed > SCALE_MIN_SPEED) - work_f = Kf + (SCALE_LIN_FACTOR) * fan_speed; + float get_fan_scale_output(const uint8_t fan_speed) { + work_f = 0; + if (fan_speed > SCALE_MIN_SPEED) + work_f = Kf + (SCALE_LIN_FACTOR) * fan_speed; - return work_f; - } + return work_f; + } }; /// @brief Inherits PID and PIDC - can't use proper diamond inheritance w/o virtual template struct PIDCF_t : public PIDC_t { - private: - using base = PID_t; - using cPID = PIDC_t; - float work_f = 0; - public: - float Kf = 0; - float c() const { return cPID::c(); } - float f() const { return Kf; } - void set_Kc(float c) { cPID::set_Kc(c); } - void set_Kf(float f) { Kf = f; } - float cTerm() const { return cPID::cTerm(); } - float fTerm() const { return work_f; } - void set(float p, float i, float d, float c=1, float f=0) { - base::set_Kp(p); - base::set_Ki(i); - base::set_Kd(d); - cPID::set_Kc(c); - set_Kf(f); - } - void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } - void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } + private: + using base = PID_t; + using cPID = PIDC_t; + float work_f = 0; + public: + float Kf = 0; + float c() const { return cPID::c(); } + float f() const { return Kf; } + void set_Kc(float c) { cPID::set_Kc(c); } + void set_Kf(float f) { Kf = f; } + float cTerm() const { return cPID::cTerm(); } + float fTerm() const { return work_f; } + void set(float p, float i, float d, float c=1, float f=0) { + base::set_Kp(p); + base::set_Ki(i); + base::set_Kd(d); + cPID::set_Kc(c); + set_Kf(f); + } + void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } + void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } - void reset() { cPID::reset(); } + void reset() { cPID::reset(); } - float get_fan_scale_output(const uint8_t fan_speed) { - work_f = fan_speed > (SCALE_MIN_SPEED) ? Kf + (SCALE_LIN_FACTOR) * fan_speed : 0; - return work_f; - } - float get_extrusion_scale_output(const bool is_active, const int32_t e_position, const float e_mm_per_step, const int16_t lpq_len) { - return cPID::get_extrusion_scale_output(is_active, e_position, e_mm_per_step, lpq_len); - } + float get_fan_scale_output(const uint8_t fan_speed) { + work_f = fan_speed > (SCALE_MIN_SPEED) ? Kf + (SCALE_LIN_FACTOR) * fan_speed : 0; + return work_f; + } + float get_extrusion_scale_output(const bool is_active, const int32_t e_position, const float e_mm_per_step, const int16_t lpq_len) { + return cPID::get_extrusion_scale_output(is_active, e_position, e_mm_per_step, lpq_len); + } }; typedef - #if BOTH(PID_EXTRUSION_SCALING, PID_FAN_SCALING) + #if ALL(PID_EXTRUSION_SCALING, PID_FAN_SCALING) PIDCF_t<0, PID_MAX, LPQ_MAX_LEN, PID_FAN_SCALING_MIN_SPEED, PID_FAN_SCALING_LIN_FACTOR> #elif ENABLED(PID_EXTRUSION_SCALING) PIDC_t<0, PID_MAX, LPQ_MAX_LEN> @@ -388,22 +388,22 @@ typedef struct { float p, i, d, c, f; } raw_pidcf_t; #endif -#if ENABLED(G26_MESH_VALIDATION) && EITHER(HAS_MARLINUI_MENU, EXTENSIBLE_UI) +#if ENABLED(G26_MESH_VALIDATION) && ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI) #define G26_CLICK_CAN_CANCEL 1 #endif // A temperature sensor typedef struct TempInfo { -private: - raw_adc_t acc; - raw_adc_t raw; -public: - celsius_float_t celsius; - inline void reset() { acc = 0; } - inline void sample(const raw_adc_t s) { acc += s; } - inline void update() { raw = acc; } - void setraw(const raw_adc_t r) { raw = r; } - raw_adc_t getraw() const { return raw; } + private: + raw_adc_t acc; + raw_adc_t raw; + public: + celsius_float_t celsius; + inline void reset() { acc = 0; } + inline void sample(const raw_adc_t s) { acc += s; } + inline void update() { raw = acc; } + void setraw(const raw_adc_t r) { raw = r; } + raw_adc_t getraw() const { return raw; } } temp_info_t; #if HAS_TEMP_REDUNDANT @@ -429,7 +429,7 @@ struct PIDHeaterInfo : public HeaterInfo { #if ENABLED(MPCTEMP) struct MPCHeaterInfo : public HeaterInfo { - MPC_t constants; + MPC_t mpc; float modeled_ambient_temp, modeled_block_temp, modeled_sensor_temp; @@ -462,7 +462,7 @@ struct PIDHeaterInfo : public HeaterInfo { #if HAS_TEMP_PROBE typedef temp_info_t probe_info_t; #endif -#if EITHER(HAS_COOLER, HAS_TEMP_COOLER) +#if ANY(HAS_COOLER, HAS_TEMP_COOLER) typedef heater_info_t cooler_info_t; #endif #if HAS_TEMP_BOARD @@ -599,7 +599,7 @@ class Temperature { static redundant_info_t temp_redundant; #endif - #if EITHER(AUTO_POWER_E_FANS, HAS_FANCHECK) + #if ANY(AUTO_POWER_E_FANS, HAS_FANCHECK) static uint8_t autofan_speed[HOTENDS]; #endif #if ENABLED(AUTO_POWER_CHAMBER_FAN) @@ -614,11 +614,7 @@ 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 BOTH(HAS_MARLINUI_MENU, PREVENT_COLD_EXTRUSION) && E_MANUAL > 0 + #if ALL(HAS_MARLINUI_MENU, PREVENT_COLD_EXTRUSION) && E_MANUAL > 0 static bool allow_cold_extrude_override; static void set_menu_cold_override(const bool allow) { allow_cold_extrude_override = allow; } #else @@ -633,6 +629,8 @@ class Temperature { 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 constexpr bool allow_cold_extrude = true; + static constexpr celsius_t extrude_min_temp = 0; static bool tooColdToExtrude(const uint8_t) { return false; } static bool targetTooColdToExtrude(const uint8_t) { return false; } #endif @@ -640,7 +638,7 @@ class Temperature { static bool hotEnoughToExtrude(const uint8_t e) { return !tooColdToExtrude(e); } static bool targetHotEnoughToExtrude(const uint8_t e) { return !targetTooColdToExtrude(e); } - #if EITHER(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) + #if ANY(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) static celsius_t singlenozzle_temp[EXTRUDERS]; #endif @@ -677,7 +675,7 @@ class Temperature { // Convert the given heater_id_t to idle array index static IdleIndex idle_index_for_id(const int8_t heater_id) { - TERN_(HAS_HEATED_BED, if (heater_id == H_BED) return IDLE_INDEX_BED); + OPTCODE(HAS_HEATED_BED, if (heater_id == H_BED) return IDLE_INDEX_BED) return (IdleIndex)_MAX(heater_id, 0); } @@ -740,7 +738,7 @@ class Temperature { static raw_adc_t mintemp_raw_COOLER, maxtemp_raw_COOLER; #endif - #if HAS_TEMP_BOARD && ENABLED(THERMAL_PROTECTION_BOARD) + #if ALL(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) static raw_adc_t mintemp_raw_BOARD, maxtemp_raw_BOARD; #endif @@ -847,7 +845,7 @@ class Temperature { #if HAS_FAN static uint8_t fan_speed[FAN_COUNT]; - #define FANS_LOOP(I) LOOP_L_N(I, FAN_COUNT) + #define FANS_LOOP(I) for (uint8_t I = 0; I < FAN_COUNT; ++I) static void set_fan_speed(const uint8_t fan, const uint16_t speed); @@ -855,7 +853,7 @@ class Temperature { static void report_fan_speed(const uint8_t fan); #endif - #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) + #if ANY(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) static bool fans_paused; static uint8_t saved_fan_speed[FAN_COUNT]; #endif @@ -883,7 +881,7 @@ class Temperature { static void set_temp_fan_speed(const uint8_t fan, const uint16_t command_or_speed); #endif - #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) + #if ANY(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) void set_fans_paused(const bool p); #endif @@ -1013,7 +1011,7 @@ class Temperature { } // Start watching the Bed to make sure it's really heating up - static void start_watching_bed() { TERN_(WATCH_BED, watch_bed.restart(degBed(), degTargetBed())); } + static void start_watching_bed() { OPTCODE(WATCH_BED, watch_bed.restart(degBed(), degTargetBed())) } static void setTargetBed(const celsius_t celsius) { TERN_(AUTO_POWER_CONTROL, if (celsius) powerManager.power_on()); @@ -1063,7 +1061,7 @@ class Temperature { start_watching_chamber(); } // Start watching the Chamber to make sure it's really heating up - static void start_watching_chamber() { TERN_(WATCH_CHAMBER, watch_chamber.restart(degChamber(), degTargetChamber())); } + static void start_watching_chamber() { OPTCODE(WATCH_CHAMBER, watch_chamber.restart(degChamber(), degTargetChamber())) } #endif #if HAS_TEMP_COOLER @@ -1105,7 +1103,7 @@ class Temperature { start_watching_cooler(); } // Start watching the Cooler to make sure it's really cooling down - static void start_watching_cooler() { TERN_(WATCH_COOLER, watch_cooler.restart(degCooler(), degTargetCooler())); } + static void start_watching_cooler() { OPTCODE(WATCH_COOLER, watch_cooler.restart(degCooler(), degTargetCooler())) } #endif /** @@ -1134,6 +1132,12 @@ class Temperature { static void auto_job_check_timer(const bool can_start, const bool can_stop); #endif + #if ENABLED(NO_FAN_SLOWING_IN_PID_TUNING) + static bool adaptive_fan_slowing; + #elif ENABLED(ADAPTIVE_FAN_SLOWING) + static constexpr bool adaptive_fan_slowing = true; + #endif + /** * Perform auto-tuning for hotend or bed in response to M303 */ @@ -1145,12 +1149,6 @@ class Temperature { static void PID_autotune(const celsius_t target, const heater_id_t heater_id, const int8_t ncycles, const bool set_result=false); - #if ENABLED(NO_FAN_SLOWING_IN_PID_TUNING) - static bool adaptive_fan_slowing; - #elif ENABLED(ADAPTIVE_FAN_SLOWING) - static constexpr bool adaptive_fan_slowing = true; - #endif - // Update the temp manager when PID values change #if ENABLED(PIDTEMP) static void updatePID() { HOTEND_LOOP() temp_hotend[e].pid.reset(); } @@ -1164,7 +1162,7 @@ class Temperature { } #endif - #endif + #endif // HAS_PID_HEATING #if ENABLED(MPCTEMP) void MPC_autotune(); @@ -1225,15 +1223,16 @@ class Temperature { // MAX Thermocouples #if HAS_MAX_TC - #define MAX_TC_COUNT TEMP_SENSOR_IS_MAX_TC(0) + TEMP_SENSOR_IS_MAX_TC(1) + TEMP_SENSOR_IS_MAX_TC(REDUNDANT) + #define MAX_TC_COUNT TEMP_SENSOR_IS_MAX_TC(0) + TEMP_SENSOR_IS_MAX_TC(1) + TEMP_SENSOR_IS_MAX_TC(2) + TEMP_SENSOR_IS_MAX_TC(REDUNDANT) #if MAX_TC_COUNT > 1 #define HAS_MULTI_MAX_TC 1 - #define READ_MAX_TC(N) read_max_tc(N) - #else - #define READ_MAX_TC(N) read_max_tc() #endif + #define READ_MAX_TC(N) read_max_tc(TERN_(HAS_MULTI_MAX_TC, N)) static raw_adc_t read_max_tc(TERN_(HAS_MULTI_MAX_TC, const uint8_t hindex=0)); #endif + #if TEMP_SENSOR_IS_MAX_TC(BED) + static raw_adc_t read_max_tc_bed(); + #endif #if HAS_AUTO_FAN #if ENABLED(POWER_OFF_WAIT_FOR_COOLDOWN) @@ -1276,9 +1275,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_(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); + OPTCODE(THERMAL_PROTECTION_CHAMBER, if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER) + OPTCODE(THERMAL_PROTECTION_COOLER, if (heater_id == H_COOLER) return RUNAWAY_IND_COOLER) + OPTCODE(THERMAL_PROTECTION_BED, if (heater_id == H_BED) return RUNAWAY_IND_BED) return (RunawayIndex)_MAX(heater_id, 0); } diff --git a/Marlin/src/module/thermistor/thermistor_1.h b/Marlin/src/module/thermistor/thermistor_1.h index 2ebf8da550a0..e581f1b5cd4b 100644 --- a/Marlin/src/module/thermistor/thermistor_1.h +++ b/Marlin/src/module/thermistor/thermistor_1.h @@ -23,6 +23,10 @@ // R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor constexpr temp_entry_t temptable_1[] PROGMEM = { + { OV( 18), 320 }, + { OV( 19), 315 }, + { OV( 20), 310 }, + { OV( 22), 305 }, { OV( 23), 300 }, { OV( 25), 295 }, { OV( 27), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_14.h b/Marlin/src/module/thermistor/thermistor_14.h new file mode 100644 index 000000000000..0d432f3d65ce --- /dev/null +++ b/Marlin/src/module/thermistor/thermistor_14.h @@ -0,0 +1,85 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +// R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor +constexpr temp_entry_t temptable_14[] PROGMEM = { + { OV( 23), 275 }, + { OV( 25), 270 }, + { OV( 27), 265 }, + { OV( 28), 260 }, + { OV( 31), 255 }, + { OV( 33), 250 }, + { OV( 35), 245 }, + { OV( 38), 240 }, + { OV( 41), 235 }, + { OV( 44), 230 }, + { OV( 47), 225 }, + { OV( 52), 220 }, + { OV( 56), 215 }, + { OV( 62), 210 }, + { OV( 68), 205 }, + { OV( 74), 200 }, + { OV( 81), 195 }, + { OV( 90), 190 }, + { OV( 99), 185 }, + { OV( 108), 180 }, + { OV( 121), 175 }, + { OV( 133), 170 }, + { OV( 147), 165 }, + { OV( 162), 160 }, + { OV( 180), 155 }, + { OV( 199), 150 }, + { OV( 219), 145 }, + { OV( 243), 140 }, + { OV( 268), 135 }, + { OV( 296), 130 }, + { OV( 326), 125 }, + { OV( 358), 120 }, + { OV( 398), 115 }, + { OV( 435), 110 }, + { OV( 476), 105 }, + { OV( 519), 100 }, + { OV( 566), 95 }, + { OV( 610), 90 }, + { OV( 658), 85 }, + { OV( 703), 80 }, + { OV( 742), 75 }, + { OV( 773), 70 }, + { OV( 807), 65 }, + { OV( 841), 60 }, + { OV( 871), 55 }, + { OV( 895), 50 }, + { OV( 918), 45 }, + { OV( 937), 40 }, + { OV( 954), 35 }, + { OV( 968), 30 }, + { OV( 978), 25 }, + { OV( 985), 20 }, + { OV( 993), 15 }, + { OV( 999), 10 }, + { OV(1004), 5 }, + { OV(1008), 0 }, + { OV(1012), -5 }, + { OV(1016), -10 }, + { OV(1020), -15 } +}; diff --git a/Marlin/src/module/thermistor/thermistor_666.h b/Marlin/src/module/thermistor/thermistor_666.h index bba3e606fc06..14a03c23b5ba 100644 --- a/Marlin/src/module/thermistor/thermistor_666.h +++ b/Marlin/src/module/thermistor/thermistor_666.h @@ -27,7 +27,7 @@ */ //#include "output_table.h" -/* +/** * Parameters: * A: -0.000480634 * B: 0.00031362 diff --git a/Marlin/src/module/thermistor/thermistor_68.h b/Marlin/src/module/thermistor/thermistor_68.h index 270456dcb59c..f8b0f625e72b 100644 --- a/Marlin/src/module/thermistor/thermistor_68.h +++ b/Marlin/src/module/thermistor/thermistor_68.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_68 1 // PT100 amplifier board from Dyze Design -const temp_entry_t temptable_68[] PROGMEM = { +constexpr temp_entry_t temptable_68[] PROGMEM = { { OV(273), 0 }, { OV(294), 20 }, { OV(315), 40 }, diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index c596d746f7fd..d5625799d3bc 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -52,163 +52,190 @@ typedef struct { raw_adc_t value; celsius_t celsius; } temp_entry_t; #define PtAdVal(T,R0,Rup) (short)(1024 / (Rup / PtRt(T, R0) + 1)) #define PtLine(T,R0,Rup) { OV(PtAdVal(T, R0, Rup)), T } -#if ANY_THERMISTOR_IS(1) // beta25 = 4092 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "EPCOS" +// +// Analog Thermistors - 4.7kΩ pullup - Normal +// + +#if ANY_THERMISTOR_IS(1) // beta25 = 4092 K, R25 = 100kΩ, Pullup = 4.7kΩ, "EPCOS" #include "thermistor_1.h" #endif -#if ANY_THERMISTOR_IS(2) // 4338 K, R25 = 200 kOhm, Pull-up = 4.7 kOhm, "ATC Semitec 204GT-2" +#if ANY_THERMISTOR_IS(331) // Like table 1, but with 3V3 as input voltage for MEGA + #include "thermistor_331.h" +#endif +#if ANY_THERMISTOR_IS(332) // Like table 1, but with 3V3 as input voltage for DUE + #include "thermistor_332.h" +#endif +#if ANY_THERMISTOR_IS(2) // 4338 K, R25 = 200kΩ, Pullup = 4.7kΩ, "ATC Semitec 204GT-2" #include "thermistor_2.h" #endif -#if ANY_THERMISTOR_IS(3) // beta25 = 4120 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Mendel-parts" +#if ANY_THERMISTOR_IS(202) // 200K thermistor in Copymaker3D hotend + #include "thermistor_202.h" +#endif +#if ANY_THERMISTOR_IS(3) // beta25 = 4120 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Mendel-parts" #include "thermistor_3.h" #endif -#if ANY_THERMISTOR_IS(4) // beta25 = 3950 K, R25 = 10 kOhm, Pull-up = 4.7 kOhm, "Generic" +#if ANY_THERMISTOR_IS(4) // beta25 = 3950 K, R25 = 10kΩ, Pullup = 4.7kΩ, "Generic" #include "thermistor_4.h" #endif -#if ANY_THERMISTOR_IS(5) // beta25 = 4267 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "ParCan, ATC 104GT-2" +#if ANY_THERMISTOR_IS(5) // beta25 = 4267 K, R25 = 100kΩ, Pullup = 4.7kΩ, "ParCan, ATC 104GT-2" #include "thermistor_5.h" #endif -#if ANY_THERMISTOR_IS(501) // 100K Zonestar thermistor +#if ANY_THERMISTOR_IS(501) // 100K Zonestar thermistor #include "thermistor_501.h" #endif -#if ANY_THERMISTOR_IS(502) // Unknown thermistor used by the Zonestar Průša P802M hot bed +#if ANY_THERMISTOR_IS(502) // Unknown thermistor used by the Zonestar Průša P802M hot bed #include "thermistor_502.h" #endif -#if ANY_THERMISTOR_IS(503) // Zonestar (Z8XM2) Heated Bed thermistor +#if ANY_THERMISTOR_IS(503) // Zonestar (Z8XM2) Heated Bed thermistor #include "thermistor_503.h" #endif -#if ANY_THERMISTOR_IS(504) // Zonestar (P802QR2 Hot End) thermistors +#if ANY_THERMISTOR_IS(504) // Zonestar (P802QR2 Hot End) thermistors #include "thermistor_504.h" #endif -#if ANY_THERMISTOR_IS(505) // Zonestar (P802QR2 Bed) thermistor +#if ANY_THERMISTOR_IS(505) // Zonestar (P802QR2 Bed) thermistor #include "thermistor_505.h" #endif -#if ANY_THERMISTOR_IS(512) // 100k thermistor in RPW-Ultra hotend, Pull-up = 4.7 kOhm, "unknown model" +#if ANY_THERMISTOR_IS(512) // 100k thermistor in RPW-Ultra hotend, Pullup = 4.7kΩ, "unknown model" #include "thermistor_512.h" #endif -#if ANY_THERMISTOR_IS(6) // beta25 = 4092 K, R25 = 100 kOhm, Pull-up = 8.2 kOhm, "EPCOS ?" +#if ANY_THERMISTOR_IS(6) // beta25 = 4092 K, R25 = 100kΩ, Pullup = 8.2kΩ, "EPCOS ?" #include "thermistor_6.h" #endif -#if ANY_THERMISTOR_IS(7) // beta25 = 3974 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Honeywell 135-104LAG-J01" +#if ANY_THERMISTOR_IS(7) // beta25 = 3974 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Honeywell 135-104LAG-J01" #include "thermistor_7.h" #endif -#if ANY_THERMISTOR_IS(71) // beta25 = 3974 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Honeywell 135-104LAF-J01" +#if ANY_THERMISTOR_IS(71) // beta25 = 3974 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Honeywell 135-104LAF-J01" #include "thermistor_71.h" #endif -#if ANY_THERMISTOR_IS(8) // beta25 = 3950 K, R25 = 100 kOhm, Pull-up = 10 kOhm, "Vishay E3104FHT" +#if ANY_THERMISTOR_IS(8) // beta25 = 3950 K, R25 = 100kΩ, Pullup = 10kΩ, "Vishay E3104FHT" #include "thermistor_8.h" #endif -#if ANY_THERMISTOR_IS(9) // beta25 = 3960 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "GE Sensing AL03006-58.2K-97-G1" +#if ANY_THERMISTOR_IS(9) // beta25 = 3960 K, R25 = 100kΩ, Pullup = 4.7kΩ, "GE Sensing AL03006-58.2K-97-G1" #include "thermistor_9.h" #endif -#if ANY_THERMISTOR_IS(10) // beta25 = 3960 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "RS 198-961" +#if ANY_THERMISTOR_IS(10) // beta25 = 3960 K, R25 = 100kΩ, Pullup = 4.7kΩ, "RS 198-961" #include "thermistor_10.h" #endif -#if ANY_THERMISTOR_IS(11) // beta25 = 3950 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "QU-BD silicone bed, QWG-104F-3950" +#if ANY_THERMISTOR_IS(11) // beta25 = 3950 K, R25 = 100kΩ, Pullup = 4.7kΩ, "QU-BD silicone bed, QWG-104F-3950" #include "thermistor_11.h" #endif -#if ANY_THERMISTOR_IS(13) // beta25 = 4100 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Hisens" +#if ANY_THERMISTOR_IS(12) // beta25 = 4700 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Personal calibration for Makibox hot bed" + #include "thermistor_12.h" +#endif +#if ANY_THERMISTOR_IS(13) // beta25 = 4100 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Hisens" #include "thermistor_13.h" #endif -#if ANY_THERMISTOR_IS(15) // JGAurora A5 thermistor calibration +#if ANY_THERMISTOR_IS(14) // beta25 = 4092 K, R25 = 100kΩ, Pullup = 4.7kΩ, "EPCOS" for hot bed + #include "thermistor_14.h" +#endif +#if ANY_THERMISTOR_IS(15) // JGAurora A5 thermistor calibration #include "thermistor_15.h" #endif -#if ANY_THERMISTOR_IS(17) // Dagoma NTC 100k white thermistor +#if ANY_THERMISTOR_IS(17) // Dagoma NTC 100k white thermistor #include "thermistor_17.h" #endif -#if ANY_THERMISTOR_IS(18) // ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327 +#if ANY_THERMISTOR_IS(18) // ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327 #include "thermistor_18.h" #endif -#if ANY_THERMISTOR_IS(20) // Pt100 with INA826 amp on Ultimaker v2.0 electronics - #include "thermistor_20.h" -#endif -#if ANY_THERMISTOR_IS(21) // Pt100 with INA826 amp with 3.3v excitation based on "Pt100 with INA826 amp on Ultimaker v2.0 electronics" - #include "thermistor_21.h" -#endif -#if ANY_THERMISTOR_IS(22) // Thermistor in a Rostock 301 hot end, calibrated with a multimeter +#if ANY_THERMISTOR_IS(22) // Thermistor in a Rostock 301 hot end, calibrated with a multimeter #include "thermistor_22.h" #endif -#if ANY_THERMISTOR_IS(23) // By AluOne #12622. Formerly 22 above. May need calibration/checking. +#if ANY_THERMISTOR_IS(23) // By AluOne #12622. Formerly 22 above. May need calibration/checking. #include "thermistor_23.h" #endif -#if ANY_THERMISTOR_IS(30) // Kis3d Silicone mat 24V 200W/300W with 6mm Precision cast plate (EN AW 5083) +#if ANY_THERMISTOR_IS(30) // Kis3d Silicone mat 24V 200W/300W with 6mm Precision cast plate (EN AW 5083) #include "thermistor_30.h" #endif -#if ANY_THERMISTOR_IS(51) // beta25 = 4092 K, R25 = 100 kOhm, Pull-up = 1 kOhm, "EPCOS" - #include "thermistor_51.h" -#endif -#if ANY_THERMISTOR_IS(52) // beta25 = 4338 K, R25 = 200 kOhm, Pull-up = 1 kOhm, "ATC Semitec 204GT-2" - #include "thermistor_52.h" -#endif -#if ANY_THERMISTOR_IS(55) // beta25 = 4267 K, R25 = 100 kOhm, Pull-up = 1 kOhm, "ATC Semitec 104GT-2 (Used on ParCan)" - #include "thermistor_55.h" -#endif -#if ANY_THERMISTOR_IS(60) // beta25 = 3950 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Maker's Tool Works Kapton Bed" +#if ANY_THERMISTOR_IS(60) // beta25 = 3950 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Maker's Tool Works Kapton Bed" #include "thermistor_60.h" #endif -#if ANY_THERMISTOR_IS(61) // beta25 = 3950 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Formbot 350°C Thermistor" +#if ANY_THERMISTOR_IS(61) // beta25 = 3950 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Formbot 350°C Thermistor" #include "thermistor_61.h" #endif -#if ANY_THERMISTOR_IS(66) // beta25 = 4500 K, R25 = 2.5 MOhm, Pull-up = 4.7 kOhm, "DyzeDesign 500 °C Thermistor" +#if ANY_THERMISTOR_IS(66) // beta25 = 4500 K, R25 = 2.5MΩ, Pullup = 4.7kΩ, "DyzeDesign 500 °C Thermistor" #include "thermistor_66.h" #endif -#if ANY_THERMISTOR_IS(67) // R25 = 500 KOhm, beta25 = 3800 K, 4.7 kOhm pull-up, SliceEngineering 450 °C Thermistor +#if ANY_THERMISTOR_IS(67) // R25 = 500kΩ, beta25 = 3800 K, 4.7kΩ pull-up, SliceEngineering 450 °C Thermistor #include "thermistor_67.h" #endif -#if ANY_THERMISTOR_IS(68) // PT-100 with Dyze amplifier board +#if ANY_THERMISTOR_IS(68) // PT-100 with Dyze amplifier board #include "thermistor_68.h" #endif -#if ANY_THERMISTOR_IS(12) // beta25 = 4700 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Personal calibration for Makibox hot bed" - #include "thermistor_12.h" -#endif -#if ANY_THERMISTOR_IS(70) // beta25 = 4100 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Hephestos 2, bqh2 stock thermistor" +#if ANY_THERMISTOR_IS(70) // beta25 = 4100 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Hephestos 2, bqh2 stock thermistor" #include "thermistor_70.h" #endif -#if ANY_THERMISTOR_IS(75) // beta25 = 4100 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "MGB18-104F39050L32 thermistor" +#if ANY_THERMISTOR_IS(75) // beta25 = 4100 K, R25 = 100kΩ, Pullup = 4.7kΩ, "MGB18-104F39050L32 thermistor" #include "thermistor_75.h" #endif -#if ANY_THERMISTOR_IS(99) // 100k bed thermistor with a 10K pull-up resistor (on some Wanhao i3 models) - #include "thermistor_99.h" +#if ANY_THERMISTOR_IS(666) // beta25 = UNK, R25 = 200K, Pullup = 10kΩ, "Unidentified 200K NTC thermistor (Einstart S)" + #include "thermistor_666.h" #endif -#if ANY_THERMISTOR_IS(110) // Pt100 with 1k0 pullup - #include "thermistor_110.h" +#if ANY_THERMISTOR_IS(2000) // "Ultimachine Rambo TDK NTCG104LH104KT1 NTC100K motherboard Thermistor" https://product.tdk.com/en/search/sensor/ntc/chip-ntc-thermistor/info?part_no=NTCG104LH104KT1 + #include "thermistor_2000.h" #endif -#if ANY_THERMISTOR_IS(147) // Pt100 with 4k7 pullup - #include "thermistor_147.h" + +// +// Analog Thermistors - 1kΩ pullup +// + +#if ANY_THERMISTOR_IS(51) // beta25 = 4092 K, R25 = 100kΩ, Pullup = 1kΩ, "EPCOS" + #include "thermistor_51.h" #endif -#if ANY_THERMISTOR_IS(201) // Pt100 with LMV324 Overlord - #include "thermistor_201.h" +#if ANY_THERMISTOR_IS(52) // beta25 = 4338 K, R25 = 200kΩ, Pullup = 1kΩ, "ATC Semitec 204GT-2" + #include "thermistor_52.h" #endif -#if ANY_THERMISTOR_IS(202) // 200K thermistor in Copymaker3D hotend - #include "thermistor_202.h" +#if ANY_THERMISTOR_IS(55) // beta25 = 4267 K, R25 = 100kΩ, Pullup = 1kΩ, "ATC Semitec 104GT-2 (Used on ParCan)" + #include "thermistor_55.h" #endif -#if ANY_THERMISTOR_IS(331) // Like table 1, but with 3V3 as input voltage for MEGA - #include "thermistor_331.h" + +// +// Analog Thermistors - 10kΩ pullup - Atypical +// + +#if ANY_THERMISTOR_IS(99) // 100k bed thermistor with a 10K pull-up resistor (on some Wanhao i3 models) + #include "thermistor_99.h" #endif -#if ANY_THERMISTOR_IS(332) // Like table 1, but with 3V3 as input voltage for DUE - #include "thermistor_332.h" + +// +// Analog RTDs (Pt100/Pt1000) +// + +#if ANY_THERMISTOR_IS(110) // Pt100 with 1k0 pullup + #include "thermistor_110.h" #endif -#if ANY_THERMISTOR_IS(666) // beta25 = UNK, R25 = 200K, Pull-up = 10 kOhm, "Unidentified 200K NTC thermistor (Einstart S)" - #include "thermistor_666.h" +#if ANY_THERMISTOR_IS(147) // Pt100 with 4k7 pullup + #include "thermistor_147.h" #endif -#if ANY_THERMISTOR_IS(1010) // Pt1000 with 1k0 pullup +#if ANY_THERMISTOR_IS(1010) // Pt1000 with 1k0 pullup #include "thermistor_1010.h" #endif -#if ANY_THERMISTOR_IS(1022) // Pt1000 with 2k2 pullup +#if ANY_THERMISTOR_IS(1022) // Pt1000 with 2k2 pullup #include "thermistor_1022.h" #endif -#if ANY_THERMISTOR_IS(1047) // Pt1000 with 4k7 pullup +#if ANY_THERMISTOR_IS(1047) // Pt1000 with 4k7 pullup #include "thermistor_1047.h" #endif -#if ANY_THERMISTOR_IS(2000) // "Ultimachine Rambo TDK NTCG104LH104KT1 NTC100K motherboard Thermistor" https://product.tdk.com/en/search/sensor/ntc/chip-ntc-thermistor/info?part_no=NTCG104LH104KT1 - #include "thermistor_2000.h" +#if ANY_THERMISTOR_IS(20) // Pt100 with INA826 amp on Ultimaker v2.0 electronics + #include "thermistor_20.h" #endif -#if ANY_THERMISTOR_IS(998) // User-defined table 1 +#if ANY_THERMISTOR_IS(21) // Pt100 with INA826 amp with 3.3v excitation based on "Pt100 with INA826 amp on Ultimaker v2.0 electronics" + #include "thermistor_21.h" +#endif +#if ANY_THERMISTOR_IS(201) // Pt100 with LMV324 Overlord + #include "thermistor_201.h" +#endif + +// +// Custom/Dummy/Other Thermal Sensors +// + +#if ANY_THERMISTOR_IS(998) // User-defined table 1 #include "thermistor_998.h" #endif -#if ANY_THERMISTOR_IS(999) // User-defined table 2 +#if ANY_THERMISTOR_IS(999) // User-defined table 2 #include "thermistor_999.h" #endif -#if ANY_THERMISTOR_IS(1000) // Custom +#if ANY_THERMISTOR_IS(1000) // Custom constexpr temp_entry_t temptable_1000[] PROGMEM = { { 0, 0 } }; #endif diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 5c831c74124d..5289eb06eaf3 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -24,19 +24,16 @@ #include "tool_change.h" -#include "probe.h" #include "motion.h" #include "planner.h" #include "temperature.h" #include "../MarlinCore.h" +#include "../gcode/gcode.h" //#define DEBUG_TOOL_CHANGE //#define DEBUG_TOOLCHANGE_FILAMENT_SWAP -#define DEBUG_OUT ENABLED(DEBUG_TOOL_CHANGE) -#include "../core/debug_out.h" - #if HAS_MULTI_EXTRUDER toolchange_settings_t toolchange_settings; // Initialized by settings.load() #endif @@ -49,12 +46,6 @@ Flags toolchange_extruder_ready; #endif -#if EITHER(MAGNETIC_PARKING_EXTRUDER, TOOL_SENSOR) \ - || defined(EVENT_GCODE_TOOLCHANGE_T0) || defined(EVENT_GCODE_TOOLCHANGE_T1) || defined(EVENT_GCODE_AFTER_TOOLCHANGE) \ - || (ENABLED(PARKING_EXTRUDER) && PARKING_EXTRUDER_SOLENOIDS_DELAY > 0) - #include "../gcode/gcode.h" -#endif - #if ENABLED(TOOL_SENSOR) #include "../lcd/marlinui.h" #endif @@ -97,8 +88,11 @@ #include "../feature/pause.h" #endif +#if HAS_BED_PROBE + #include "probe.h" +#endif + #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - #include "../gcode/gcode.h" #if TOOLCHANGE_FS_WIPE_RETRACT <= 0 #undef TOOLCHANGE_FS_WIPE_RETRACT #define TOOLCHANGE_FS_WIPE_RETRACT 0 @@ -130,9 +124,8 @@ inline void _move_nozzle_servo(const uint8_t e, const uint8_t angle_index) { constexpr int8_t sns_index[2] = { SWITCHING_NOZZLE_SERVO_NR, SWITCHING_NOZZLE_E1_SERVO_NR }; - constexpr int16_t sns_angles[2] = SWITCHING_NOZZLE_SERVO_ANGLES; planner.synchronize(); - servo[sns_index[e]].move(sns_angles[angle_index]); + servo[sns_index[e]].move(servo_angles[sns_index[e]][angle_index]); safe_delay(SWITCHING_NOZZLE_SERVO_DWELL); } @@ -158,6 +151,9 @@ void _line_to_current(const AxisEnum fr_axis, const float fscale=1) { void slow_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0.2f); } void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0.5f); } +#define DEBUG_OUT ENABLED(DEBUG_TOOL_CHANGE) +#include "../core/debug_out.h" + #if ENABLED(MAGNETIC_PARKING_EXTRUDER) float parkingposx[2], // M951 R L @@ -256,7 +252,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. #elif ENABLED(PARKING_EXTRUDER) void pe_solenoid_init() { - LOOP_LE_N(n, 1) pe_solenoid_set_pin_state(n, !PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE); + for (uint8_t n = 0; n <= 1; ++n) pe_solenoid_set_pin_state(n, !PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE); } void pe_solenoid_set_pin_state(const uint8_t extruder_num, const uint8_t state) { @@ -441,7 +437,6 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. } } - #endif // TOOL_SENSOR #if ENABLED(SWITCHING_TOOLHEAD) @@ -887,7 +882,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. } // Ensure X axis DIR pertains to the correct carriage - stepper.set_directions(); + stepper.apply_directions(); DEBUG_ECHOLNPGM("Active extruder parked: ", active_extruder_parked ? "yes" : "no"); DEBUG_POS("New extruder (parked)", current_position); @@ -900,11 +895,8 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. */ #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) - #ifdef DEBUG_TOOLCHANGE_FILAMENT_SWAP - #define FS_DEBUG(V...) SERIAL_ECHOLNPGM("DEBUG: " V) - #else - #define FS_DEBUG(...) NOOP - #endif + #define DEBUG_OUT ENABLED(DEBUG_TOOLCHANGE_FILAMENT_SWAP) + #include "../core/debug_out.h" // Define any variables required static Flags extruder_was_primed; // Extruders primed status @@ -929,7 +921,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. * Returns FALSE if able to move. */ bool too_cold(uint8_t toolID){ - if (TERN0(PREVENT_COLD_EXTRUSION, !DEBUGGING(DRYRUN) && thermalManager.targetTooColdToExtrude(toolID))) { + if (!DEBUGGING(DRYRUN) && thermalManager.targetTooColdToExtrude(toolID)) { SERIAL_ECHO_MSG(STR_ERR_HOTEND_TOO_COLD); return true; } @@ -945,32 +937,33 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. * sync_plan_position_e(); */ void extruder_cutting_recover(const_float_t e) { - if (!too_cold(active_extruder)) { - const float dist = toolchange_settings.extra_resume + toolchange_settings.wipe_retract; - FS_DEBUG("Performing Cutting Recover | Distance: ", dist, " | Speed: ", MMM_TO_MMS(toolchange_settings.unretract_speed), "mm/s"); - unscaled_e_move(dist, MMM_TO_MMS(toolchange_settings.unretract_speed)); - planner.synchronize(); - FS_DEBUG("Set position to: ", e); - current_position.e = e; - sync_plan_position_e(); // Resume new E Position - } + if (too_cold(active_extruder)) return; + const float dist = toolchange_settings.extra_resume + toolchange_settings.wipe_retract; + DEBUG_ECHOLNPGM("Performing Cutting Recover | Distance: ", dist, " | Speed: ", MMM_TO_MMS(toolchange_settings.unretract_speed), "mm/s"); + unscaled_e_move(dist, MMM_TO_MMS(toolchange_settings.unretract_speed)); + + DEBUG_ECHOLNPGM("Set E position: ", e); + current_position.e = e; + sync_plan_position_e(); // Resume new E Position } /** * Prime the currently selected extruder (Filament loading only) + * Leave the E position unchanged so subsequent extrusion works properly. * * If too_cold(toolID) returns TRUE -> returns without moving extruder. * Extruders filament = swap_length + extra prime, then performs cutting retraction if enabled. * If cooling fan is enabled, calls filament_swap_cooling(); */ void extruder_prime() { - if (too_cold(active_extruder)) { - FS_DEBUG("Priming Aborted - Nozzle Too Cold!"); + DEBUG_ECHOLNPGM("Priming Aborted - Nozzle Too Cold!"); return; // Extruder too cold to prime } - float fr = toolchange_settings.unretract_speed; // Set default speed for unretract + feedRate_t fr_mm_s = MMM_TO_MMS(toolchange_settings.unretract_speed); // Set default speed for unretract + + const float resume_current_e = current_position.e; #if ENABLED(TOOLCHANGE_FS_SLOW_FIRST_PRIME) /** @@ -980,21 +973,22 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. if (!extruder_did_first_prime[active_extruder]) { extruder_did_first_prime.set(active_extruder); // Log first prime complete // new nozzle - prime at user-specified speed. - FS_DEBUG("First time priming T", active_extruder, ", reducing speed from ", MMM_TO_MMS(fr), " to ", MMM_TO_MMS(toolchange_settings.prime_speed), "mm/s"); - fr = toolchange_settings.prime_speed; - unscaled_e_move(0, MMM_TO_MMS(fr)); // Init planner with 0 length move + const feedRate_t prime_mm_s = MMM_TO_MMS(toolchange_settings.prime_speed); + DEBUG_ECHOLNPGM("First time priming T", active_extruder, ", reducing speed from ", fr_mm_s, " to ", prime_mm_s, "mm/s"); + fr_mm_s = prime_mm_s; + unscaled_e_move(0, fr_mm_s); // Init planner with 0 length move } #endif - //Calculate and perform the priming distance + // Calculate and perform the priming distance if (toolchange_settings.extra_prime >= 0) { // Positive extra_prime value - // - Return filament at speed (fr) then extra_prime at prime speed - FS_DEBUG("Loading Filament for T", active_extruder, " | Distance: ", toolchange_settings.swap_length, " | Speed: ", MMM_TO_MMS(fr), "mm/s"); - unscaled_e_move(toolchange_settings.swap_length, MMM_TO_MMS(fr)); // Prime (Unretract) filament by extruding equal to Swap Length (Unretract) + // - Return filament at speed (fr_mm_s) then extra_prime at prime speed + DEBUG_ECHOLNPGM("Loading Filament for T", active_extruder, " | Distance: ", toolchange_settings.swap_length, " | Speed: ", fr_mm_s, "mm/s"); + unscaled_e_move(toolchange_settings.swap_length, fr_mm_s); // Prime (Unretract) filament by extruding equal to Swap Length (Unretract) if (toolchange_settings.extra_prime > 0) { - FS_DEBUG("Performing Extra Priming for T", active_extruder, " | Distance: ", toolchange_settings.extra_prime, " | Speed: ", MMM_TO_MMS(toolchange_settings.prime_speed), "mm/s"); + DEBUG_ECHOLNPGM("Performing Extra Priming for T", active_extruder, " | Distance: ", toolchange_settings.extra_prime, " | Speed: ", MMM_TO_MMS(toolchange_settings.prime_speed), "mm/s"); unscaled_e_move(toolchange_settings.extra_prime, MMM_TO_MMS(toolchange_settings.prime_speed)); // Extra Prime Distance } } @@ -1002,22 +996,25 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. // Negative extra_prime value // - Unretract distance (swap length) is reduced by the value of extra_prime const float eswap = toolchange_settings.swap_length + toolchange_settings.extra_prime; - FS_DEBUG("Negative ExtraPrime value - Swap Return Length has been reduced from ", toolchange_settings.swap_length, " to ", eswap); - FS_DEBUG("Loading Filament for T", active_extruder, " | Distance: ", eswap, " | Speed: ", MMM_TO_MMS(fr), "mm/s"); - unscaled_e_move(eswap, MMM_TO_MMS(fr)); + DEBUG_ECHOLNPGM("Negative ExtraPrime value - Swap Return Length has been reduced from ", toolchange_settings.swap_length, " to ", eswap); + DEBUG_ECHOLNPGM("Loading Filament for T", active_extruder, " | Distance: ", eswap, " | Speed: ", fr_mm_s, "mm/s"); + unscaled_e_move(eswap, fr_mm_s); } extruder_was_primed.set(active_extruder); // Log that this extruder has been primed // Cutting retraction #if TOOLCHANGE_FS_WIPE_RETRACT - FS_DEBUG("Performing Cutting Retraction | Distance: ", -toolchange_settings.wipe_retract, " | Speed: ", MMM_TO_MMS(toolchange_settings.retract_speed), "mm/s"); + DEBUG_ECHOLNPGM("Performing Cutting Retraction | Distance: ", -toolchange_settings.wipe_retract, " | Speed: ", MMM_TO_MMS(toolchange_settings.retract_speed), "mm/s"); unscaled_e_move(-toolchange_settings.wipe_retract, MMM_TO_MMS(toolchange_settings.retract_speed)); #endif + // Leave E unchanged when priming + current_position.e = resume_current_e; + sync_plan_position_e(); + // Cool down with fan filament_swap_cooling(); - } /** @@ -1026,12 +1023,12 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. */ void tool_change_prime() { - FS_DEBUG(">>> tool_change_prime()"); + DEBUG_SECTION(tcp, "tool_change_prime", true); if (!too_cold(active_extruder)) { destination = current_position; // Remember the old position - const bool ok = TERN1(TOOLCHANGE_PARK, all_axes_homed() && toolchange_settings.enable_park); + const bool ok = TERN0(TOOLCHANGE_PARK, all_axes_homed() && toolchange_settings.enable_park); #if HAS_FAN && TOOLCHANGE_FS_FAN >= 0 // Store and stop fan. Restored on any exit. @@ -1067,25 +1064,37 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. } #endif + // Prime without changing E extruder_prime(); // Move back #if ENABLED(TOOLCHANGE_PARK) if (ok) { #if ENABLED(TOOLCHANGE_NO_RETURN) - const float temp = destination.z; - destination = current_position; - destination.z = temp; + destination.x = current_position.x; + destination.y = current_position.y; #endif - prepare_internal_move_to_destination(TERN(TOOLCHANGE_NO_RETURN, planner.settings.max_feedrate_mm_s[Z_AXIS], MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE))); + do_blocking_move_to_xy(destination, MMM_TO_MMS(TOOLCHANGE_PARK_XY_FEEDRATE)); + do_blocking_move_to_z(destination.z, planner.settings.max_feedrate_mm_s[Z_AXIS]); + planner.synchronize(); } #endif + // Clone previous position extruder_cutting_recover(destination.e); // Cutting recover - } - FS_DEBUG("<<< tool_change_prime"); + // Retract if previously retracted + #if ENABLED(FWRETRACT) + if (fwretract.retracted[active_extruder]) + unscaled_e_move(-fwretract.settings.retract_length, fwretract.settings.retract_feedrate_mm_s); + #endif + + // If resume_position is negative + if (current_position.e < 0) unscaled_e_move(current_position.e, MMM_TO_MMS(toolchange_settings.retract_speed)); + planner.synchronize(); + planner.set_e_position_mm(current_position.e); // Extruder primed and ready + } } #endif // TOOLCHANGE_FILAMENT_SWAP @@ -1173,7 +1182,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (new_tool != old_tool || TERN0(PARKING_EXTRUDER, extruder_parked)) { // PARKING_EXTRUDER may need to attach old_tool when homing destination = current_position; - #if BOTH(TOOLCHANGE_FILAMENT_SWAP, HAS_FAN) && TOOLCHANGE_FS_FAN >= 0 + #if ALL(TOOLCHANGE_FILAMENT_SWAP, HAS_FAN) && TOOLCHANGE_FS_FAN >= 0 // Store and stop fan. Restored on any exit. REMEMBER(fan, thermalManager.fan_speed[TOOLCHANGE_FS_FAN], 0); #endif @@ -1200,7 +1209,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { else if (extruder_was_primed[old_tool]) { // Retract the old extruder if it was previously primed // To-Do: Should SingleNozzle always retract? - FS_DEBUG("Retracting Filament for T", old_tool, ". | Distance: ", toolchange_settings.swap_length, " | Speed: ", MMM_TO_MMS(toolchange_settings.retract_speed), "mm/s"); + DEBUG_ECHOLNPGM("Retracting Filament for T", old_tool, ". | Distance: ", toolchange_settings.swap_length, " | Speed: ", MMM_TO_MMS(toolchange_settings.retract_speed), "mm/s"); unscaled_e_move(-toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.retract_speed)); } } @@ -1223,7 +1232,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif #endif - #if DISABLED(TOOLCHANGE_ZRAISE_BEFORE_RETRACT) && DISABLED(SWITCHING_NOZZLE) + #if NONE(TOOLCHANGE_ZRAISE_BEFORE_RETRACT, SWITCHING_NOZZLE) if (can_move_away && TERN1(TOOLCHANGE_PARK, toolchange_settings.enable_park)) { // Do a small lift to avoid the workpiece in the move back (below) current_position.z += toolchange_settings.z_raise; @@ -1311,7 +1320,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { const bool should_move = safe_to_move && !no_move && IsRunning(); if (should_move) { - #if EITHER(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) + #if ANY(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) thermalManager.singlenozzle_change(old_tool, new_tool); #endif @@ -1437,12 +1446,10 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { bool extruder_migration() { - #if ENABLED(PREVENT_COLD_EXTRUSION) - if (thermalManager.targetTooColdToExtrude(active_extruder)) { - DEBUG_ECHOLNPGM("Migration Source Too Cold"); - return false; - } - #endif + if (thermalManager.targetTooColdToExtrude(active_extruder)) { + DEBUG_ECHOLNPGM("Migration Source Too Cold"); + return false; + } // No auto-migration or specified target? if (!migration.target && active_extruder >= migration.last) { @@ -1507,6 +1514,9 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { unscaled_e_move(-fwretract.settings.retract_length, fwretract.settings.retract_feedrate_mm_s); #endif + // If resume_position is negative + if (resume_current_e < 0) unscaled_e_move(resume_current_e, MMM_TO_MMS(toolchange_settings.retract_speed)); + // If no available extruder if (EXTRUDERS < 2 || active_extruder >= EXTRUDERS - 2 || active_extruder == migration.last) migration.automode = false; @@ -1517,6 +1527,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { planner.synchronize(); planner.set_e_position_mm(current_position.e); // New extruder primed and ready + DEBUG_ECHOLNPGM("Migration Complete"); return true; } diff --git a/Marlin/src/module/tool_change.h b/Marlin/src/module/tool_change.h index ff456485e23d..3cb8b4a63784 100644 --- a/Marlin/src/module/tool_change.h +++ b/Marlin/src/module/tool_change.h @@ -34,8 +34,8 @@ float extra_resume; // M217 B int16_t prime_speed; // M217 P int16_t wipe_retract; // M217 G - int16_t retract_speed; // M217 R - int16_t unretract_speed; // M217 U + int16_t retract_speed; // M217 R (mm/min) + int16_t unretract_speed; // M217 U (mm/min) uint8_t fan_speed; // M217 F uint8_t fan_time; // M217 D #endif diff --git a/Marlin/src/pins/esp32/env_validate.h b/Marlin/src/pins/esp32/env_validate.h index ce14c33414ad..0bfd0ebd92be 100644 --- a/Marlin/src/pins/esp32/env_validate.h +++ b/Marlin/src/pins/esp32/env_validate.h @@ -19,8 +19,11 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if NOT_TARGET(ARDUINO_ARCH_ESP32) #error "Oops! Select an ESP32 board in 'Tools > Board.'" #endif + +#endif diff --git a/Marlin/src/pins/esp32/pins_E4D.h b/Marlin/src/pins/esp32/pins_E4D.h index d12b5276b7be..06e46e3c4c08 100644 --- a/Marlin/src/pins/esp32/pins_E4D.h +++ b/Marlin/src/pins/esp32/pins_E4D.h @@ -30,9 +30,7 @@ #include "env_validate.h" -#if EXTRUDERS > 1 || E_STEPPERS > 1 - #error "E4d@box only supports 1 E stepper." -#elif HAS_MULTI_HOTEND +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "E4d@box only supports 1 hotend / E stepper." #endif @@ -90,7 +88,7 @@ // Heaters / Fans // #define HEATER_0_PIN 2 -#define FAN_PIN 0 +#define FAN0_PIN 0 #define HEATER_BED_PIN 15 // diff --git a/Marlin/src/pins/esp32/pins_ENWI_ESPNP.h b/Marlin/src/pins/esp32/pins_ENWI_ESPNP.h index 80923d972deb..4f8b4b0fe48f 100644 --- a/Marlin/src/pins/esp32/pins_ENWI_ESPNP.h +++ b/Marlin/src/pins/esp32/pins_ENWI_ESPNP.h @@ -34,7 +34,9 @@ // // I2S (steppers & other output-only pins) // -#define I2S_STEPPER_STREAM +#ifndef I2S_STEPPER_STREAM + #define I2S_STEPPER_STREAM +#endif #if ENABLED(I2S_STEPPER_STREAM) #define I2S_WS 17 #define I2S_BCK 22 @@ -91,7 +93,9 @@ #define K_CS_PIN 159 // Reduce baud rate to improve software serial reliability -#define TMC_BAUD_RATE 19200 +#ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 +#endif // // Temperature Sensors @@ -101,14 +105,14 @@ // General use mosfets, useful for things like pumps and solenoids // Shift register pins 128, 129, 130 and 131 are broken out and can be used -#define FAN_PIN 132 +#define FAN0_PIN 132 #define FAN1_PIN 134 #define FAN2_PIN 135 #define FAN3_PIN 136 // #define FAN_SOFT_PWM_REQUIRED // check if needed -// Neopixel Rings +// NeoPixel Rings #define NEOPIXEL_PIN 14 #define NEOPIXEL2_PIN 27 diff --git a/Marlin/src/pins/esp32/pins_ESP32.h b/Marlin/src/pins/esp32/pins_ESP32.h index 266de7e9f60e..9c9b06ca6437 100644 --- a/Marlin/src/pins/esp32/pins_ESP32.h +++ b/Marlin/src/pins/esp32/pins_ESP32.h @@ -32,7 +32,9 @@ // // I2S (steppers & other output-only pins) // -#define I2S_STEPPER_STREAM +#ifndef I2S_STEPPER_STREAM + #define I2S_STEPPER_STREAM +#endif #if ENABLED(I2S_STEPPER_STREAM) #define I2S_WS 25 #define I2S_BCK 26 @@ -79,7 +81,7 @@ // Heaters / Fans // #define HEATER_0_PIN 2 -#define FAN_PIN 13 +#define FAN0_PIN 13 #define HEATER_BED_PIN 4 // SPI diff --git a/Marlin/src/pins/esp32/pins_ESPA_common.h b/Marlin/src/pins/esp32/pins_ESPA_common.h index ca949cdf9716..36068150f720 100644 --- a/Marlin/src/pins/esp32/pins_ESPA_common.h +++ b/Marlin/src/pins/esp32/pins_ESPA_common.h @@ -68,7 +68,7 @@ // Heaters / Fans // #define HEATER_0_PIN 2 -#define FAN_PIN 13 +#define FAN0_PIN 13 #define HEATER_BED_PIN 4 // diff --git a/Marlin/src/pins/esp32/pins_FYSETC_E4.h b/Marlin/src/pins/esp32/pins_FYSETC_E4.h index 7dc59979c8f1..4bcffb545ee0 100644 --- a/Marlin/src/pins/esp32/pins_FYSETC_E4.h +++ b/Marlin/src/pins/esp32/pins_FYSETC_E4.h @@ -30,9 +30,7 @@ #include "env_validate.h" -#if EXTRUDERS > 1 || E_STEPPERS > 1 - #error "FYSETC E4 only supports 1 E stepper." -#elif HAS_MULTI_HOTEND +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "FYSETC E4 only supports 1 hotend / E stepper." #endif diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h index 37ce4ee94e56..297ba34e7157 100644 --- a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h +++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h @@ -22,10 +22,8 @@ #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. + * MKS TinyBee pin assignments + * https://github.com/makerbase-mks/MKS-TinyBee */ #include "env_validate.h" @@ -58,7 +56,9 @@ // // Enable I2S stepper stream // -#define I2S_STEPPER_STREAM +#ifndef I2S_STEPPER_STREAM + #define I2S_STEPPER_STREAM +#endif #if ENABLED(I2S_STEPPER_STREAM) #define I2S_WS 26 #define I2S_BCK 25 @@ -104,7 +104,7 @@ // #define HEATER_0_PIN 145 #define HEATER_1_PIN 146 -#define FAN_PIN 147 +#define FAN0_PIN 147 #define FAN1_PIN 148 #define HEATER_BED_PIN 144 @@ -121,7 +121,7 @@ * ------ ------ * (BEEPER) 149 | 1 2 | 13 (BTN_ENC) (SPI MISO) 19 | 1 2 | 18 (SPI SCK) * (LCD_EN) 21 | 3 4 | 4 (LCD_RS) (BTN_EN1) 14 | 3 4 | 5 (SPI CS) - * (LCD_D4) 0 5 6 | 16 (LCD_D5) (BTN_EN2) 12 5 6 | 23 (SPI MOSI) + * (LCD_D4) 0 | 5 6 16 (LCD_D5) (BTN_EN2) 12 | 5 6 23 (SPI MOSI) * (LCD_D6) 15 | 7 8 | 17 (LCD_D7) (SPI_DET) 34 | 7 8 | RESET * GND | 9 10 | 5V GND | 9 10 | 3.3V * ------ ------ @@ -158,7 +158,7 @@ #if HAS_WIRED_LCD #define BEEPER_PIN EXP1_01_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_RS EXP1_04_PIN #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP2_03_PIN @@ -171,7 +171,7 @@ #define DOGLCD_A0 EXP1_07_PIN #define LCD_RESET_PIN -1 #elif ENABLED(FYSETC_MINI_12864_2_1) - // MKS_MINI_12864_V3, BTT_MINI_12864_V1, FYSETC_MINI_12864_2_1 + // MKS_MINI_12864_V3, BTT_MINI_12864, FYSETC_MINI_12864_2_1 #define DOGLCD_CS EXP1_03_PIN #define DOGLCD_A0 EXP1_04_PIN #define LCD_RESET_PIN EXP1_05_PIN @@ -179,7 +179,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif - #if BOTH(MKS_MINI_12864_V3, SDSUPPORT) + #if ALL(MKS_MINI_12864_V3, HAS_MEDIA) #define PAUSE_LCD_FOR_BUSY_SD #endif #else diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPA.h b/Marlin/src/pins/esp32/pins_MRR_ESPA.h index e9e3db575896..ba5f6cbe35fa 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPA.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPA.h @@ -30,9 +30,7 @@ #include "env_validate.h" -#if EXTRUDERS > 1 || E_STEPPERS > 1 - #error "MRR ESPA only supports 1 E stepper." -#elif HAS_MULTI_HOTEND +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "MRR ESPA only supports 1 hotend / E stepper." #endif diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPE.h b/Marlin/src/pins/esp32/pins_MRR_ESPE.h index f372de9e0110..bcdb8c4faa75 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPE.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPE.h @@ -51,7 +51,9 @@ // // Enable I2S stepper stream // -#define I2S_STEPPER_STREAM +#ifndef I2S_STEPPER_STREAM + #define I2S_STEPPER_STREAM +#endif #if ENABLED(I2S_STEPPER_STREAM) #define I2S_WS 26 #define I2S_BCK 25 @@ -102,7 +104,7 @@ // Heaters / Fans // #define HEATER_0_PIN 145 // 2 -#define FAN_PIN 146 // 15 +#define FAN0_PIN 146 // 15 #define HEATER_BED_PIN 144 // 4 #define CONTROLLER_FAN_PIN 147 @@ -119,14 +121,14 @@ #define SDSS 5 #define USES_SHARED_SPI // SPI is shared by SD card with TMC SPI drivers -////////////////////////// -// LCDs and Controllers // -////////////////////////// +// +// LCD / Controller +// #if HAS_WIRED_LCD #define LCD_PINS_RS 13 - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_EN 17 #define LCD_PINS_D4 16 #if ENABLED(CR10_STOCKDISPLAY) diff --git a/Marlin/src/pins/esp32/pins_PANDA_M4.h b/Marlin/src/pins/esp32/pins_PANDA_M4.h index 5e2e72af05df..c619be43a5f8 100644 --- a/Marlin/src/pins/esp32/pins_PANDA_M4.h +++ b/Marlin/src/pins/esp32/pins_PANDA_M4.h @@ -27,6 +27,10 @@ #define BOARD_INFO_NAME "Panda_M4" +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 + #error "PANDA M4 only supports 1 hotend / E stepper." +#endif + #include "pins_PANDA_common.h" // diff --git a/Marlin/src/pins/esp32/pins_PANDA_ZHU.h b/Marlin/src/pins/esp32/pins_PANDA_ZHU.h index 47500578976e..36a589b60035 100644 --- a/Marlin/src/pins/esp32/pins_PANDA_ZHU.h +++ b/Marlin/src/pins/esp32/pins_PANDA_ZHU.h @@ -27,6 +27,13 @@ #define BOARD_INFO_NAME "Panda_ZHU" +#if E_STEPPERS > 5 + #error "PANDA ZHU supports up to 5 E steppers." +#endif +#if HAS_MULTI_HOTEND + #error "PANDA ZHU only supports 1 hotend." +#endif + #include "pins_PANDA_common.h" // diff --git a/Marlin/src/pins/esp32/pins_PANDA_common.h b/Marlin/src/pins/esp32/pins_PANDA_common.h index afc9a78aec01..2cc954940e47 100644 --- a/Marlin/src/pins/esp32/pins_PANDA_common.h +++ b/Marlin/src/pins/esp32/pins_PANDA_common.h @@ -63,10 +63,10 @@ #define TEMP_BED_PIN 36 // Analog Input #if ENABLED(MAX31856_PANDAPI) - #define MAX31856_CLK_PIN 29 - #define MAX31856_MISO_PIN 24 - #define MAX31856_MOSI_PIN 28 - #define MAX31856_CS_PIN 27 + #define TEMP_0_CLK_PIN 29 + #define TEMP_0_MISO_PIN 24 + #define TEMP_0_MOSI_PIN 28 + #define TEMP_0_CS_PIN 27 #endif // @@ -74,7 +74,7 @@ // #define HEATER_0_PIN 108 #define HEATER_BED_PIN 109 -#define FAN_PIN 118 // FAN0 +#define FAN0_PIN 118 // FAN0 #define FAN1_PIN 119 // FAN1 #ifndef E0_AUTO_FAN_PIN @@ -86,7 +86,7 @@ * (EN1) 33 | 3 4 | (5 SDSS?) (EN) 26 | 3 4 | 27 (RS) * (EN2) 32 5 6 | (23 MOSI?) (D4) 14 | 5 6 -- * (SDDET 2?) | 7 8 | (RESET) -- | 7 8 | -- - * -- | 9 10 | -- (GND) | 9 10 | (5V) + * -- | 9 10 | -- GND | 9 10 | 5V * ------ ------ * EXP2 EXP1 */ @@ -107,7 +107,7 @@ // // SD Card // -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #define SD_MOSI_PIN EXP2_06_PIN #define SD_MISO_PIN EXP2_01_PIN #define SD_SCK_PIN EXP2_02_PIN @@ -123,6 +123,6 @@ #define BTN_EN2 EXP2_05_PIN #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #endif diff --git a/Marlin/src/pins/esp32/pins_RESP32_CUSTOM.h b/Marlin/src/pins/esp32/pins_RESP32_CUSTOM.h index 5d3f75574d89..f627909a7a32 100644 --- a/Marlin/src/pins/esp32/pins_RESP32_CUSTOM.h +++ b/Marlin/src/pins/esp32/pins_RESP32_CUSTOM.h @@ -34,4 +34,6 @@ // // I2S (steppers & other output-only pins) // -#define I2S_STEPPER_STREAM +#ifndef I2S_STEPPER_STREAM + #define I2S_STEPPER_STREAM +#endif diff --git a/Marlin/src/pins/gd32f1/env_validate.h b/Marlin/src/pins/gd32f1/env_validate.h new file mode 100644 index 000000000000..f6882e70d633 --- /dev/null +++ b/Marlin/src/pins/gd32f1/env_validate.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H + +#if NOT_TARGET(__STM32F1__, STM32F1) + #error "Oops! Select an STM32F1 board in 'Tools > Board.'" +#endif + +#endif diff --git a/Marlin/src/pins/gd32f1/pins_SOVOL_V131.h b/Marlin/src/pins/gd32f1/pins_SOVOL_V131.h new file mode 100644 index 000000000000..e92c24b86cdb --- /dev/null +++ b/Marlin/src/pins/gd32f1/pins_SOVOL_V131.h @@ -0,0 +1,76 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 + +/** + * Sovol 1.3.1 (GD32F103RET6) board pin assignments + */ + +#include "env_validate.h" + +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 + #error "SOVOL V131 only supports 1 hotend / E-stepper." + #define E_ERROR 1 +#endif + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "Sovol V131" +#endif +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME "Sovol SV06" +#endif + +#include "../stm32f1/pins_CREALITY_V4.h" + +#if HAS_TMC_UART + + /** + * TMC2208/TMC2209 stepper drivers + * + * Hardware serial communication ports. + * If undefined software serial is used according to the pins below + */ + + #define X_SERIAL_TX_PIN PC1 + #define X_SERIAL_RX_PIN PC1 + + #define Y_SERIAL_TX_PIN PC0 + #define Y_SERIAL_RX_PIN PC0 + + #define Z_SERIAL_TX_PIN PA15 + #define Z_SERIAL_RX_PIN PA15 + + #define E0_SERIAL_TX_PIN PC14 + #define E0_SERIAL_RX_PIN PC14 + + // Reduce baud rate to improve software serial reliability + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART + +// +// SD Card +// +#define ONBOARD_SPI_DEVICE 1 +#define ONBOARD_SD_CS_PIN PA4 // SDSS diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 3616b7a27c43..48b419e70827 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -136,7 +136,7 @@ #define TEMP_BED_PIN 2 // Analog Input // SPI for MAX Thermocouple -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) @@ -161,21 +161,21 @@ #define HEATER_0_PIN MOSFET_A_PIN #if FET_ORDER_EFB // Hotend, Fan, Bed - #define FAN_PIN MOSFET_B_PIN + #define FAN0_PIN MOSFET_B_PIN #define HEATER_BED_PIN MOSFET_C_PIN #elif FET_ORDER_EEF // Hotend, Hotend, Fan #define HEATER_1_PIN MOSFET_B_PIN - #define FAN_PIN MOSFET_C_PIN + #define FAN0_PIN MOSFET_C_PIN #elif FET_ORDER_EEB // Hotend, Hotend, Bed #define HEATER_1_PIN MOSFET_B_PIN #define HEATER_BED_PIN MOSFET_C_PIN #elif FET_ORDER_EFF // Hotend, Fan, Fan - #define FAN_PIN MOSFET_B_PIN + #define FAN0_PIN MOSFET_B_PIN #define FAN1_PIN MOSFET_C_PIN #elif FET_ORDER_SF // Spindle, Fan - #define FAN_PIN MOSFET_C_PIN + #define FAN0_PIN MOSFET_C_PIN #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") - #define FAN_PIN MOSFET_B_PIN + #define FAN0_PIN MOSFET_B_PIN #define HEATER_BED_PIN MOSFET_C_PIN #if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL) #define FAN1_PIN MOSFET_D_PIN @@ -184,8 +184,8 @@ #endif #endif -#ifndef FAN_PIN - #define FAN_PIN 4 // IO pin. Buffer needed +#ifndef FAN0_PIN + #define FAN0_PIN 4 // IO pin. Buffer needed #endif // @@ -221,12 +221,12 @@ // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // Prefer the servo connector - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #elif HAS_FREE_AUX2_PINS // try to use AUX 2 - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_DIR_PIN 65 #endif #endif @@ -247,18 +247,16 @@ #endif /** - * Default pins for TMC software SPI + * Default pins for TMC SPI */ -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 66 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO 44 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK 64 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI 66 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO 44 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK 64 #endif #if HAS_TMC_UART @@ -373,24 +371,53 @@ #endif #endif -////////////////////////// -// LCDs and Controllers // -////////////////////////// +/** Faux Expansion Headers + * ------ ------ + * (BEEP) 37 | 1 2 | 35 (ENC) (MISO) 50 | 1 2 | 52 (SCK) + * (LCD_EN) 17 | 3 4 | 16 (LCD_RS) (EN1) 31 | 3 4 | 53 (SDSS) + * (LCD_D4) 23 5 6 | 25 (LCD_D5) (EN2) 33 5 6 | 51 (MOSI) + * (LCD_D6) 27 | 7 8 | 29 (LCD_D7) (SD_DET) 49 | 7 8 | 41 (KILL) + * -- | 9 10 | -- -- | 9 10 | -- + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_01_PIN 37 // BEEPER +#define EXP1_02_PIN 35 // ENC +#define EXP1_03_PIN 17 // LCD_EN +#define EXP1_04_PIN 16 // LCD_RS +#define EXP1_05_PIN 23 // LCD_D4 +#define EXP1_06_PIN 25 // LCD_D5 +#define EXP1_07_PIN 27 // LCD_D6 +#define EXP1_08_PIN 29 // LCD_D7 + +#define EXP2_01_PIN 50 // MISO +#define EXP2_02_PIN 52 // SCK +#define EXP2_03_PIN 31 // EN1 +#define EXP2_04_PIN 53 // SDSS +#define EXP2_05_PIN 33 // EN2 +#define EXP2_06_PIN 51 // MOSI +#define EXP2_07_PIN 49 // SD_DET +#define EXP2_08_PIN 41 // KILL + +// +// LCD / Controller +// #if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI) - #define TFT_A0_PIN 43 #define TFT_CS_PIN 49 #define TFT_DC_PIN 43 + #define TFT_A0_PIN TFT_DC_PIN #define TFT_SCK_PIN SD_SCK_PIN - #define TFT_MOSI_PIN SD_MOSI_PIN #define TFT_MISO_PIN SD_MISO_PIN + #define TFT_MOSI_PIN SD_MOSI_PIN #define LCD_USE_DMA_SPI + #define BEEPER_PIN 42 + + #define BTN_ENC 59 #define BTN_EN1 40 #define BTN_EN2 63 - #define BTN_ENC 59 - #define BEEPER_PIN 42 #define TOUCH_CS_PIN 33 @@ -398,19 +425,19 @@ #define SPI_FLASH #if ENABLED(SPI_FLASH) - #define SPI_DEVICE 1 + #define SPI_DEVICE 1 // Maple #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN 31 - #define SPI_FLASH_MOSI_PIN SD_MOSI_PIN - #define SPI_FLASH_MISO_PIN SD_MISO_PIN #define SPI_FLASH_SCK_PIN SD_SCK_PIN + #define SPI_FLASH_MISO_PIN SD_MISO_PIN + #define SPI_FLASH_MOSI_PIN SD_MOSI_PIN #endif - #define TFT_BUFFER_SIZE 0xFFFF + #define TFT_BUFFER_WORDS 0xFFFF #ifndef TFT_DRIVER #define TFT_DRIVER ST7796 #endif - #ifndef TOUCH_SCREEN_CALIBRATION + #if DISABLED(TOUCH_SCREEN_CALIBRATION) #if ENABLED(TFT_RES_320x240) #ifndef TOUCH_CALIBRATION_X #define TOUCH_CALIBRATION_X 20525 @@ -475,14 +502,14 @@ // #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS EXP2_07_PIN // CS chip select /SS chip slave select + #define LCD_PINS_EN EXP2_06_PIN // SID (MOSI) + #define LCD_PINS_D4 EXP2_02_PIN // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) #define LCD_PINS_RS 40 - #define LCD_PINS_ENABLE 42 + #define LCD_PINS_EN 42 #define LCD_PINS_D4 65 #define LCD_PINS_D5 66 #define LCD_PINS_D6 44 @@ -492,18 +519,18 @@ #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 25 + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_EN EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #if !IS_NEWPANEL - #define BEEPER_PIN 37 + #define BEEPER_PIN EXP1_01_PIN #endif #elif ENABLED(ZONESTAR_LCD) #define LCD_PINS_RS 64 - #define LCD_PINS_ENABLE 44 + #define LCD_PINS_EN 44 #define LCD_PINS_D4 63 #define LCD_PINS_D5 40 #define LCD_PINS_D6 42 @@ -511,39 +538,29 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) - #define LCD_PINS_DC 25 // Set as output on init - #define LCD_PINS_RS 27 // Pull low for 1s to init + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) + #define LCD_PINS_DC EXP1_06_PIN // Set as output on init + #define LCD_PINS_RS EXP1_07_PIN // Pull low for 1s to init // DOGM SPI LCD Support - #define DOGLCD_CS 16 - #define DOGLCD_MOSI 17 - #define DOGLCD_SCK 23 + #define DOGLCD_CS EXP1_04_PIN + #define DOGLCD_MOSI EXP1_03_PIN + #define DOGLCD_SCK EXP1_05_PIN #define DOGLCD_A0 LCD_PINS_DC #else - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN #endif - #define LCD_PINS_D7 29 + #define LCD_PINS_D7 EXP1_08_PIN #if !IS_NEWPANEL - #define BEEPER_PIN 33 + #define BEEPER_PIN EXP2_05_PIN #endif #endif - - #if !IS_NEWPANEL - // Buttons attached to a shift register - // Not wired yet - //#define SHIFT_CLK_PIN 38 - //#define SHIFT_LD_PIN 42 - //#define SHIFT_OUT_PIN 40 - //#define SHIFT_EN_PIN 17 - #endif - #endif // @@ -553,19 +570,19 @@ #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 37 + #define BEEPER_PIN EXP1_01_PIN #if ENABLED(CR10_STOCKDISPLAY) - #define BTN_EN1 17 - #define BTN_EN2 23 + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN #else - #define BTN_EN1 31 - #define BTN_EN2 33 + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #endif - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define BTN_ENC EXP1_02_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #define KILL_PIN EXP2_08_PIN #if ENABLED(BQ_LCD_SMART_CONTROLLER) #define LCD_BACKLIGHT_PIN 39 @@ -595,7 +612,7 @@ #define LCD_SDSS SDSS #define SD_DETECT_PIN 49 - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #define DOGLCD_CS 45 #define DOGLCD_A0 44 @@ -615,34 +632,34 @@ #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN - #define BEEPER_PIN 23 - #define LCD_BACKLIGHT_PIN 33 + #define BEEPER_PIN EXP1_05_PIN + #define LCD_BACKLIGHT_PIN EXP2_05_PIN - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 + #define BTN_EN1 EXP1_02_PIN + #define BTN_EN2 EXP1_01_PIN + #define BTN_ENC EXP2_03_PIN #define LCD_SDSS SDSS - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN EXP2_07_PIN + #define KILL_PIN EXP2_08_PIN #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 27 - #define DOGLCD_CS 25 + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN - #define BEEPER_PIN 37 + #define BEEPER_PIN EXP1_01_PIN // not connected to a pin #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN EXP2_07_PIN #define KILL_PIN 64 //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 @@ -675,7 +692,6 @@ #else - // Beeper on AUX-4 #define BEEPER_PIN 33 // Buttons are directly attached to AUX-2 @@ -691,15 +707,15 @@ #define BTN_EN2 63 // AUX2 PIN 4 #define BTN_ENC 49 // AUX3 PIN 7 #else - #define BTN_EN1 37 - #define BTN_EN2 35 - #define BTN_ENC 31 - #define SD_DETECT_PIN 41 + #define BTN_EN1 EXP1_01_PIN + #define BTN_EN2 EXP1_02_PIN + #define BTN_ENC EXP2_03_PIN + #define SD_DETECT_PIN EXP2_08_PIN #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN EXP2_07_PIN + #define KILL_PIN EXP2_08_PIN #endif #endif diff --git a/Marlin/src/pins/lpc1768/env_validate.h b/Marlin/src/pins/lpc1768/env_validate.h index adb3ea938dc2..8a6a1cebd368 100644 --- a/Marlin/src/pins/lpc1768/env_validate.h +++ b/Marlin/src/pins/lpc1768/env_validate.h @@ -19,7 +19,8 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if ENABLED(REQUIRE_LPC1769) && NOT_TARGET(MCU_LPC1769) #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." @@ -28,3 +29,5 @@ #endif #undef REQUIRE_LPC1769 + +#endif diff --git a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h index 657eb8a0466c..ca8010493bb9 100644 --- a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h +++ b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h @@ -82,8 +82,8 @@ // EFB #define HEATER_0_PIN P2_04 #define HEATER_BED_PIN P2_05 -#ifndef FAN_PIN - #define FAN_PIN P2_07 +#ifndef FAN0_PIN + #define FAN0_PIN P2_07 #endif #define FAN1_PIN P0_26 diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h index 217e270b9caa..c498af3a64d9 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h @@ -73,18 +73,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P0_18 // ETH - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_17 // ETH - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_15 // ETH - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P0_18 // ETH +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_17 // ETH +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_15 // ETH #endif // @@ -99,8 +97,8 @@ // #define HEATER_0_PIN P2_07 #define HEATER_BED_PIN P2_05 -#ifndef FAN_PIN - #define FAN_PIN P2_04 +#ifndef FAN0_PIN + #define FAN0_PIN P2_04 #endif // @@ -129,14 +127,14 @@ #define SD_DETECT_PIN P0_27 // EXP2-7 #define LCD_PINS_RS P0_16 // EXP1-4 - #define LCD_PINS_ENABLE P0_18 // (MOSI) EXP1-3 + #define LCD_PINS_EN P0_18 // (MOSI) EXP1-3 #define LCD_PINS_D4 P0_15 // (SCK) EXP1-5 - #if BOTH(HAS_MARLINUI_HD44780, IS_RRD_SC) + #if ALL(HAS_MARLINUI_HD44780, IS_RRD_SC) #error "REPRAP_DISCOUNT_SMART_CONTROLLER displays aren't supported by the BIQU B300 v1.0" #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA #error "SDSUPPORT is not supported by the BIQU B300 v1.0 when an LCD controller is used" #endif @@ -148,7 +146,7 @@ * Software SPI is used to interface with a stand-alone SD card reader connected to EXP1. * Hardware SPI can't be used because P0_17 (MISO) is not brought out on this board. */ -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #define SD_SCK_PIN P0_15 // EXP1-5 #define SD_MISO_PIN P0_16 // EXP1-4 #define SD_MOSI_PIN P0_18 // EXP1-3 @@ -161,7 +159,7 @@ * * There are 6 PWMS. Each PWM can be assigned to one of two pins. * - * PWM1.1 P0_18 LCD_PINS_ENABLE + * PWM1.1 P0_18 LCD_PINS_EN * PWM1.1 P2_0 X_STEP_PIN * PWM1.2 P1_20 * PWM1.2 P2_1 Y_STEP_PIN @@ -170,7 +168,7 @@ * PWM1.4 P1_23 * PWM1.4 P2_3 E0_STEP_PIN * PWM1.5 P1_24 X_MIN_PIN - * PWM1.5 P2_4 FAN_PIN + * PWM1.5 P2_4 FAN0_PIN * PWM1.6 P1_26 Y_MIN_PIN * PWM1.6 P2_5 HEATER_BED_PIN */ diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h index 2c0d52ef9a10..3fb29b90929d 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h @@ -74,8 +74,8 @@ // #define HEATER_0_PIN P2_07 #define HEATER_BED_PIN P2_05 -#ifndef FAN_PIN - #define FAN_PIN P2_04 +#ifndef FAN0_PIN + #define FAN0_PIN P2_04 #endif // @@ -104,14 +104,14 @@ #define SD_DETECT_PIN P0_27 // EXP2-7 #define LCD_PINS_RS P0_16 // EXP1-4 - #define LCD_PINS_ENABLE P0_18 // (MOSI) EXP1-3 + #define LCD_PINS_EN P0_18 // (MOSI) EXP1-3 #define LCD_PINS_D4 P0_15 // (SCK) EXP1-5 - #if BOTH(HAS_MARLINUI_HD44780, IS_RRD_SC) + #if ALL(HAS_MARLINUI_HD44780, IS_RRD_SC) #error "REPRAP_DISCOUNT_SMART_CONTROLLER displays aren't supported by the BIQU BQ111-A4" #endif - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA #error "SDSUPPORT is not supported by the BIQU BQ111-A4 when an LCD controller is used" #endif @@ -123,7 +123,7 @@ * Software SPI is used to interface with a stand-alone SD card reader connected to EXP1. * Hardware SPI can't be used because P0_17 (MISO) is not brought out on this board. */ -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #define SD_SCK_PIN P0_15 // EXP1-5 #define SD_MISO_PIN P0_16 // EXP1-4 @@ -131,14 +131,14 @@ #define SD_SS_PIN P1_30 // EXP1-2 #define SDSS SD_SS_PIN -#endif // SDSUPPORT +#endif // HAS_MEDIA /** * PWMS * * There are 6 PWMS. Each PWM can be assigned to one of two pins. * - * PWM1.1 P0_18 LCD_PINS_ENABLE + * PWM1.1 P0_18 LCD_PINS_EN * PWM1.1 P2_0 X_STEP_PIN * PWM1.2 P1_20 * PWM1.2 P2_1 Y_STEP_PIN @@ -147,7 +147,7 @@ * PWM1.4 P1_23 * PWM1.4 P2_3 E0_STEP_PIN * PWM1.5 P1_24 X_MIN_PIN - * PWM1.5 P2_4 FAN_PIN + * PWM1.5 P2_4 FAN0_PIN * PWM1.6 P1_26 Y_MIN_PIN * PWM1.6 P2_5 HEATER_BED_PIN */ 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 879e98243cef..008fc3d4a0b3 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -58,7 +58,6 @@ #define E0_DIR_PIN P2_13 #define E0_ENABLE_PIN P2_12 - /** ------ ------ * 1.30 | 1 2 | 2.11 0.17 | 1 2 | 0.15 * 0.18 | 3 4 | 0.16 3.26 | 3 4 | 1.23 @@ -113,7 +112,7 @@ #define LCD_SDSS EXP2_04_PIN #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP2_06_PIN + #define LCD_PINS_EN EXP2_06_PIN #define LCD_PINS_D4 EXP2_02_PIN #if ENABLED(MKS_MINI_12864) @@ -167,12 +166,12 @@ // When using any TMC SPI-based drivers, software SPI is used // because pins may be shared with the display or SD card. #define TMC_USE_SW_SPI - #define TMC_SW_MOSI EXP2_06_PIN - #define TMC_SW_MISO EXP2_01_PIN + #define TMC_SPI_MOSI EXP2_06_PIN + #define TMC_SPI_MISO EXP2_01_PIN // To minimize pin usage use the same clock pin as the display/SD card reader. (May generate LCD noise.) - #define TMC_SW_SCK EXP2_02_PIN + #define TMC_SPI_SCK EXP2_02_PIN // If pin 2_06 is unused, it can be used for the clock to avoid the LCD noise. - //#define TMC_SW_SCK P2_06 + //#define TMC_SPI_SCK P2_06 #if ENABLED(SOFTWARE_DRIVER_ENABLE) @@ -203,7 +202,7 @@ #undef E1_ENABLE_PIN #endif - #else // !SOFTWARE_DRIVER_ENABLE + #else // !SOFTWARE_DRIVER_ENABLE // A chip-select pin is needed for each driver. 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 6653a94f8059..9c901e249de7 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -96,6 +96,13 @@ #define Z_MIN_PROBE_PIN P1_24 #endif +// +// Probe enable +// +#if ENABLED(PROBE_ENABLE_DISABLE) && !defined(PROBE_ENABLE_PIN) + #define PROBE_ENABLE_PIN SERVO0_PIN +#endif + // // Filament Runout Sensor // @@ -139,18 +146,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P4_28 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_05 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_04 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P4_28 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_05 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_04 #endif #if HAS_TMC_UART @@ -188,8 +193,11 @@ #define E1_SERIAL_RX_PIN P1_01 // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART /** * ------ ------ @@ -256,7 +264,7 @@ #define BTN_EN2 EXP1_07_PIN #define BTN_ENC EXP1_03_PIN - #define LCD_PINS_ENABLE EXP1_06_PIN + #define LCD_PINS_EN EXP1_06_PIN #define LCD_PINS_D4 EXP1_04_PIN #elif ENABLED(WYH_L12864) @@ -284,14 +292,15 @@ * ------ ------ * LCD LCD */ + #define BTN_ENC EXP1_03_PIN #define BTN_EN1 EXP1_05_PIN #define BTN_EN2 EXP1_07_PIN - #define BTN_ENC EXP1_03_PIN + #define DOGLCD_CS EXP1_08_PIN #define DOGLCD_A0 EXP1_06_PIN #define DOGLCD_SCK EXP1_04_PIN #define DOGLCD_MOSI EXP1_01_PIN - #define LCD_BACKLIGHT_PIN -1 + #define LCD_BACKLIGHT_PIN -1 #elif ENABLED(CR10_STOCKDISPLAY) @@ -301,7 +310,7 @@ #define BTN_EN2 EXP1_05_PIN #define BTN_ENC EXP1_02_PIN // (58) open-drain - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif HAS_ADC_BUTTONS @@ -310,28 +319,15 @@ #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI - #define TFT_A0_PIN EXP1_08_PIN - #define TFT_DC_PIN EXP1_08_PIN - #define TFT_CS_PIN EXP1_07_PIN - #define TFT_RESET_PIN EXP1_04_PIN - #define TFT_BACKLIGHT_PIN EXP1_03_PIN - - //#define TFT_RST_PIN EXP2_07_PIN - #define TFT_MOSI_PIN EXP2_06_PIN - #define TFT_SCK_PIN EXP2_02_PIN - #define TFT_MISO_PIN EXP2_01_PIN - - #define BTN_EN2 EXP2_05_PIN - #define BTN_EN1 EXP2_03_PIN - #define BTN_ENC EXP1_02_PIN + #define SDCARD_CONNECTION ONBOARD #define BEEPER_PIN EXP1_01_PIN - #define SDCARD_CONNECTION ONBOARD - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define TFT_BUFFER_SIZE 2400 + #define TFT_A0_PIN TFT_DC_PIN #ifndef TFT_WIDTH #define TFT_WIDTH 480 @@ -340,21 +336,84 @@ #define TFT_HEIGHT 320 #endif - #define LCD_READ_ID 0xD3 - #define LCD_USE_DMA_SPI + #if ENABLED(BTT_TFT35_SPI_V1_0) + + /** + * ------ ------ + * BEEPER | 1 2 | LCD-BTN MISO | 1 2 | CLK + * T_MOSI | 3 4 | T_CS LCD-ENCA | 3 4 | TFTCS + * T_CLK | 5 6 T_MISO LCD-ENCB | 5 6 MOSI + * PENIRQ | 7 8 | F_CS RS | 7 8 | RESET + * GND | 9 10 | VCC GND | 9 10 | NC + * ------ ------ + * EXP1 EXP2 + * + * 480x320, 3.5", SPI Display with Rotary Encoder. + * Stock Display for the BIQU B1 SE Series. + * Schematic: https://github.com/bigtreetech/TFT35-SPI/blob/master/v1/Hardware/BTT%20TFT35-SPI%20V1-SCH.pdf + */ + #define TFT_CS_PIN EXP2_04_PIN + #define TFT_DC_PIN EXP2_07_PIN + + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + + #define TOUCH_CS_PIN EXP1_04_PIN + #define TOUCH_SCK_PIN EXP1_05_PIN + #define TOUCH_MISO_PIN EXP1_06_PIN + #define TOUCH_MOSI_PIN EXP1_03_PIN + #define TOUCH_INT_PIN EXP1_07_PIN + + #elif ENABLED(MKS_TS35_V2_0) + + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! MKS_TS35_V2_0 requires wiring modifications. The SKR 1.3 EXP ports are rotated 180° from what the MKS_TS35_V2_0 expects. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this error.)" + #endif + + /** ------ ------ + * BEEPER | 1 2 | BTN_ENC SPI1_MISO | 1 2 | SPI1_SCK + * TFT_BKL / LCD_EN | 3 4 | TFT_RESET / LCD_RS BTN_EN1 | 3 4 | SPI1_CS + * TOUCH_CS / LCD_D4 | 5 6 TOUCH_INT / LCD_D5 BTN_EN2 | 5 6 SPI1_MOSI + * SPI1_CS / LCD_D6 | 7 8 | SPI1_RS / LCD_D7 SPI1_RS | 7 8 | RESET + * GND | 9 10 | VCC GND | 9 10 | VCC + * ------ ------ + * EXP1 EXP2 + */ + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_DC_PIN EXP1_08_PIN + + #define TFT_RESET_PIN EXP1_04_PIN + #define TFT_BACKLIGHT_PIN EXP1_03_PIN + + //#define TFT_RST_PIN EXP2_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + + #define LCD_USE_DMA_SPI + + #define TFT_BUFFER_WORDS 2400 + + #define TOUCH_CS_PIN EXP1_05_PIN + #define TOUCH_INT_PIN EXP1_06_PIN + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #endif #if ENABLED(TFT_CLASSIC_UI) #ifndef TOUCH_CALIBRATION_X - #define TOUCH_CALIBRATION_X -11386 + #define TOUCH_CALIBRATION_X -16794 #endif #ifndef TOUCH_CALIBRATION_Y - #define TOUCH_CALIBRATION_Y 8684 + #define TOUCH_CALIBRATION_Y 11000 #endif #ifndef TOUCH_OFFSET_X - #define TOUCH_OFFSET_X 689 + #define TOUCH_OFFSET_X 1024 #endif #ifndef TOUCH_OFFSET_Y - #define TOUCH_OFFSET_Y -273 + #define TOUCH_OFFSET_Y -352 #endif #elif ENABLED(TFT_COLOR_UI) #ifndef TOUCH_CALIBRATION_X @@ -369,7 +428,7 @@ #ifndef TOUCH_OFFSET_Y #define TOUCH_OFFSET_Y -367 #endif - #define TFT_BUFFER_SIZE 2400 + #define TFT_BUFFER_WORDS 2400 #endif #elif IS_TFTGLCD_PANEL @@ -379,7 +438,7 @@ #define SD_DETECT_PIN EXP2_07_PIN - #else // !CR10_STOCKDISPLAY + #else // !CR10_STOCKDISPLAY #define LCD_PINS_RS EXP1_04_PIN @@ -387,7 +446,7 @@ #define BTN_EN2 EXP2_05_PIN // (33) J3-4 & AUX-4 #define BTN_ENC EXP1_02_PIN // (58) open-drain - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #define LCD_SDSS EXP2_04_PIN // (16) J3-7 & AUX-4 @@ -399,14 +458,12 @@ #define DOGLCD_SCK EXP2_02_PIN #define DOGLCD_MOSI EXP2_06_PIN - #define LCD_BACKLIGHT_PIN -1 - #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif @@ -420,7 +477,7 @@ #define NEOPIXEL_PIN EXP1_06_PIN #endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) @@ -472,14 +529,6 @@ #endif // HAS_WIRED_LCD -#if NEED_TOUCH_PINS - #define TOUCH_CS_PIN EXP1_05_PIN - #define TOUCH_SCK_PIN EXP2_02_PIN - #define TOUCH_MOSI_PIN EXP2_06_PIN - #define TOUCH_MISO_PIN EXP2_01_PIN - #define TOUCH_INT_PIN EXP1_06_PIN -#endif - /** * Special pins * P1_30 (37) (NOT 5V tolerant) 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 667b0fa949c3..fa222bdac2ee 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -134,6 +134,13 @@ #define Z_MIN_PROBE_PIN P0_10 #endif +// +// Probe enable +// +#if ENABLED(PROBE_ENABLE_DISABLE) && !defined(PROBE_ENABLE_PIN) + #define PROBE_ENABLE_PIN SERVO0_PIN +#endif + // // Filament Runout Sensor // @@ -196,18 +203,16 @@ #define TEMP_BED_PIN P0_25_A2 // A2 (T2) - (69) - TEMP_BED_PIN // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_17 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_05 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_04 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P1_17 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_05 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_04 #endif #if HAS_TMC_UART @@ -245,8 +250,11 @@ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART /** ------ ------ * 1.30 | 1 2 | 0.28 0.17 | 1 2 | 0.15 @@ -318,7 +326,7 @@ #define BTN_EN2 EXP1_07_PIN #define BTN_ENC EXP1_01_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #define BEEPER_PIN EXP1_08_PIN @@ -354,7 +362,7 @@ #define BTN_EN2 EXP1_07_PIN #define BTN_ENC EXP1_03_PIN - #define LCD_PINS_ENABLE EXP1_06_PIN + #define LCD_PINS_EN EXP1_06_PIN #define LCD_PINS_D4 EXP1_04_PIN #define BEEPER_PIN EXP1_01_PIN @@ -366,7 +374,7 @@ #define BTN_EN2 EXP1_05_PIN #define BTN_ENC EXP1_02_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(ENDER2_STOCKDISPLAY) @@ -394,26 +402,119 @@ #define LCD_BACKLIGHT_PIN -1 #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI - #define TFT_CS_PIN EXP1_07_PIN - #define TFT_A0_PIN EXP1_08_PIN - #define TFT_DC_PIN EXP1_08_PIN - #define TFT_MISO_PIN EXP2_01_PIN - #define TFT_BACKLIGHT_PIN EXP1_03_PIN - #define TFT_RESET_PIN EXP1_04_PIN - #define LCD_USE_DMA_SPI + #define SDCARD_CONNECTION ONBOARD + + #define BEEPER_PIN EXP1_01_PIN + + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + + #define TFT_A0_PIN TFT_DC_PIN + + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #if ENABLED(BTT_TFT35_SPI_V1_0) + + /** + * ------ ------ + * BEEPER | 1 2 | LCD-BTN MISO | 1 2 | CLK + * T_MOSI | 3 4 | T_CS LCD-ENCA | 3 4 | TFTCS + * T_CLK | 5 6 T_MISO LCD-ENCB | 5 6 MOSI + * PENIRQ | 7 8 | F_CS RS | 7 8 | RESET + * GND | 9 10 | VCC GND | 9 10 | NC + * ------ ------ + * EXP1 EXP2 + * + * 480x320, 3.5", SPI Display with Rotary Encoder. + * Stock Display for the BIQU B1 SE Series. + * Schematic: https://github.com/bigtreetech/TFT35-SPI/blob/master/v1/Hardware/BTT%20TFT35-SPI%20V1-SCH.pdf + */ + #define TFT_CS_PIN EXP2_04_PIN + #define TFT_DC_PIN EXP2_07_PIN + + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + + #define TOUCH_CS_PIN EXP1_04_PIN + #define TOUCH_SCK_PIN EXP1_05_PIN + #define TOUCH_MISO_PIN EXP1_06_PIN + #define TOUCH_MOSI_PIN EXP1_03_PIN + #define TOUCH_INT_PIN EXP1_07_PIN + + #elif ENABLED(MKS_TS35_V2_0) + + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! MKS_TS35_V2_0 requires wiring modifications. The SKR 1.4 EXP ports are rotated 180° from what the MKS_TS35_V2_0 expects. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this error.)" + #endif + + /** ------ ------ + * BEEPER | 1 2 | BTN_ENC SPI1_MISO | 1 2 | SPI1_SCK + * TFT_BKL / LCD_EN | 3 4 | TFT_RESET / LCD_RS BTN_EN1 | 3 4 | SPI1_CS + * TOUCH_CS / LCD_D4 | 5 6 TOUCH_INT / LCD_D5 BTN_EN2 | 5 6 SPI1_MOSI + * SPI1_CS / LCD_D6 | 7 8 | SPI1_RS / LCD_D7 SPI1_RS | 7 8 | RESET + * GND | 9 10 | VCC GND | 9 10 | VCC + * ------ ------ + * EXP1 EXP2 + */ + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_DC_PIN EXP1_08_PIN + + #define TFT_RESET_PIN EXP1_04_PIN + #define TFT_BACKLIGHT_PIN EXP1_03_PIN - #define TOUCH_INT_PIN EXP1_06_PIN - #define TOUCH_CS_PIN EXP1_05_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + //#define TFT_RST_PIN EXP2_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN - // SPI 1 - #define SD_SCK_PIN EXP2_02_PIN - #define SD_MISO_PIN EXP2_01_PIN - #define SD_MOSI_PIN EXP2_06_PIN + #define LCD_USE_DMA_SPI - #define TFT_BUFFER_SIZE 2400 + #define TFT_BUFFER_WORDS 2400 + + #define TOUCH_CS_PIN EXP1_05_PIN + #define TOUCH_INT_PIN EXP1_06_PIN + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #endif + + #if ENABLED(TFT_CLASSIC_UI) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X -16794 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 11000 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 1024 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -352 + #endif + + #elif ENABLED(TFT_COLOR_UI) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X -16741 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 11258 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 1024 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -367 + #endif + #define TFT_BUFFER_WORDS 2400 + #endif #elif IS_TFTGLCD_PANEL @@ -431,7 +532,7 @@ #define BTN_EN1 EXP2_03_PIN // (31) J3-2 & AUX-4 #define BTN_EN2 EXP2_05_PIN // (33) J3-4 & AUX-4 - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #define LCD_SDSS EXP2_04_PIN // (16) J3-7 & AUX-4 @@ -449,7 +550,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif @@ -463,7 +564,7 @@ #define NEOPIXEL_PIN EXP1_06_PIN #endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) #define DOGLCD_CS EXP1_06_PIN diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index ec74cc640e85..c7393e6546e5 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -27,8 +27,8 @@ // https://github.com/bigtreetech/BTT-Expansion-module/tree/master/BTT%20EXP-MOT //#define BTT_MOTOR_EXPANSION -#if BOTH(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) - #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) +#if ALL(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) + #if ANY(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) #define EXP_MOT_USE_EXP2_ONLY 1 #else #error "You can't use both an LCD and a Motor Expansion Module on EXP1/EXP2 at the same time." @@ -101,8 +101,8 @@ #define HEATER_1_PIN P2_04 #endif #endif -#ifndef FAN_PIN - #define FAN_PIN P2_03 +#ifndef FAN0_PIN + #define FAN0_PIN P2_03 #endif #ifndef HEATER_BED_PIN #define HEATER_BED_PIN P2_05 @@ -111,8 +111,9 @@ // // LCD / Controller // + #if !defined(BEEPER_PIN) && HAS_WIRED_LCD && DISABLED(LCD_USE_I2C_BUZZER) - #define BEEPER_PIN P1_30 // (37) not 5V tolerant + #define BEEPER_PIN P1_30 // (EXP1-1) Not 5V-tolerant #endif // diff --git a/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h b/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h index 9e62be8edb57..5c4e8d40e85b 100644 --- a/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h +++ b/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h @@ -87,7 +87,7 @@ #define HEATER_0_PIN P2_06 // (H2: 10A shared) #define HEATER_1_PIN P2_07 // (H3: 10A shared) -#define FAN_PIN P2_11 // (FAN0: 1A) +#define FAN0_PIN P2_11 // (FAN0: 1A) #define FAN1_PIN P2_13 // (FAN1: 1A) // @@ -138,6 +138,7 @@ // // LCD / Controller // + #if ENABLED(EMOTION_TECH_LCD) #define BEEPER_PIN EXP2_01_PIN #define DOGLCD_A0 EXP2_06_PIN diff --git a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h index aedbd7be606e..a9184073c5d6 100644 --- a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h +++ b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h @@ -106,7 +106,9 @@ #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif #else #error "TMC2208 UART configuration is required for GMarsh X6." #endif @@ -123,7 +125,7 @@ // #define HEATER_BED_PIN P1_19 // Not a PWM pin, software PWM required #define HEATER_0_PIN P3_26 // PWM1[3] -#define FAN_PIN P3_25 // Part cooling fan - connected to PWM1[2] +#define FAN0_PIN P3_25 // Part cooling fan - connected to PWM1[2] #define E0_AUTO_FAN_PIN P0_27 // Extruder cooling fan // @@ -141,7 +143,7 @@ #define BTN_EN2 P1_24 #define BTN_ENC P1_25 #define LCD_PINS_RS P0_20 - #define LCD_PINS_ENABLE P0_21 + #define LCD_PINS_EN P0_21 #define LCD_PINS_D4 P2_11 #define LCD_PINS_D5 P0_22 #define LCD_PINS_D6 P1_29 diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index 1c300cbcdb0f..fe21e1824e18 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -101,8 +101,8 @@ #define HEATER_BED_PIN P2_05 #define HEATER_0_PIN P2_07 #define HEATER_1_PIN P2_06 -#ifndef FAN_PIN - #define FAN_PIN P2_04 +#ifndef FAN0_PIN + #define FAN0_PIN P2_04 #endif // @@ -110,31 +110,25 @@ // Note: These pins are all digitally shared with the EXP1/EXP2 Connector. // Using them with an LCD connected or configured will lead to hangs & crashes. // - -// 5V -// NC -// GND -#define PIN_P0_17 P0_17 -#define PIN_P0_16 P0_16 -#define PIN_P0_15 P0_15 +//#define PIN_P0_17 P0_17 // 5V +//#define PIN_P0_16 P0_16 // NC +//#define PIN_P0_15 P0_15 // GND // // Connector J8 // - -// GND -#define PIN_P1_22 P1_22 -#define PIN_P1_23 P1_23 // PWM Capable -#define PIN_P2_12 P2_12 // Interrupt Capable -#define PIN_P2_11 P2_11 // Interrupt Capable +#define PIN_P1_22 P1_22 // GND +#define PIN_P1_23 P1_23 // PWM-capable +#define PIN_P2_12 P2_12 // Interrupt-capable +#define PIN_P2_11 P2_11 // Interrupt-capable // // Průša i3 MMU1 (Multi Material Multiplexer) Support // #if HAS_PRUSA_MMU1 - #define E_MUX0_PIN P1_23 // J8-3 - #define E_MUX1_PIN P2_12 // J8-4 - #define E_MUX2_PIN P2_11 // J8-5 + #define E_MUX0_PIN PIN_P1_23 // J8-3 + #define E_MUX1_PIN PIN_P2_12 // J8-4 + #define E_MUX2_PIN PIN_P2_11 // J8-5 #endif // @@ -170,21 +164,19 @@ #if SD_CONNECTION_IS(CUSTOM_CABLE) /** - * A custom cable is needed. See the README file in the - * Marlin\src\config\examples\Mks\Sbase directory - * P0.27 is on EXP2 and the on-board SD card's socket. That means it can't be - * used as the SD_DETECT for the LCD's SD card. + * A custom cable is needed. + * See https://github.com/MarlinFirmware/Configurations/blob/release-2.1/config/examples/Mks/Sbase/README.md + * P0.27 is on EXP2 and the on-board SD card socket so it can't be used as SD_DETECT for the LCD SD card. * - * The best solution is to use the custom cable to connect the LCD's SD_DETECT - * to a pin NOT on EXP2. + * The best solution is to use the custom cable to connect the LCD SD_DETECT to a pin NOT on EXP2. * - * If you can't find a pin to use for the LCD's SD_DETECT then comment out - * SD_DETECT_PIN entirely and remove that wire from the the custom cable. + * If you can't find a pin to use for the LCD SD_DETECT then comment out SD_DETECT_PIN and remove that wire + * from the the custom cable. */ - #define SD_DETECT_PIN P2_11 // J8-5 (moved from EXP2 P0.27) - #define SD_SCK_PIN P1_22 // J8-2 (moved from EXP2 P0.7) - #define SD_MISO_PIN P1_23 // J8-3 (moved from EXP2 P0.8) - #define SD_MOSI_PIN P2_12 // J8-4 (moved from EXP2 P0.9) + #define SD_DETECT_PIN PIN_P2_11 // J8-5 (moved from EXP2 P0.27) + #define SD_SCK_PIN PIN_P1_22 // J8-2 (moved from EXP2 P0.7) + #define SD_MISO_PIN PIN_P1_23 // J8-3 (moved from EXP2 P0.8) + #define SD_MOSI_PIN PIN_P2_12 // J8-4 (moved from EXP2 P0.9) #define SD_SS_PIN P0_28 #define SOFTWARE_SPI // With a custom cable we need software SPI because the // selected pins are not on a hardware SPI controller @@ -205,42 +197,53 @@ #endif /** - * Smart LCD adapter - * - * The Smart LCD adapter can be used for the two 10 pin LCD controllers such as - * REPRAP_DISCOUNT_SMART_CONTROLLER. It can't be used for controllers that use - * DOGLCD_A0, DOGLCD_CS, LCD_PINS_D5, LCD_PINS_D6 or LCD_PINS_D7. A custom cable - * is needed to pick up 5V for the EXP1 connection. - * - * SD card on the LCD uses the same SPI signals as the LCD. This results in garbage/lines - * on the LCD display during accesses of the SD card. The menus/code has been arranged so - * that the garbage/lines are erased immediately after the SD card accesses are completed. + * ------ ------ + * 1.31 | 1 2 | 1.30 0.08 | 1 2 | 0.07 + * 0.18 | 3 4 | 0.16 3.25 | 3 4 | 0.28 + * 0.15 | 5 6 -- 3.26 | 5 6 0.09 + * -- | 7 8 | -- 0.27 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- + * ------ ------ + * EXP1 EXP2 */ +#define EXP1_01_PIN P1_31 +#define EXP1_02_PIN P1_30 +#define EXP1_03_PIN P0_18 +#define EXP1_04_PIN P0_16 +#define EXP1_05_PIN P0_15 + +#define EXP2_01_PIN P0_08 +#define EXP2_02_PIN P0_07 +#define EXP2_03_PIN P3_25 +#define EXP2_04_PIN P0_28 +#define EXP2_05_PIN P3_26 +#define EXP2_06_PIN P0_09 +#define EXP2_07_PIN P0_27 // // LCD / Controller // + #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS P3_25 // EXP2.3 + #define TFTGLCD_CS EXP2_03_PIN #endif - #if SD_CONNECTION_IS(LCD) - #define SD_DETECT_PIN P0_28 // EXP2.4 + #define SD_DETECT_PIN EXP2_04_PIN #endif #elif HAS_WIRED_LCD - #define BEEPER_PIN P1_31 // EXP1.1 - #define BTN_ENC P1_30 // EXP1.2 - #define BTN_EN1 P3_26 // EXP2.5 - #define BTN_EN2 P3_25 // EXP2.3 - #define LCD_PINS_RS P0_16 // EXP1.4 - #define LCD_SDSS P0_28 // EXP2.4 - #define LCD_PINS_ENABLE P0_18 // EXP1.3 - #define LCD_PINS_D4 P0_15 // EXP1.5 - #if EITHER(VIKI2, miniVIKI) + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_SDSS EXP2_04_PIN + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #if ANY(VIKI2, miniVIKI) #define DOGLCD_SCK SD_SCK_PIN #define DOGLCD_MOSI SD_MOSI_PIN #endif @@ -257,26 +260,26 @@ * Pins 6, 7 & 8 on EXP2 are no connects. That means a second special * cable will be needed if the RGB LEDs are to be active. */ - #define DOGLCD_CS LCD_PINS_ENABLE // EXP1.3 (LCD_EN on FYSETC schematic) - #define DOGLCD_A0 LCD_PINS_RS // EXP1.4 (LCD_A0 on FYSETC schematic) - #define DOGLCD_SCK P2_11 // J8-5 (SCK on FYSETC schematic) + #define DOGLCD_CS EXP1_03_PIN // LCD_EN + #define DOGLCD_A0 EXP1_04_PIN // LCD_A0 + #define DOGLCD_SCK PIN_P2_11 // J8-5 (SCK on FYSETC schematic) #define DOGLCD_MOSI P4_28 // J8-6 (MOSI on FYSETC schematic) //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN P2_12 // J8-4 (LCD_D6 on FYSETC schematic) + #define RGB_LED_R_PIN PIN_P2_12 // J8-4 (LCD_D6 on FYSETC schematic) #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN P1_23 // J8-3 (LCD_D5 on FYSETC schematic) + #define RGB_LED_G_PIN PIN_P1_23 // J8-3 (LCD_D5 on FYSETC schematic) #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN P1_22 // J8-2 (LCD_D7 on FYSETC schematic) + #define RGB_LED_B_PIN PIN_P1_22 // J8-2 (LCD_D7 on FYSETC schematic) #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN P2_12 + #define NEOPIXEL_PIN PIN_P2_12 #endif #elif ENABLED(MINIPANEL) @@ -293,25 +296,23 @@ #if HAS_DRIVER(TMC2130) // J8 - #define X_CS_PIN P1_22 - #define Y_CS_PIN P1_23 - #define Z_CS_PIN P2_12 - #define E0_CS_PIN P2_11 + #define X_CS_PIN PIN_P1_22 + #define Y_CS_PIN PIN_P1_23 + #define Z_CS_PIN PIN_P2_12 + #define E0_CS_PIN PIN_P2_11 #define E1_CS_PIN P4_28 // Hardware SPI is on EXP2. See if you can make it work: // https://github.com/makerbase-mks/MKS-SBASE/issues/25 #define TMC_USE_SW_SPI - #if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P0_03 // AUX1 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_02 // AUX1 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_26 // TH4 - #endif + #ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P0_03 // AUX1 + #endif + #ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_02 // AUX1 + #endif + #ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_26 // TH4 #endif #endif @@ -325,21 +326,24 @@ * Worst case you may have to give up the LCD * RX pins need to be interrupt capable */ - #define X_SERIAL_TX_PIN P1_22 // J8-2 - #define X_SERIAL_RX_PIN P2_12 // J8-4 Interrupt Capable + #define X_SERIAL_TX_PIN PIN_P1_22 // J8-2 + #define X_SERIAL_RX_PIN PIN_P2_12 // J8-4 Interrupt Capable - #define Y_SERIAL_TX_PIN P1_23 // J8-3 - #define Y_SERIAL_RX_PIN P2_11 // J8-5 Interrupt Capable + #define Y_SERIAL_TX_PIN PIN_P1_23 // J8-3 + #define Y_SERIAL_RX_PIN PIN_P2_11 // J8-5 Interrupt Capable - #define Z_SERIAL_TX_PIN P2_12 // J8-4 + #define Z_SERIAL_TX_PIN PIN_P2_12 // J8-4 #define Z_SERIAL_RX_PIN P0_25 // TH3 #define E0_SERIAL_TX_PIN P4_28 // J8-6 #define E0_SERIAL_RX_PIN P0_26 // TH4 // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // UNUSED //#define PIN_P0_02 P0_02 // AUX1 (Interrupt Capable/ADC/Serial Port 0) diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index cdbc6d154fce..e507f7b7fa24 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -134,18 +134,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P4_28 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_05 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_04 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P4_28 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_05 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_04 #endif #if HAS_TMC_UART @@ -186,7 +184,10 @@ #define Z2_SERIAL_RX_PIN P1_17 // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + #endif // HAS_TMC_UART // @@ -211,8 +212,8 @@ #define HEATER_1_PIN P2_06 #endif #endif -#ifndef FAN_PIN - #define FAN_PIN P2_04 +#ifndef FAN0_PIN + #define FAN0_PIN P2_04 #endif // @@ -289,13 +290,13 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI #define TFT_CS_PIN EXP1_07_PIN - #define TFT_A0_PIN EXP1_08_PIN #define TFT_DC_PIN EXP1_08_PIN + #define TFT_A0_PIN TFT_DC_PIN #define TFT_MISO_PIN EXP2_01_PIN #define TFT_BACKLIGHT_PIN EXP1_03_PIN #define TFT_RESET_PIN EXP1_04_PIN @@ -308,11 +309,11 @@ #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 // Disable any LCD related PINs config - #define LCD_PINS_ENABLE -1 + #define LCD_PINS_EN -1 #define LCD_PINS_RS -1 - #ifndef TFT_BUFFER_SIZE - #define TFT_BUFFER_SIZE 1200 + #ifndef TFT_BUFFER_WORDS + #define TFT_BUFFER_WORDS 1200 #endif #ifndef TFT_QUEUE_SIZE #define TFT_QUEUE_SIZE 6144 @@ -349,11 +350,11 @@ #define LCD_PINS_D7 EXP1_08_PIN #define KILL_PIN -1 // NC - #else // !MKS_12864OLED_SSD1306 + #else // !MKS_12864OLED_SSD1306 #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -370,7 +371,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif @@ -384,7 +385,7 @@ #define NEOPIXEL_PIN EXP1_06_PIN #endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) #define DOGLCD_CS EXP1_06_PIN diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index 28d8d3cfb5ef..84c2eca91984 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -99,18 +99,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_00 // ETH - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P1_08 // ETH - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P1_09 // ETH - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P1_00 // ETH +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P1_08 // ETH +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P1_09 // ETH #endif #if HAS_TMC_UART @@ -121,7 +119,6 @@ * If undefined software serial is used according to the pins below */ - // P2_08 E1-Step // P2_13 E1-Dir @@ -154,8 +151,11 @@ #endif // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -167,7 +167,7 @@ #define TEMP_2_PIN P0_26_A3 // A3 - (63) - J5-3 & AUX-2 #define TEMP_3_PIN P1_30_A4 // A4 - (37) - BUZZER_PIN //#define TEMP_4_PIN P1_31_A5 // A5 - (49) - SD_DETECT_PIN -//#define ?? P0_03_A6 // A6 - ( 0) - RXD0 - J4-4 & AUX-1 +//#define PIN_P0_03 P0_03_A6 // A6 - ( 0) - RXD0 - J4-4 & AUX-1 #define FILWIDTH_PIN P0_02_A7 // A7 - ( 1) - TXD0 - J4-5 & AUX-1 // @@ -206,15 +206,15 @@ #endif #endif -#ifndef FAN_PIN - #if EITHER(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan - #define FAN_PIN MOSFET_B_PIN - #elif EITHER(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan - #define FAN_PIN MOSFET_C_PIN +#ifndef FAN0_PIN + #if ANY(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan + #define FAN0_PIN MOSFET_B_PIN + #elif ANY(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan + #define FAN0_PIN MOSFET_C_PIN #elif FET_ORDER_EEB // Hotend, Hotend, Bed - #define FAN_PIN P1_18 // (4) IO pin. Buffer needed + #define FAN0_PIN P1_18 // (4) IO pin. Buffer needed #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") - #define FAN_PIN MOSFET_B_PIN + #define FAN0_PIN MOSFET_B_PIN #endif #endif @@ -252,8 +252,8 @@ #error "LASER_FEATURE requires 3 free servo pins." #endif #endif - #define SPINDLE_LASER_ENA_PIN SERVO1_PIN // (6) Pin should have a pullup/pulldown! #define SPINDLE_LASER_PWM_PIN SERVO3_PIN // (4) MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENA_PIN SERVO1_PIN // (6) Pin should have a pullup/pulldown! #define SPINDLE_DIR_PIN SERVO2_PIN // (5) #endif @@ -293,18 +293,17 @@ #if ENABLED(CR10_STOCKDISPLAY) // Re-Arm can support Creality stock display without SD card reader and single cable on EXP3. - // Re-Arm J3 pins 1 (p1.31) & 2 (P3.26) are not used. Stock cable will need to have one + // Re-Arm J3 pins 1 (P1.31) & 2 (P3.26) are not used. Stock cable will need to have one // 10-pin IDC connector trimmed or replaced with a 12-pin IDC connector to fit J3. - // Requires REVERSE_ENCODER_DIRECTION in Configuration.h #define BEEPER_PIN P2_11 // J3-3 & AUX-4 - #define BTN_EN1 P0_16 // J3-7 & AUX-4 - #define BTN_EN2 P1_23 // J3-5 & AUX-4 + #define BTN_EN1 P1_23 // J3-5 & AUX-4 + #define BTN_EN2 P0_16 // J3-7 & AUX-4 #define BTN_ENC P3_25 // J3-4 & AUX-4 #define LCD_PINS_RS P0_15 // J3-9 & AUX-4 (CS) - #define LCD_PINS_ENABLE P0_18 // J3-10 & AUX-3 (SID, MOSI) + #define LCD_PINS_EN P0_18 // J3-10 & AUX-3 (SID, MOSI) #define LCD_PINS_D4 P2_06 // J3-8 & AUX-3 (SCK, CLK) #elif ENABLED(ZONESTAR_LCD) @@ -325,8 +324,8 @@ #elif HAS_WIRED_LCD #if ENABLED(FYSETC_MINI_12864) - #define BEEPER_PIN P1_01 - #define BTN_ENC P1_04 + #define BEEPER_PIN P1_01 // (79) J12-12 + #define BTN_ENC P1_04 // (77) J12-10 #else #define BEEPER_PIN P1_30 // (37) not 5V tolerant #define BTN_ENC P2_11 // (35) J3-3 & AUX-4 @@ -353,7 +352,7 @@ //#define SHIFT_EN_PIN P1_22 // (41) J5-4 & AUX-4 #endif - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define DOGLCD_CS P0_16 // (16) #define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2 #define DOGLCD_SCK P0_15 // (52) (SCK) J3-9 & AUX-3 @@ -367,18 +366,18 @@ #else #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_SCK P0_15 - #define DOGLCD_MOSI P0_18 + #define DOGLCD_SCK P0_15 // (52) (SCK) J3-9 & AUX-3 + #define DOGLCD_MOSI P0_18 // (51) (MOSI) J3-10 & AUX-3 // EXP1 on LCD adapter is not usable - using Ethernet connector instead - #define DOGLCD_CS P1_09 - #define DOGLCD_A0 P1_14 - //#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 DOGLCD_CS P1_09 // (74) J12-7 + #define DOGLCD_A0 P1_14 // (73) J12-6 + //#define FORCE_SOFT_SPI // Use this if Hardware SPI causes display problems. + // Results in LCD Software SPI mode 3, SD Software SPI mode 0. #define LCD_RESET_PIN P0_16 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN P1_00 #endif @@ -396,24 +395,22 @@ #define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2 #endif - #define LCD_BACKLIGHT_PIN P0_16 //(16) J3-7 & AUX-4 - only used on DOGLCD controllers - #define LCD_PINS_ENABLE P0_18 // (51) (MOSI) J3-10 & AUX-3 + #define LCD_BACKLIGHT_PIN P0_16 // (16) J3-7 & AUX-4 - only used on DOGLCD controllers + #define LCD_PINS_EN P0_18 // (51) (MOSI) J3-10 & AUX-3 #define LCD_PINS_D4 P0_15 // (52) (SCK) J3-9 & AUX-3 #if IS_ULTIPANEL #define LCD_PINS_D5 P1_17 // (71) ENET_MDIO #define LCD_PINS_D6 P1_14 // (73) ENET_RX_ER #define LCD_PINS_D7 P1_10 // (75) ENET_RXD1 - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif - #endif #endif #if ENABLED(MINIPANEL) //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 - #endif + #endif #endif // HAS_WIRED_LCD @@ -421,17 +418,17 @@ // Ethernet pins // #if !IS_ULTIPANEL - #define ENET_MDIO P1_17 // (71) J12-4 - #define ENET_RX_ER P1_14 // (73) J12-6 - #define ENET_RXD1 P1_10 // (75) J12-8 + #define ENET_MDIO P1_17 // (71) J12-4 + #define ENET_RX_ER P1_14 // (73) J12-6 + #define ENET_RXD1 P1_10 // (75) J12-8 #endif -#define ENET_MOC P1_16 // (70) J12-3 -#define REF_CLK P1_15 // (72) J12-5 -#define ENET_RXD0 P1_09 // (74) J12-7 -#define ENET_CRS P1_08 // (76) J12-9 -#define ENET_TX_EN P1_04 // (77) J12-10 -#define ENET_TXD0 P1_00 // (78) J12-11 -#define ENET_TXD1 P1_01 // (79) J12-12 +#define ENET_MOC P1_16 // (70) J12-3 +#define REF_CLK P1_15 // (72) J12-5 +#define ENET_RXD0 P1_09 // (74) J12-7 +#define ENET_CRS P1_08 // (76) J12-9 +#define ENET_TX_EN P1_04 // (77) J12-10 +#define ENET_TXD0 P1_00 // (78) J12-11 +#define ENET_TXD1 P1_01 // (79) J12-12 // // SD Support @@ -441,10 +438,10 @@ #endif #if SD_CONNECTION_IS(LCD) - #define SD_SCK_PIN P0_15 // (52) system defined J3-9 & AUX-3 - #define SD_MISO_PIN P0_17 // (50) system defined J3-10 & AUX-3 - #define SD_MOSI_PIN P0_18 // (51) system defined J3-10 & AUX-3 - #define SD_SS_PIN P1_23 // (53) system defined J3-5 & AUX-3 (Sometimes called SDSS) - CS used by Marlin + #define SD_SCK_PIN P0_15 // (52) System-defined J3-9 & AUX-3 + #define SD_MISO_PIN P0_17 // (50) System-defined J3-10 & AUX-3 + #define SD_MOSI_PIN P0_18 // (51) System-defined J3-10 & AUX-3 + #define SD_SS_PIN P1_23 // (53) System-defined J3-5 & AUX-3 (aka SDSS, CS) #elif SD_CONNECTION_IS(ONBOARD) #undef SD_DETECT_PIN #define SD_SCK_PIN P0_07 diff --git a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h index 30cd76b9a22d..16858c0b566a 100644 --- a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h +++ b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h @@ -87,8 +87,8 @@ #define HEATER_BED2_PIN P2_04 #define HEATER_0_PIN P2_07 #define HEATER_1_PIN P2_06 -#ifndef FAN_PIN - #define FAN_PIN P1_24 +#ifndef FAN0_PIN + #define FAN0_PIN P1_24 #endif #define FAN1_PIN P1_26 @@ -98,7 +98,7 @@ #if IS_RRD_FG_SC #define LCD_PINS_RS P0_16 - #define LCD_PINS_ENABLE P0_18 + #define LCD_PINS_EN P0_18 #define LCD_PINS_D4 P0_15 #define LCD_PINS_D5 P1_00 #define LCD_PINS_D6 P1_01 diff --git a/Marlin/src/pins/lpc1769/env_validate.h b/Marlin/src/pins/lpc1769/env_validate.h index 2e2b63d5203f..0f62412453a4 100644 --- a/Marlin/src/pins/lpc1769/env_validate.h +++ b/Marlin/src/pins/lpc1769/env_validate.h @@ -19,8 +19,11 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if NOT_TARGET(MCU_LPC1769) #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." #endif + +#endif diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h index a9c61cb8c9e6..8412f1c12d3b 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h @@ -100,16 +100,15 @@ #define HEATER_BED_PIN P2_07 #define HEATER_0_PIN P2_04 #define HEATER_1_PIN P2_05 -#ifndef FAN_PIN - #define FAN_PIN P0_26 +#ifndef FAN0_PIN + #define FAN0_PIN P0_26 #endif #define FAN1_PIN P1_22 // // Display // - -#if EITHER(VIKI2, miniVIKI) +#if ANY(VIKI2, miniVIKI) #define BEEPER_PIN P1_31 #define DOGLCD_A0 P2_06 #define DOGLCD_CS P0_16 diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h index eabb338504f8..f1753d0e2b95 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h @@ -33,7 +33,7 @@ #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "Azteeg X5 MINI" #endif -#define BOARD_WEBSITE_URL "tiny.cc/x5_mini" +#define BOARD_WEBSITE_URL "panucatt.com" // // LED @@ -56,11 +56,11 @@ #define Z_STOP_PIN P1_28 #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN P2_04 + #define FIL_RUNOUT_PIN _EXP1_09 #endif #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN P0_25_A2 // Analog Input (P0_25) + #define FILWIDTH_PIN _EXP1_04 // Analog Input (P0_25) #endif // @@ -104,11 +104,52 @@ // #define HEATER_BED_PIN P2_07 #define HEATER_0_PIN P2_05 -#ifndef FAN_PIN - #define FAN_PIN P0_26 +#ifndef FAN0_PIN + #define FAN0_PIN P0_26 #endif #define FAN1_PIN P1_25 +// +// Headers V1.1 - V3.0 +// +//#define _EXP1_01 -1 // GND +#define _EXP1_02 P1_03 +//#define _EXP1_03 -1 // 3.3V +#define _EXP1_04 P0_25_A2 +#define _EXP1_05 P0_27 // SDA0 +#define _EXP1_06 P4_29 +#define _EXP1_07 P0_28 // SCL0 +#define _EXP1_08 P2_08 +#define _EXP1_09 P2_04 +#define _EXP1_10 P1_22 + +#define _EXP2_01 P1_31 +#define _EXP2_02 P3_26 +#define _EXP2_03 P2_11 +#define _EXP2_04 P3_25 +#define _EXP2_05 P1_23 +#define _EXP2_06 P0_17 +#define _EXP2_07 P0_16 +#define _EXP2_08 P2_06 +#define _EXP2_09 P0_15 +#define _EXP2_10 P0_18 + +// +// Only V2.0 +// +//#define _J7_01 -1 // 3.3V +//#define _J7_02 -1 // GND +#define _J7_03 P1_16 +#define _J7_04 P1_17 +#define _J7_05 P1_15 +#define _J7_06 P0_14 +#define _J7_07 P1_09 +#define _J7_08 P1_10 +#define _J7_09 P1_08 +#define _J7_10 P1_04 +#define _J7_11 P1_00 +#define _J7_12 P1_01 + // // Display // @@ -121,61 +162,60 @@ // 10-pin IDC connector trimmed or replaced with a 12-pin IDC connector to fit J3. // Requires REVERSE_ENCODER_DIRECTION in Configuration.h - #define BEEPER_PIN P2_11 // J3-3 & AUX-4 + #define BEEPER_PIN _EXP2_03 - #define BTN_EN1 P0_16 // J3-7 & AUX-4 - #define BTN_EN2 P1_23 // J3-5 & AUX-4 - #define BTN_ENC P3_25 // J3-4 & AUX-4 + #define BTN_EN1 _EXP2_07 + #define BTN_EN2 _EXP2_05 + #define BTN_ENC _EXP2_04 - #define LCD_PINS_RS P0_15 // J3-9 & AUX-4 (CS) - #define LCD_PINS_ENABLE P0_18 // J3-10 & AUX-3 (SID, MOSI) - #define LCD_PINS_D4 P2_06 // J3-8 & AUX-3 (SCK, CLK) + #define LCD_PINS_RS _EXP2_09 + #define LCD_PINS_EN _EXP2_10 + #define LCD_PINS_D4 _EXP2_08 #else - #define BTN_EN1 P3_26 // (31) J3-2 & AUX-4 - #define BTN_EN2 P3_25 // (33) J3-4 & AUX-4 - #define BTN_ENC P2_11 // (35) J3-3 & AUX-4 + #define BTN_EN1 _EXP2_02 + #define BTN_EN2 _EXP2_04 + #define BTN_ENC _EXP2_03 - #define SD_DETECT_PIN P1_31 // (49) not 5V tolerant J3-1 & AUX-3 - #define KILL_PIN P1_22 // (41) J5-4 & AUX-4 - #define LCD_PINS_RS P0_16 // (16) J3-7 & AUX-4 - #define LCD_SDSS P0_16 // (16) J3-7 & AUX-4 - #define LCD_BACKLIGHT_PIN P0_16 // (16) J3-7 & AUX-4 - only used on DOGLCD controllers - #define LCD_PINS_ENABLE P0_18 // (51) (MOSI) J3-10 & AUX-3 - #define LCD_PINS_D4 P0_15 // (52) (SCK) J3-9 & AUX-3 + #define SD_DETECT_PIN _EXP2_01 + #define KILL_PIN _EXP1_10 + #define LCD_PINS_RS _EXP2_07 + #define LCD_SDSS _EXP2_07 + #define LCD_BACKLIGHT_PIN _EXP2_07 + #define LCD_PINS_EN _EXP2_10 + #define LCD_PINS_D4 _EXP2_09 - #define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2 + #define DOGLCD_A0 _EXP2_08 #if IS_RRW_KEYPAD - #define SHIFT_OUT_PIN P0_18 // (51) (MOSI) J3-10 & AUX-3 - #define SHIFT_CLK_PIN P0_15 // (52) (SCK) J3-9 & AUX-3 - #define SHIFT_LD_PIN P1_31 // (49) not 5V tolerant J3-1 & AUX-3 + #define SHIFT_OUT_PIN _EXP2_10 + #define SHIFT_CLK_PIN _EXP2_09 + #define SHIFT_LD_PIN _EXP2_01 #elif !IS_NEWPANEL - //#define SHIFT_OUT_PIN P2_11 // (35) J3-3 & AUX-4 - //#define SHIFT_CLK_PIN P3_26 // (31) J3-2 & AUX-4 - //#define SHIFT_LD_PIN P3_25 // (33) J3-4 & AUX-4 - //#define SHIFT_EN_PIN P1_22 // (41) J5-4 & AUX-4 + //#define SHIFT_OUT_PIN _EXP2_03 + //#define SHIFT_CLK_PIN _EXP2_02 + //#define SHIFT_LD_PIN _EXP2_04 + //#define SHIFT_EN_PIN _EXP1_10 #endif - #if EITHER(VIKI2, miniVIKI) - #define BEEPER_PIN P1_30 // (37) may change if cable changes - #define DOGLCD_CS P0_26 // (63) J5-3 & AUX-2 + #if ANY(VIKI2, miniVIKI) + #define BEEPER_PIN P1_30 + #define DOGLCD_CS P0_26 #define DOGLCD_SCK SD_SCK_PIN #define DOGLCD_MOSI SD_MOSI_PIN - #define STAT_LED_BLUE_PIN P0_26 // (63) may change if cable changes - #define STAT_LED_RED_PIN P1_21 // ( 6) may change if cable changes + #define STAT_LED_BLUE_PIN P0_26 + #define STAT_LED_RED_PIN P1_21 - //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #else #if IS_ULTIPANEL - #define LCD_PINS_D5 P1_17 // (71) ENET_MDIO - #define LCD_PINS_D6 P1_14 // (73) ENET_RX_ER - #define LCD_PINS_D7 P1_10 // (75) ENET_RXD1 + #define LCD_PINS_D5 P1_17 + #define LCD_PINS_D6 P1_14 + #define LCD_PINS_D7 P1_10 #endif - #define BEEPER_PIN P1_30 // (37) not 5V tolerant - #define DOGLCD_CS P0_16 // (16) + #define BEEPER_PIN P1_30 + #define DOGLCD_CS _EXP2_07 #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -183,7 +223,7 @@ #endif - #if ENABLED(MINIPANEL) + #if ANY(VIKI2, miniVIKI, MINIPANEL) //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #endif @@ -199,10 +239,10 @@ #endif #if SD_CONNECTION_IS(LCD) - #define SD_SCK_PIN P0_15 - #define SD_MISO_PIN P0_17 - #define SD_MOSI_PIN P0_18 - #define SD_SS_PIN P1_23 + #define SD_SCK_PIN _EXP2_09 + #define SD_MISO_PIN _EXP2_06 + #define SD_MOSI_PIN _EXP2_10 + #define SD_SS_PIN _EXP2_05 #elif SD_CONNECTION_IS(ONBOARD) #undef SD_DETECT_PIN #define SD_SCK_PIN P0_07 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 d9f56407e294..966ff5ef957f 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -153,8 +153,11 @@ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // TMC Low Power Standby pins @@ -171,7 +174,10 @@ #define TEMP_0_PIN P0_24 #define TEMP_1_PIN P0_23 #define TEMP_BED_PIN P0_25 -#define TEMP_BOARD_PIN P1_30 // Onboard thermistor, NTC100K + +#ifndef TEMP_BOARD_PIN + #define TEMP_BOARD_PIN P1_30 // Onboard thermistor, NTC100K +#endif // // Heaters / Fans @@ -179,7 +185,7 @@ #define HEATER_0_PIN P2_03 // EXTRUDER 0 #define HEATER_1_PIN P2_04 // EXTRUDER 1 #define HEATER_BED_PIN P2_05 // BED -#define FAN_PIN P2_01 +#define FAN0_PIN P2_01 #define FAN1_PIN P2_02 #ifndef CONTROLLER_FAN_PIN @@ -237,7 +243,7 @@ #define BTN_ENC EXP1_02_PIN #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! @@ -247,14 +253,14 @@ #endif #define LCD_PINS_RS EXP1_06_PIN - #define LCD_PINS_ENABLE EXP1_02_PIN + #define LCD_PINS_EN EXP1_02_PIN #define LCD_PINS_D4 EXP1_07_PIN #define LCD_PINS_D5 EXP1_05_PIN #define LCD_PINS_D6 EXP1_03_PIN #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN P1_23 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h index 03d681d333d1..70781cb0b588 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h @@ -72,16 +72,14 @@ // // Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_16 // Ethernet Expansion - Pin 5 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P1_17 // Ethernet Expansion - Pin 6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P1_08 // Ethernet Expansion - Pin 7 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P1_16 // Ethernet Expansion - Pin 5 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P1_17 // Ethernet Expansion - Pin 6 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P1_08 // Ethernet Expansion - Pin 7 #endif // @@ -96,8 +94,8 @@ // #define HEATER_BED_PIN P2_05 #define HEATER_0_PIN P2_07 // FET 1 -#ifndef FAN_PIN - #define FAN_PIN P2_06 // FET 3 +#ifndef FAN0_PIN + #define FAN0_PIN P2_06 // FET 3 #endif // @@ -127,7 +125,7 @@ #define SPINDLE_LASER_ENA_PIN P2_07 // FET 1 #undef HEATER_BED_PIN #define SPINDLE_LASER_PWM_PIN P2_05 // Bed FET - #undef FAN_PIN + #undef FAN0_PIN #define SPINDLE_DIR_PIN P2_06 // FET 3 #endif @@ -151,12 +149,12 @@ #define LCD_PINS_RS P0_16 // EXP1-4 #define LCD_SDSS P0_28 // EXP2-4 - #define LCD_PINS_ENABLE P0_18 // EXP1-3 + #define LCD_PINS_EN P0_18 // EXP1-3 #define LCD_PINS_D4 P0_15 // EXP1-5 #define KILL_PIN P2_11 // EXP2-10 - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA #error "SDSUPPORT is not currently supported by the Cohesion3D boards" #endif diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index e25a6688990a..a6acde35ffe3 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -89,16 +89,14 @@ // // Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_16 // Ethernet Expansion - Pin 5 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P1_17 // Ethernet Expansion - Pin 6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P1_08 // Ethernet Expansion - Pin 7 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P1_16 // Ethernet Expansion - Pin 5 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P1_17 // Ethernet Expansion - Pin 6 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P1_08 // Ethernet Expansion - Pin 7 #endif // @@ -121,8 +119,8 @@ #define HEATER_0_PIN P2_07 // FET 1 #define HEATER_1_PIN P1_23 // FET 2 #define HEATER_2_PIN P1_22 // FET 3 -#ifndef FAN_PIN - #define FAN_PIN P2_06 // FET 4 +#ifndef FAN0_PIN + #define FAN0_PIN P2_06 // FET 4 #endif // @@ -154,12 +152,43 @@ #if HAS_CUTTER #undef HEATER_0_PIN #undef HEATER_BED_PIN - #undef FAN_PIN - #define SPINDLE_LASER_ENA_PIN P2_07 // FET 1 + #undef FAN0_PIN #define SPINDLE_LASER_PWM_PIN P2_05 // Bed FET + #define SPINDLE_LASER_ENA_PIN P2_07 // FET 1 #define SPINDLE_DIR_PIN P2_06 // FET 4 #endif +/** ------ ------ + * (BEEPER) 1.31 | 1 2 | 1.30 (BTN_ENC) (MISO) 0.8 | 1 2 | 0.7 (SD_SCK) + * (EN) 0.18 | 3 4 | 0.16 (RS) (EN1) 3.26 | 3 4 | 0.28 (SD_CS2) + * (D4) 0.15 5 6 | -- (EN2) 3.25 5 6 | 0.9 (SD_MOSI) + * -- | 7 8 | 0.27 (D7) (SD_DET) 0.27 | 7 8 | 2.11 + * GND | 9 10 | 5V GND | 9 10 | -- + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_01_PIN P1_31 +#define EXP1_02_PIN P1_30 +#define EXP1_03_PIN P0_18 +#define EXP1_04_PIN P0_16 +#define EXP1_05_PIN P0_15 +#define EXP1_06_PIN -1 +#define EXP1_07_PIN -1 +#define EXP1_08_PIN P0_27 // (also on EXP2-7) +#define EXP1_09_PIN -1 +#define EXP1_10_PIN -1 + +#define EXP2_01_PIN P0_08 +#define EXP2_02_PIN P0_07 +#define EXP2_03_PIN P3_26 +#define EXP2_04_PIN P0_28 +#define EXP2_05_PIN P3_25 +#define EXP2_06_PIN P0_09 +#define EXP2_07_PIN P0_27 // (also on EXP1-8) +#define EXP2_08_PIN P2_11 +#define EXP2_09_PIN -1 +#define EXP2_10_PIN -1 + // // LCD / Controller // @@ -173,54 +202,54 @@ #if ENABLED(FYSETC_MINI_12864) - #define FORCE_SOFT_SPI // REQUIRED - results in LCD soft SPI mode 3 + #define FORCE_SOFT_SPI // REQUIRED. Results in LCD Software SPI mode 3 - #define BEEPER_PIN P1_31 // EXP1-1 - #define BTN_ENC P1_30 // EXP1-2 - #define DOGLCD_CS P0_18 // EXP1-3 - #define DOGLCD_A0 P0_16 // EXP1-4 - #define LCD_RESET_PIN P0_15 // EXP1-5 + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define LCD_RESET_PIN EXP1_05_PIN // A custom cable is REQUIRED for EXP2 cable because the SCK & MOSI on the card's EXP2 are dedicated // to the onboard SD card. All required EXP2 signals come from the Ethernet connector. Pin 1 of this // connector is the one nearest the motor power connector. - #define DOGLCD_SCK P1_17 // EXP2-2 => Ethernet pin 5 (bottom, 3 from left) - #define BTN_EN2 P1_09 // EXP2-3 => Ethernet pin 9 (bottom, 5 from left) - #define BTN_EN1 P1_04 // EXP2-5 => Ethernet pin 11 (bottom, 6 from left) - #define DOGLCD_MOSI P1_01 // EXP2-6 => Ethernet pin 13 (bottom, 7 from left) + #define DOGLCD_SCK P1_17 // LCD2-2 => Ethernet pin 5 (bottom, 3 from left) + #define BTN_EN2 P1_09 // LCD2-3 => Ethernet pin 9 (bottom, 5 from left) + #define BTN_EN1 P1_04 // LCD2-5 => Ethernet pin 11 (bottom, 6 from left) + #define DOGLCD_MOSI P1_01 // LCD2-6 => Ethernet pin 13 (bottom, 7 from left) // A custom EXP1 cable is required colored LEDs. Pins 1-5, 9, 10 of the cable go to pins 1-5, 9, 10 // on the board's EXP1 connector. Pins 6, 7, and 8 of the EXP1 cable go to the Ethernet connector. // Rev 1.2 displays do NOT require the RGB LEDs. 2.0 and 2.1 displays do require RGB. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN P1_16 // EXP1-6 => Ethernet pin 6 (top row, 3 from left) + #define RGB_LED_R_PIN P1_16 // LCD1-6 => Ethernet pin 6 (top row, 3 from left) #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN P1_10 // EXP1-7 => Ethernet pin 10 (top row, 5 from left) + #define RGB_LED_G_PIN P1_10 // LCD1-7 => Ethernet pin 10 (top row, 5 from left) #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN P1_00 // EXP1-8 => Ethernet pin 12 (top row, 6 from left) + #define RGB_LED_B_PIN P1_00 // LCD1-8 => Ethernet pin 12 (top row, 6 from left) #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN P1_16 // EXP1-6 => Ethernet pin 6 (top row, 3 from left) + #define NEOPIXEL_PIN P1_16 // LCD1-6 => Ethernet pin 6 (top row, 3 from left) #endif #elif HAS_WIRED_LCD - #define BEEPER_PIN P1_31 // EXP1-1 - //#define SD_DETECT_PIN P0_27 // EXP2-7 + #define BEEPER_PIN EXP1_01_PIN + //#define SD_DETECT_PIN EXP2_07_PIN - #define BTN_EN1 P3_26 // EXP2-5 - #define BTN_EN2 P3_25 // EXP2-3 - #define BTN_ENC P1_30 // EXP1-2 + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN - #define LCD_PINS_RS P0_16 // EXP1-4 - #define LCD_SDSS P0_28 // EXP2-4 - #define LCD_PINS_ENABLE P0_18 // EXP1-3 - #define LCD_PINS_D4 P0_15 // EXP1-5 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_SDSS EXP2_04_PIN + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN - #define KILL_PIN P2_11 // EXP2-10 + #define KILL_PIN EXP2_08_PIN #endif // HAS_WIRED_LCD @@ -232,11 +261,11 @@ #endif #if SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) - #define SD_SCK_PIN P0_07 // (52) system defined J3-9 & AUX-3 - #define SD_MISO_PIN P0_08 // (50) system defined J3-10 & AUX-3 - #define SD_MOSI_PIN P0_09 // (51) system defined J3-10 & AUX-3 + #define SD_SCK_PIN EXP2_02_PIN // (52) System-defined J3-9 & AUX-3 + #define SD_MISO_PIN EXP2_01_PIN // (50) System-defined J3-10 & AUX-3 + #define SD_MOSI_PIN EXP2_06_PIN // (51) System-defined J3-10 & AUX-3 #if SD_CONNECTION_IS(LCD) - #define SD_SS_PIN P1_23 // (53) system defined J3-5 & AUX-3 (Sometimes called SDSS) - CS used by Marlin + #define SD_SS_PIN P1_23 // (53) System-defined J3-5 & AUX-3 (Sometimes called SDSS) - CS used by Marlin #else #undef SD_DETECT_PIN #define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card @@ -259,30 +288,3 @@ //#define ENET_TX_EN P1_04 // Ethernet pin 11 (bottom, 6 from left) //#define ENET_TXD0 P1_00 // Ethernet pin 12 (top row, 6 from left) //#define ENET_TXD1 P1_01 // Ethernet pin 13 (bottom, 7 from left) - -/** - * EXP1 pins - * 1 - P1_31 - * 2 - P1_30 - * 3 - P0_18 - * 4 - P0_16 - * 5 - P0_15 - * 6 - N/C - * 7 - N/C - * 8 - P0_27 (also on EXP2-7) - * 9 - GND - * 10 - +5V - * - * - * EXP2 pins - * 1 - P0_08 - * 2 - P0_07 - * 3 - P3_26 - * 4 - P0_28 - * 5 - P3_25 - * 6 - P0_09 - * 7 - P0_27 (also on EXP1_8) - * 8 - P2_11 - * 9 - GND - * 10 - N/C - */ diff --git a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h index 1c0cb05892a7..d5a7a38c234d 100644 --- a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h +++ b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h @@ -94,18 +94,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P0_20 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_19 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_21 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P0_20 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_19 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_21 #endif #if HAS_TMC_UART @@ -128,8 +126,11 @@ #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -146,8 +147,8 @@ #define HEATER_0_PIN P3_25 #define HEATER_1_PIN P1_20 #define HEATER_2_PIN P1_23 -#ifndef FAN_PIN - #define FAN_PIN P1_18 +#ifndef FAN0_PIN + #define FAN0_PIN P1_18 #endif #define FAN1_PIN P1_21 #define FAN2_PIN P1_24 @@ -157,7 +158,7 @@ // #define BEEPER_PIN P2_07 #define LCD_PINS_RS P2_10 -#define LCD_PINS_ENABLE P0_22 +#define LCD_PINS_EN P0_22 #define LCD_PINS_D4 P1_19 #define LCD_PINS_D5 P2_08 #define LCD_PINS_D6 P1_30 diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h index 1e71fccfe5c5..5e552353cd31 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h @@ -56,5 +56,8 @@ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART 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 cf3b884683a9..1257f1805bf4 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -148,18 +148,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_16 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_05 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_04 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P1_16 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_05 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_04 #endif #if HAS_TMC_UART @@ -197,7 +195,10 @@ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + #endif // HAS_TMC_UART // @@ -231,8 +232,8 @@ #define FAN2_PIN P2_06 // HE1 for FAN3 #endif #endif -#ifndef FAN_PIN - #define FAN_PIN P2_04 // FAN1 +#ifndef FAN0_PIN + #define FAN0_PIN P2_04 // FAN1 #endif #ifndef FAN1_PIN #define FAN1_PIN P1_04 // FAN2 @@ -318,7 +319,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #else @@ -344,7 +345,7 @@ #define TFT_CS_PIN EXP1_07_PIN #define TFT_DC_PIN EXP1_08_PIN - #define TFT_A0_PIN TFT_DC_PIN + #define TFT_A0_PIN TFT_DC_PIN #define TFT_MISO_PIN EXP2_01_PIN #define TFT_BACKLIGHT_PIN EXP1_03_PIN #define TFT_RESET_PIN EXP1_04_PIN @@ -357,21 +358,21 @@ #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 // Disable any LCD related PINs config - #define LCD_PINS_ENABLE -1 + #define LCD_PINS_EN -1 #define LCD_PINS_RS -1 - #ifndef TFT_BUFFER_SIZE - #define TFT_BUFFER_SIZE 1200 + #ifndef TFT_BUFFER_WORDS + #define TFT_BUFFER_WORDS 1200 #endif #ifndef TFT_QUEUE_SIZE #define TFT_QUEUE_SIZE 6144 #endif - #else // !MKS_12864OLED_SSD1306 + #else // !MKS_12864OLED_SSD1306 #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -388,7 +389,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif @@ -402,7 +403,7 @@ #define NEOPIXEL_PIN EXP1_06_PIN #endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) #define DOGLCD_CS EXP1_06_PIN @@ -428,6 +429,9 @@ #endif // HAS_WIRED_LCD +// +// SD Card +// #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif diff --git a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h index 124c8f63c2e8..0134e936319d 100644 --- a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h @@ -85,15 +85,16 @@ #define HEATER_BED_PIN P2_05 #define HEATER_0_PIN P2_07 #define HEATER_1_PIN P1_23 -#ifndef FAN_PIN - #define FAN_PIN P2_06 +#ifndef FAN0_PIN + #define FAN0_PIN P2_06 #endif #define FAN1_PIN P2_04 // // LCD / Controller // -#if EITHER(VIKI2, miniVIKI) + +#if ANY(VIKI2, miniVIKI) #define BEEPER_PIN P1_31 #define DOGLCD_A0 P2_11 @@ -142,7 +143,7 @@ // EXP1 Pins #define BEEPER_PIN P1_31 // EXP1 Pin 1 #define BTN_ENC P1_30 // EXP1 Pin 2 - #define LCD_PINS_ENABLE P0_18 // EXP1 Pin 3 (MOSI) + #define LCD_PINS_EN P0_18 // EXP1 Pin 3 (MOSI) #define LCD_PINS_RS P0_16 // EXP1 Pin 4 (CS) #define LCD_PINS_D4 P0_15 // EXP1 Pin 5 (SCK) // EXP2 Pins diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index f39b0374c28a..634e50c223af 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -99,8 +99,11 @@ #define E0_SERIAL_RX_PIN P0_21 // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temp Sensors @@ -119,8 +122,8 @@ // #define HEATER_BED_PIN P2_05 #define HEATER_0_PIN P2_07 -#ifndef FAN_PIN - #define FAN_PIN P2_06 +#ifndef FAN0_PIN + #define FAN0_PIN P2_06 #endif #define FAN1_PIN P1_22 @@ -185,7 +188,7 @@ */ #define BEEPER_PIN EXP1_01_PIN #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #define KILL_PIN EXP1_04_PIN @@ -214,7 +217,7 @@ #endif -#if EITHER(CR10_STOCKDISPLAY, MKS_MINI_12864) +#if ANY(CR10_STOCKDISPLAY, MKS_MINI_12864) #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN #define BTN_ENC EXP1_02_PIN diff --git a/Marlin/src/pins/mega/env_validate.h b/Marlin/src/pins/mega/env_validate.h index 97c52d4e5e05..7b6462ab7a97 100644 --- a/Marlin/src/pins/mega/env_validate.h +++ b/Marlin/src/pins/mega/env_validate.h @@ -19,7 +19,8 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if NOT_TARGET(__AVR_ATmega2560__) #if DISABLED(ALLOW_MEGA1280) @@ -30,3 +31,5 @@ #endif #undef ALLOW_MEGA1280 + +#endif diff --git a/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h b/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h index e81295a6530a..62215a8224e0 100644 --- a/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h +++ b/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h @@ -86,8 +86,8 @@ #define HEATER_1_PIN 7 #define HEATER_2_PIN 8 #define HEATER_BED_PIN 9 -#ifndef FAN_PIN - #define FAN_PIN 3 +#ifndef FAN0_PIN + #define FAN0_PIN 3 #endif #define FAN2_PIN 58 // additional fan or light control output @@ -113,7 +113,7 @@ // LCD / Controller // #define LCD_PINS_RS 19 -#define LCD_PINS_ENABLE 42 +#define LCD_PINS_EN 42 #define LCD_PINS_D4 18 #define LCD_PINS_D5 38 #define LCD_PINS_D6 41 @@ -128,7 +128,7 @@ // #define BEEPER_PIN 44 -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #define SDSS 53 #define SD_DETECT_PIN 49 #endif diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h index d996635c8c94..1c0623aea866 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h @@ -93,8 +93,8 @@ #define HEATER_3_PIN 46 #define HEATER_BED_PIN 2 -#ifndef FAN_PIN - //#define FAN_PIN 7 // common PWM pin for all tools +#ifndef FAN0_PIN + //#define FAN0_PIN 7 // common PWM pin for all tools #endif // @@ -138,6 +138,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #define BEEPER_PIN 6 diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h index ea82fe429c33..4864a6d83c78 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h @@ -93,8 +93,8 @@ #define HEATER_3_PIN 3 #define HEATER_BED_PIN 24 -#ifndef FAN_PIN - #define FAN_PIN 5 // 5 is PWMtool3 -> 7 is common PWM pin for all tools +#ifndef FAN0_PIN + #define FAN0_PIN 5 // 5 is PWMtool3 -> 7 is common PWM pin for all tools #endif // @@ -143,6 +143,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #define BEEPER_PIN 16 diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h index c77e711f9c22..bbb0385844f9 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h @@ -87,7 +87,7 @@ // // Fans // -#define FAN_PIN 8 +#define FAN0_PIN 8 // // Auto fans diff --git a/Marlin/src/pins/mega/pins_EINSTART-S.h b/Marlin/src/pins/mega/pins_EINSTART-S.h index 274684f337d2..92c85c12110f 100644 --- a/Marlin/src/pins/mega/pins_EINSTART-S.h +++ b/Marlin/src/pins/mega/pins_EINSTART-S.h @@ -70,7 +70,7 @@ #define HEATER_0_PIN 83 #define HEATER_BED_PIN 38 -#define FAN_PIN 82 +#define FAN0_PIN 82 // // Misc. Functions @@ -78,12 +78,8 @@ #define SDSS 53 #define LED_PIN 4 -////////////////////////// -// LCDs and Controllers // -////////////////////////// - // -// LCD Display output pins +// LCD / Controller // // Requires #define U8GLIB_SH1106_EINSTART in Configuration.h diff --git a/Marlin/src/pins/mega/pins_ELEFU_3.h b/Marlin/src/pins/mega/pins_ELEFU_3.h index 6cf9e1b4e1af..71797a30fff8 100644 --- a/Marlin/src/pins/mega/pins_ELEFU_3.h +++ b/Marlin/src/pins/mega/pins_ELEFU_3.h @@ -92,8 +92,8 @@ #define HEATER_2_PIN 17 // 12V PWM3 #define HEATER_BED_PIN 44 // DOUBLE 12V PWM -#ifndef FAN_PIN - #define FAN_PIN 16 // 5V PWM +#ifndef FAN0_PIN + #define FAN0_PIN 16 // 5V PWM #endif // diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A.h b/Marlin/src/pins/mega/pins_GT2560_REV_A.h index bb251dfb4e18..55632e97bff4 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A.h @@ -47,14 +47,12 @@ #define Y_MAX_PIN 28 #define Z_MIN_PIN 30 -#if ENABLED(BLTOUCH) - #if MB(GT2560_REV_A_PLUS) - #define SERVO0_PIN 11 - #define Z_MAX_PIN 32 - #else - #define SERVO0_PIN 32 - #define Z_MAX_PIN -1 - #endif +#if ENABLED(BLTOUCH) && !defined(SERVO0_PIN) + #define SERVO0_PIN 32 +#endif + +#if SERVO0_PIN == 32 + #define Z_MAX_PIN -1 #else #define Z_MAX_PIN 32 #endif @@ -95,71 +93,107 @@ #define HEATER_0_PIN 2 #define HEATER_1_PIN 3 #define HEATER_BED_PIN 4 -#ifndef FAN_PIN - #define FAN_PIN 7 +#ifndef FAN0_PIN + #define FAN0_PIN 7 #endif // // Misc. Functions // -#define SDSS 53 + +// Power monitoring pins - set to 0 for main VIN, 1 for dedicated bed supply rail. +// Don't forget to enable POWER_MONITOR_VOLTAGE in Configuration_adv.h +// and set POWER_MONITOR_VOLTS_PER_VOLT to 0.090909. +#define POWER_MONITOR_VOLTAGE_PIN 0 + +/** LCD SDCARD + * ------ ------ + * (TX1) 18 | 1 2 | 19 (RX1) (MISO) 50 | 1 2 | 52 (SCK) + * (RX2) 17 | 3 4 | 20 (SDA) 42 | 3 4 | 53 (SS) + * (TX2) 16 | 5 6 21 (SCL) 40 | 5 6 51 (MOSI) + * 5 | 7 8 | 6 38 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 5V/3V3 + * ------ ------ + * SV1 SV3 + * + * GT2560 LCD & SD headers follow typical EXP1 & EXP2 format. + * SD header voltage pin set by link pads beneath the header; R25 for 5V, R44 for 3.3V (default) + * Pins 20 (SDA) and 21 (SCL) have external 10K pull-ups on the board. + */ + +#define EXP1_01_PIN 18 // TX1 / BEEPER +#define EXP1_02_PIN 19 // RX1 / ENC +#define EXP1_03_PIN 17 // RX2 / CS +#define EXP1_04_PIN 20 // SDA / A0 +#define EXP1_05_PIN 16 // TX2 / LCD_RS +#define EXP1_06_PIN 21 // SCL / CS +#define EXP1_07_PIN 5 // D6 / A0 +#define EXP1_08_PIN 6 // D7 / D4 + +#define EXP2_01_PIN 50 // MISO +#define EXP2_02_PIN 52 // SCK +#define EXP2_03_PIN 42 // EN2 +#define EXP2_04_PIN 53 // SDSS +#define EXP2_05_PIN 40 // EN1 +#define EXP2_06_PIN 51 // MOSI +#define EXP2_07_PIN 38 // SD_DET +#define EXP2_08_PIN -1 // RESET + +#define SDSS EXP2_04_PIN #define LED_PIN 13 -#define PS_ON_PIN 12 -#define SUICIDE_PIN 54 // Must be enabled at startup to keep power flowing -#define KILL_PIN -1 #if HAS_WIRED_LCD - #define BEEPER_PIN 18 + #define BEEPER_PIN EXP1_01_PIN #if IS_NEWPANEL #if ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 5 - #define DOGLCD_CS 21 - #define BTN_EN1 40 - #define BTN_EN2 42 + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN #elif ENABLED(FYSETC_MINI_12864) // Disconnect EXP2-1 and EXP2-2, otherwise future firmware upload won't work. - #define DOGLCD_A0 20 - #define DOGLCD_CS 17 + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN - #define NEOPIXEL_PIN 21 - #define BTN_EN1 42 - #define BTN_EN2 40 + #define NEOPIXEL_PIN EXP1_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_RESET_PIN 16 + #define LCD_RESET_PIN EXP1_05_PIN #define LCD_CONTRAST_INIT 220 #define LCD_BACKLIGHT_PIN -1 #else - #define LCD_PINS_RS 20 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 16 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 - #define BTN_EN1 42 - #define BTN_EN2 40 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #endif - #define BTN_ENC 19 - #define SD_DETECT_PIN 38 + #define BTN_ENC EXP1_02_PIN + #define SD_DETECT_PIN EXP2_07_PIN - #else // !IS_NEWPANEL + #else // !IS_NEWPANEL - #define SHIFT_CLK_PIN 38 - #define SHIFT_LD_PIN 42 - #define SHIFT_OUT_PIN 40 - #define SHIFT_EN_PIN 17 + #define SHIFT_CLK_PIN EXP2_07_PIN + #define SHIFT_LD_PIN EXP2_03_PIN + #define SHIFT_OUT_PIN EXP2_05_PIN + #define SHIFT_EN_PIN EXP1_03_PIN - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 5 - #define LCD_PINS_D4 6 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 20 - #define LCD_PINS_D7 19 + #define LCD_PINS_RS EXP1_05_PIN + #define LCD_PINS_EN EXP1_07_PIN + #define LCD_PINS_D4 EXP1_08_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_02_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h b/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h index a982a0e00e73..a90c075be57f 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h @@ -30,8 +30,6 @@ #define BOARD_INFO_NAME "GT2560 Rev.A+" -#include "pins_GT2560_REV_A.h" +#define SERVO0_PIN 11 -#if DISABLED(BLTOUCH) - #define SERVO0_PIN 32 -#endif +#include "pins_GT2560_REV_A.h" diff --git a/Marlin/src/pins/mega/pins_GT2560_V3.h b/Marlin/src/pins/mega/pins_GT2560_V3.h index 5d2436b68406..b684214c6964 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3.h @@ -33,6 +33,10 @@ #define ALLOW_MEGA1280 #include "env_validate.h" +#if HOTENDS > 3 || E_STEPPERS > 3 + #error "GT2560 supports up to 3 hotends / E steppers." +#endif + #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "GT2560 3.x" #endif @@ -91,7 +95,7 @@ #endif // -// Power Recovery +// Power Loss Detection // #define POWER_LOSS_PIN 69 // Pin to detect power loss #define POWER_LOSS_STATE LOW @@ -138,7 +142,7 @@ #define HEATER_1_PIN 3 #define HEATER_2_PIN 2 #define HEATER_BED_PIN 4 -#define FAN_PIN 9 +#define FAN0_PIN 9 #define FAN1_PIN 8 #define FAN2_PIN 7 @@ -164,24 +168,24 @@ #define BEEPER_PIN 18 #if ENABLED(YHCB2004) - #ifndef YHCB2004_CLK - #define YHCB2004_CLK 5 - #define DIO52 YHCB2004_CLK + #ifndef YHCB2004_MOSI_PIN + #define YHCB2004_MOSI_PIN 21 + #endif + #ifndef YHCB2004_MISO_PIN + #define YHCB2004_MISO_PIN 36 #endif - #ifndef YHCB2004_MOSI - #define YHCB2004_MOSI 21 - #define DIO50 YHCB2004_MOSI + #ifndef YHCB2004_SCK_PIN + #define YHCB2004_SCK_PIN 5 #endif - #ifndef YHCB2004_MISO - #define YHCB2004_MISO 36 - #define DIO51 YHCB2004_MISO + #ifndef YHCB2004_SS_PIN + #define YHCB2004_SS_PIN SS #endif #elif HAS_WIRED_LCD #ifndef LCD_PINS_RS #define LCD_PINS_RS 20 #endif - #ifndef LCD_PINS_ENABLE - #define LCD_PINS_ENABLE 17 + #ifndef LCD_PINS_EN + #define LCD_PINS_EN 17 #endif #ifndef LCD_PINS_D4 #define LCD_PINS_D4 16 diff --git a/Marlin/src/pins/mega/pins_GT2560_V3_A20.h b/Marlin/src/pins/mega/pins_GT2560_V3_A20.h index b5bf349eebf2..2422dfdd73e5 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3_A20.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3_A20.h @@ -26,12 +26,16 @@ * ATmega2560 */ -#define LCD_PINS_RS 5 -#define LCD_PINS_ENABLE 36 -#define LCD_PINS_D4 21 -#define LCD_PINS_D7 6 +#if HAS_WIRED_LCD + #define LCD_PINS_RS 5 + #define LCD_PINS_EN 36 + #define LCD_PINS_D4 21 + #define LCD_PINS_D7 6 +#endif -#define SPEAKER // The speaker can produce tones +#ifndef SPEAKER + #define SPEAKER // The speaker can produce tones +#endif #if IS_NEWPANEL #define BTN_EN1 16 diff --git a/Marlin/src/pins/mega/pins_GT2560_V4_A20.h b/Marlin/src/pins/mega/pins_GT2560_V4_A20.h index eeba1485d77b..405a3aba5bf8 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V4_A20.h +++ b/Marlin/src/pins/mega/pins_GT2560_V4_A20.h @@ -28,12 +28,16 @@ #define BOARD_INFO_NAME "GT2560 4.x" -#define LCD_PINS_RS 5 -#define LCD_PINS_ENABLE 36 -#define LCD_PINS_D4 21 -#define LCD_PINS_D7 6 +#if HAS_WIRED_LCD + #define LCD_PINS_RS 5 + #define LCD_PINS_EN 36 + #define LCD_PINS_D4 21 + #define LCD_PINS_D7 6 +#endif -#define SPEAKER // The speaker can produce tones +#ifndef SPEAKER + #define SPEAKER // The speaker can produce tones +#endif #if IS_NEWPANEL #define BTN_EN1 16 diff --git a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h index 1b3b7b29afe6..638465f3b9eb 100644 --- a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h +++ b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h @@ -92,8 +92,8 @@ #define HEATER_1_PIN 3 #define HEATER_BED_PIN 4 -#ifndef FAN_PIN - #define FAN_PIN 7 //默认不使用PWM_FAN冷却喷嘴,如果需要,则取消注释 +#ifndef FAN0_PIN + #define FAN0_PIN 7 //默认不使用PWM_FAN冷却喷嘴,如果需要,则取消注释 #endif // @@ -114,14 +114,15 @@ // M3/M4/M5 - Spindle/Laser Control // #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 + #define SPINDLE_LASER_ENA_PIN 17 // Pin should have a pullup! + #define SPINDLE_DIR_PIN 16 #endif // // LCD / Controller // + #if HAS_WIRED_LCD #define BEEPER_PIN 18 @@ -129,7 +130,7 @@ #if IS_NEWPANEL #define LCD_PINS_RS 20 // LCD_CS - #define LCD_PINS_ENABLE 15 // LCD_SDA + #define LCD_PINS_EN 15 // LCD_SDA #define LCD_PINS_D4 14 // LCD_SCK #if ENABLED(HJC_LCD_SMART_CONTROLLER) @@ -161,7 +162,7 @@ #define SHIFT_EN_PIN 17 #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 5 + #define LCD_PINS_EN 5 #define LCD_PINS_D4 6 #define LCD_PINS_D5 21 #define LCD_PINS_D6 20 diff --git a/Marlin/src/pins/mega/pins_INTAMSYS40.h b/Marlin/src/pins/mega/pins_INTAMSYS40.h index ec466fb09faa..6b8296506552 100644 --- a/Marlin/src/pins/mega/pins_INTAMSYS40.h +++ b/Marlin/src/pins/mega/pins_INTAMSYS40.h @@ -99,7 +99,7 @@ #define HEATER_0_PIN 2 // PWM #define HEATER_BED_PIN 4 // PWM #define HEATER_CHAMBER_PIN 3 // PWM -#define FAN_PIN 7 // PWM +#define FAN0_PIN 7 // PWM // // Misc. Functions @@ -123,7 +123,7 @@ #if HAS_WIRED_LCD #define LCD_PINS_RS 20 - #define LCD_PINS_ENABLE 30 + #define LCD_PINS_EN 30 #define LCD_PINS_D4 14 #define LCD_PINS_D5 21 #define LCD_PINS_D6 5 diff --git a/Marlin/src/pins/mega/pins_LEAPFROG.h b/Marlin/src/pins/mega/pins_LEAPFROG.h index 3762ea98f051..d986728e7273 100644 --- a/Marlin/src/pins/mega/pins_LEAPFROG.h +++ b/Marlin/src/pins/mega/pins_LEAPFROG.h @@ -79,7 +79,7 @@ #define HEATER_2_PIN 11 // 13 #define HEATER_BED_PIN 10 // 14/15 -#define FAN_PIN 7 +#define FAN0_PIN 7 // // Misc. Functions diff --git a/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h b/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h index 7be96c5defc5..7b3cb2b723db 100644 --- a/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h +++ b/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h @@ -104,7 +104,7 @@ #define HEATER_1_PIN 9 // Misc Connector, pins 5 and 6 (Out3) #define HEATER_BED_PIN 6 // Misc Connector, pins 9(-) and 10(+) (OutA) -#define FAN_PIN 10 // Misc Connector, pins 7(-) and 8 (+) (Out4) +#define FAN0_PIN 10 // Misc Connector, pins 7(-) and 8 (+) (Out4) #define LED_PIN 13 diff --git a/Marlin/src/pins/mega/pins_MALYAN_M180.h b/Marlin/src/pins/mega/pins_MALYAN_M180.h index 3ef606de7723..a4bc98a14706 100644 --- a/Marlin/src/pins/mega/pins_MALYAN_M180.h +++ b/Marlin/src/pins/mega/pins_MALYAN_M180.h @@ -93,10 +93,9 @@ #define HEATER_1_PIN 11 #define HEATER_BED_PIN 45 -#ifndef FAN_PIN - #define FAN_PIN 7 // M106 Sxxx command supported and tested. M107 as well. +#ifndef FAN0_PIN + #define FAN0_PIN 7 // M106 Sxxx command supported and tested. M107 as well. #endif - -#ifndef FAN_PIN1 - #define FAN_PIN1 12 // Currently Unsupported by Marlin +#ifndef FAN1_PIN + #define FAN1_PIN 12 // Currently Unsupported by Marlin #endif diff --git a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h index f45da25f623a..688c147a6890 100644 --- a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h +++ b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h @@ -114,8 +114,8 @@ #define HEATER_1_PIN 34 #define HEATER_BED_PIN 28 -#ifndef FAN_PIN - #define FAN_PIN 39 +#ifndef FAN0_PIN + #define FAN0_PIN 39 #endif #define FAN1_PIN 35 #define FAN2_PIN 36 @@ -129,31 +129,60 @@ // // Misc. Functions // -#define SDSS 53 +#define SDSS MINI_06 #define LED_PIN 13 #ifndef CASE_LIGHT_PIN #define CASE_LIGHT_PIN 2 #endif +/** + * MegaController LCD/SD Connector + * + * SDD MOSI SDSS -- RESET -- LCDSS A0 KILL ENC + * 49 51 53 | 45 47 12 10 + * PL0 PB2 PB0 | PL4 PL2 PB6 PB4 + * ---------------------------------------------------------- + * | 2 4 6 8 10 12 14 16 18 20 | + * | 1 3 5 7 9 11 13 15 17 19 | + * ---------------------------------------------------------- + * | PB3 PB1 | | PL5 PL3 PL1 PB5 + * | 50 52 | | 44 46 48 11 + * 5V MISO SCK GND 3V3 -- BL BEEP EN1 EN2 + */ +#define MINI_02 49 // SD_DETECT +#define MINI_03 50 // MISO +#define MINI_04 51 // MOSI +#define MINI_05 52 // SCK +#define MINI_06 53 // SDSS +#define MINI_13 44 // BACKLIGHT +#define MINI_14 45 // LCDSS +#define MINI_15 46 // BEEP +#define MINI_16 47 // A0 +#define MINI_17 48 // EN1 +#define MINI_18 12 // KILL +#define MINI_19 11 // EN2 +#define MINI_20 10 // ENC + // // LCD / Controller // + #if ENABLED(MINIPANEL) - #define BEEPER_PIN 46 + #define BEEPER_PIN MINI_15 - #define DOGLCD_A0 47 - #define DOGLCD_CS 45 - #define LCD_BACKLIGHT_PIN 44 // backlight LED on PA3 + #define DOGLCD_A0 MINI_16 + #define DOGLCD_CS MINI_14 + #define LCD_BACKLIGHT_PIN MINI_13 // backlight LED on PA3 - #define KILL_PIN 12 + #define KILL_PIN MINI_18 - #define BTN_EN1 48 - #define BTN_EN2 11 - #define BTN_ENC 10 + #define BTN_ENC MINI_20 + #define BTN_EN1 MINI_17 + #define BTN_EN2 MINI_19 - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN MINI_02 //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 @@ -162,6 +191,8 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 7 // Pullup! -#define SPINDLE_DIR_PIN 8 +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 7 // Pullup! + #define SPINDLE_DIR_PIN 8 +#endif diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS.h b/Marlin/src/pins/mega/pins_MEGATRONICS.h index a51615e3d91e..066b577c629b 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS.h @@ -89,8 +89,8 @@ #define HEATER_1_PIN 8 #define HEATER_BED_PIN 10 -#ifndef FAN_PIN - #define FAN_PIN 7 // IO pin. Buffer needed +#ifndef FAN0_PIN + #define FAN0_PIN 7 // IO pin. Buffer needed #endif // @@ -112,7 +112,7 @@ #if HAS_WIRED_LCD && IS_NEWPANEL #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_EN 17 #define LCD_PINS_D4 23 #define LCD_PINS_D5 25 #define LCD_PINS_D6 27 @@ -130,6 +130,8 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 3 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 4 // Pullup! -#define SPINDLE_DIR_PIN 11 +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 3 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup! + #define SPINDLE_DIR_PIN 11 +#endif diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h index 3f7afe562b72..ff118e732315 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h @@ -103,8 +103,8 @@ #define HEATER_1_PIN 8 #define HEATER_BED_PIN 10 -#ifndef FAN_PIN - #define FAN_PIN 7 +#ifndef FAN0_PIN + #define FAN0_PIN 7 #endif #define FAN1_PIN 6 @@ -122,9 +122,11 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 3 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 16 // Pullup! -#define SPINDLE_DIR_PIN 11 +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 3 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 16 // Pullup! + #define SPINDLE_DIR_PIN 11 +#endif // // LCD / Controller @@ -134,7 +136,7 @@ #if HAS_WIRED_LCD #define LCD_PINS_RS 14 - #define LCD_PINS_ENABLE 15 + #define LCD_PINS_EN 15 #define LCD_PINS_D4 30 #define LCD_PINS_D5 31 #define LCD_PINS_D6 32 diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h index b194c31b5d91..5e571d5a3fa2 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h @@ -127,8 +127,8 @@ #define HEATER_2_PIN 8 #define HEATER_BED_PIN 10 -#ifndef FAN_PIN - #define FAN_PIN 6 +#ifndef FAN0_PIN + #define FAN0_PIN 6 #endif #define FAN1_PIN 7 @@ -155,14 +155,14 @@ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) #define LCD_PINS_RS 56 // CS chip select / SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) + #define LCD_PINS_EN 51 // SID (MOSI) #define LCD_PINS_D4 52 // SCK (CLK) clock #define SD_DETECT_PIN 35 #else #define LCD_PINS_RS 32 - #define LCD_PINS_ENABLE 31 + #define LCD_PINS_EN 31 #define LCD_PINS_D4 14 #define LCD_PINS_D5 30 #define LCD_PINS_D6 39 diff --git a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h index db41ef75d557..22c14fc5e89e 100644 --- a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h @@ -146,39 +146,34 @@ //#define TEMP_1_MOSI_PIN TEMP_0_MOSI_PIN // -// FET Pin Mapping - FET 1 is closest to the input power connector +// FET Pin Mapping - FET A is closest to the input power connector // -#define MOSFET_1_PIN 6 // Plug EX1 Pin 1-2 -> PH3 #15 -> Logical 06 -#define MOSFET_2_PIN 7 // Plug EX1 Pin 3-4 -> PH4 #16 -> Logical 07 -#define MOSFET_3_PIN 11 // Plug EX2 1-2 -> PB5 #24 -> Logical 11 -#define MOSFET_4_PIN 12 // Plug EX2 3-4 -> PB6 #25 -> Logical 12 -#define MOSFET_5_PIN 45 // Plug HBD 1-2 -> PL4 #39 -> Logical 45 -#define MOSFET_6_PIN 44 // Plug Extra 1-2 -> PL5 #40 -> Logical 44 (FET not soldered in all boards) +#define MOSFET_A_PIN 6 // Plug EX1 Pin 1-2 -> PH3 #15 -> Logical 06 +#define MOSFET_B_PIN 11 // Plug EX2 1-2 -> PB5 #24 -> Logical 11 +#define MOSFET_C_PIN 45 // Plug HBD 1-2 -> PL4 #39 -> Logical 45 +#define MOSFET_D_PIN 7 // Plug EX1 Pin 3-4 -> PH4 #16 -> Logical 07 +#define MOSFET_E_PIN 12 // Plug EX2 3-4 -> PB6 #25 -> Logical 12 +#define MOSFET_F_PIN 44 // Plug Extra 1-2 -> PL5 #40 -> Logical 44 (FET not soldered in all boards) // // Heaters / Fans (24V) // -#define HEATER_0_PIN MOSFET_1_PIN // EX1 -#define HEATER_1_PIN MOSFET_3_PIN // EX2 -#define HEATER_BED_PIN MOSFET_5_PIN // HBP +#define HEATER_0_PIN MOSFET_A_PIN // EX1 +#define HEATER_1_PIN MOSFET_B_PIN // EX2 +#define HEATER_BED_PIN MOSFET_C_PIN // HBP -// EX1 FAN (Automatic Fans are disabled by default in Configuration_adv.h - comment that out for auto fans) #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN MOSFET_2_PIN -#else - #ifndef FAN_PIN - #define FAN_PIN MOSFET_2_PIN - #endif + #define E0_AUTO_FAN_PIN MOSFET_D_PIN +#elif !defined(FAN0_PIN) + #define FAN0_PIN MOSFET_D_PIN #endif -// EX2 FAN (Automatic Fans are disabled by default in Configuration_adv.h - comment that out for auto fans) + #ifndef E1_AUTO_FAN_PIN - #define E1_AUTO_FAN_PIN MOSFET_4_PIN -#else - #ifndef FAN1_PIN - #define FAN1_PIN MOSFET_4_PIN - #endif + #define E1_AUTO_FAN_PIN MOSFET_E_PIN +#elif !defined(FAN1_PIN) + #define FAN1_PIN MOSFET_E_PIN #endif // @@ -192,12 +187,13 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #if IS_RRD_FG_SC #define LCD_PINS_RS 33 // C4: LCD-STROBE - #define LCD_PINS_ENABLE 72 // J2: LEFT + #define LCD_PINS_EN 72 // J2: LEFT #define LCD_PINS_D4 35 // C2: LCD-CLK #define LCD_PINS_D5 32 // C5: RLED #define LCD_PINS_D6 34 // C3: LCD-DATA diff --git a/Marlin/src/pins/mega/pins_MINITRONICS.h b/Marlin/src/pins/mega/pins_MINITRONICS.h index ddf6d2047deb..c8828faea7ab 100644 --- a/Marlin/src/pins/mega/pins_MINITRONICS.h +++ b/Marlin/src/pins/mega/pins_MINITRONICS.h @@ -90,8 +90,8 @@ #define HEATER_1_PIN 8 // EXTRUDER 2 #define HEATER_BED_PIN 3 // BED -#ifndef FAN_PIN - #define FAN_PIN 9 +#ifndef FAN0_PIN + #define FAN0_PIN 9 #endif // @@ -108,7 +108,7 @@ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) #define LCD_PINS_RS 15 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 11 // SID (MOSI) + #define LCD_PINS_EN 11 // SID (MOSI) #define LCD_PINS_D4 10 // SCK (CLK) clock #define BTN_EN1 18 @@ -120,7 +120,7 @@ #else #define LCD_PINS_RS -1 - #define LCD_PINS_ENABLE -1 + #define LCD_PINS_EN -1 // Buttons are directly attached using keypad #define BTN_EN1 -1 @@ -141,7 +141,7 @@ #define HEATER_BED_PIN 4 // won't compile #define TEMP_BED_PIN 50 #define TEMP_0_PIN 51 - #define SPINDLE_LASER_ENA_PIN 52 // using A6 because it already has a pullup #define SPINDLE_LASER_PWM_PIN 3 // WARNING - LED & resistor pull up to +12/+24V stepper voltage + #define SPINDLE_LASER_ENA_PIN 52 // using A6 because it already has a pullup #define SPINDLE_DIR_PIN 53 #endif diff --git a/Marlin/src/pins/mega/pins_OVERLORD.h b/Marlin/src/pins/mega/pins_OVERLORD.h index 01c02dafe24f..332d7d4cb4dc 100644 --- a/Marlin/src/pins/mega/pins_OVERLORD.h +++ b/Marlin/src/pins/mega/pins_OVERLORD.h @@ -95,7 +95,7 @@ #define HEATER_1_PIN 3 #define HEATER_BED_PIN 4 -#define FAN_PIN 7 // material cooling fan +#define FAN0_PIN 7 // material cooling fan // // SD Card @@ -122,11 +122,12 @@ // // LCD / Controller // + #if HAS_WIRED_LCD // OVERLORD OLED pins #define LCD_PINS_RS 20 #define LCD_PINS_D5 21 - #define LCD_PINS_ENABLE 15 + #define LCD_PINS_EN 15 #define LCD_PINS_D4 14 #define LCD_PINS_D6 5 #define LCD_PINS_D7 6 diff --git a/Marlin/src/pins/mega/pins_PICA.h b/Marlin/src/pins/mega/pins_PICA.h index 109859388c60..0a6478439c58 100644 --- a/Marlin/src/pins/mega/pins_PICA.h +++ b/Marlin/src/pins/mega/pins_PICA.h @@ -35,19 +35,14 @@ #include "env_validate.h" +#if HOTENDS > 2 || E_STEPPERS > 2 + #error "PICA supports up to 2 hotends / E steppers." +#endif + #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "PICA" #endif -/* -// Note that these are the "pins" that correspond to the analog inputs on the arduino mega. -// These are not the same as the physical pin numbers - AD0 = 54; AD1 = 55; AD2 = 56; AD3 = 57; - AD4 = 58; AD5 = 59; AD6 = 60; AD7 = 61; - AD8 = 62; AD9 = 63; AD10 = 64; AD11 = 65; - AD12 = 66; AD13 = 67; AD14 = 68; AD15 = 69; -*/ - // // Servos // @@ -108,8 +103,8 @@ #endif #define HEATER_BED_PIN 8 // HEAT-BED -#ifndef FAN_PIN - #define FAN_PIN 9 +#ifndef FAN0_PIN + #define FAN0_PIN 9 #endif #ifndef FAN_2_PIN #define FAN_2_PIN 7 @@ -123,7 +118,7 @@ #define SSR_PIN 6 // SPI for MAX Thermocouple -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) @@ -132,25 +127,53 @@ // // SD Support // -#define SD_DETECT_PIN 49 -#define SDSS 53 +#define SD_DETECT_PIN EXP2_07_PIN +#define SDSS EXP2_04_PIN + +/** PICA Expansion Headers + * ------ ------ + * (BEEP) 29 | 1 2 | 31 (ENC) (MISO) 50 | 1 2 | 52 (SCK) + * (LCD_EN) 30 | 3 4 | 33 (LCD_RS) (EN1) 47 | 3 4 | 53 (SDSS) + * (LCD_D4) 35 5 6 | 32 (LCD_D5) (EN2) 48 5 6 | 51 (MOSI) + * (LCD_D6) 37 | 7 8 | 36 (LCD_D7) (SDDET) 49 | 7 8 | 41 (KILL) + * GND | 9 10 | 5V -- | 9 10 | -- + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_01_PIN 29 // BEEPER +#define EXP1_02_PIN 31 // ENC +#define EXP1_03_PIN 30 // LCD_EN +#define EXP1_04_PIN 33 // LCD_RS +#define EXP1_05_PIN 35 // LCD_D4 +#define EXP1_06_PIN 32 // LCD_D5 +#define EXP1_07_PIN 37 // LCD_D6 +#define EXP1_08_PIN 36 // LCD_D7 + +#define EXP2_01_PIN 50 // MISO +#define EXP2_02_PIN 52 // SCK +#define EXP2_03_PIN 47 // EN1 +#define EXP2_04_PIN 53 // SDSS +#define EXP2_05_PIN 48 // EN2 +#define EXP2_06_PIN 51 // MOSI +#define EXP2_07_PIN 49 // SDDET +#define EXP2_08_PIN 41 // KILL // // LCD / Controller // -#define BEEPER_PIN 29 +#define BEEPER_PIN EXP1_01_PIN #if HAS_WIRED_LCD - #define LCD_PINS_RS 33 - #define LCD_PINS_ENABLE 30 - #define LCD_PINS_D4 35 - #define LCD_PINS_D5 32 - #define LCD_PINS_D6 37 - #define LCD_PINS_D7 36 - - #define BTN_EN1 47 - #define BTN_EN2 48 - #define BTN_ENC 31 - - #define LCD_SDSS 53 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN + + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN + + #define LCD_SDSS EXP2_04_PIN #endif diff --git a/Marlin/src/pins/mega/pins_PICAOLD.h b/Marlin/src/pins/mega/pins_PICAOLD.h index 961462fc5279..3654a45d3fdd 100644 --- a/Marlin/src/pins/mega/pins_PICAOLD.h +++ b/Marlin/src/pins/mega/pins_PICAOLD.h @@ -25,9 +25,9 @@ // Origin: https://github.com/mjrice/PICA/blob/97ab9e7771a8e5eef97788f3adcc17a9fa9de9b9/pica_schematic.pdf // ATmega2560 -#define HEATER_0_PIN 9 // E0 -#define HEATER_1_PIN 10 // E1 -#define FAN_PIN 11 -#define FAN2_PIN 12 +#define HEATER_0_PIN 9 // E0 +#define HEATER_1_PIN 10 // E1 +#define FAN0_PIN 11 +#define FAN2_PIN 12 #include "pins_PICA.h" diff --git a/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h b/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h index 18e2c0f64747..962fddc19248 100644 --- a/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h +++ b/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h @@ -54,16 +54,16 @@ #define Y_STEP_PIN 3 #define Y_DIR_PIN 6 -#define Y_ENABLE_PIN X_ENABLE_PIN +#define Y_ENABLE_PIN X_ENABLE_PIN #define Z_STEP_PIN 4 #define Z_DIR_PIN 7 -#define Z_ENABLE_PIN X_ENABLE_PIN +#define Z_ENABLE_PIN X_ENABLE_PIN // Designated with letter "A" on BOARD #define E0_STEP_PIN 12 #define E0_DIR_PIN 13 -#define E0_ENABLE_PIN X_ENABLE_PIN +#define E0_ENABLE_PIN X_ENABLE_PIN // // Temperature sensors - These could be any analog output not hidden by board diff --git a/Marlin/src/pins/mega/pins_SILVER_GATE.h b/Marlin/src/pins/mega/pins_SILVER_GATE.h index 18ada3aa251b..d739157aaf4e 100644 --- a/Marlin/src/pins/mega/pins_SILVER_GATE.h +++ b/Marlin/src/pins/mega/pins_SILVER_GATE.h @@ -57,8 +57,8 @@ #define FIL_RUNOUT_PIN 34 // X_MAX unless overridden #endif -#ifndef FAN_PIN - #define FAN_PIN 5 +#ifndef FAN0_PIN + #define FAN0_PIN 5 #endif #define HEATER_0_PIN 7 @@ -75,9 +75,9 @@ #define TEMP_BED_PIN 6 #if HAS_WIRED_LCD - #if IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 + #if IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 #define LCD_PINS_RS 30 - #define LCD_PINS_ENABLE 20 + #define LCD_PINS_EN 20 #define LCD_PINS_D4 25 #define BEEPER_PIN 29 #define BTN_EN1 19 diff --git a/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h b/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h index 6ab6c4ceb9b2..e224e061787f 100644 --- a/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h +++ b/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h @@ -76,7 +76,7 @@ // #define HEATER_0_PIN 4 #define HEATER_BED_PIN 44 -#define FAN_PIN 12 // IO pin. Buffer needed +#define FAN0_PIN 12 // IO pin. Buffer needed // // SD Card diff --git a/Marlin/src/pins/mega/pins_WEEDO_62A.h b/Marlin/src/pins/mega/pins_WEEDO_62A.h index 4165d9e2341b..436529cb3510 100644 --- a/Marlin/src/pins/mega/pins_WEEDO_62A.h +++ b/Marlin/src/pins/mega/pins_WEEDO_62A.h @@ -25,7 +25,6 @@ * Copyright (c) 2019 WEEDO3D Perron * ATmega2560 */ - #pragma once #include "env_validate.h" @@ -74,7 +73,7 @@ // #define HEATER_0_PIN 10 // EXTRUDER 1 #define HEATER_BED_PIN 8 // BED -#define FAN_PIN 4 // IO pin. Buffer needed +#define FAN0_PIN 4 // IO pin. Buffer needed // // Misc. Functions @@ -85,7 +84,7 @@ // // SD Support // -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #define SDSS 53 #define SD_DETECT_PIN 49 #endif @@ -93,6 +92,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #define BEEPER_PIN 37 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 724c34897707..e9f6f4af9b55 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -61,7 +61,7 @@ #endif #endif -#if !(BOTH(HAS_WIRED_LCD, IS_NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, WYH_L12864, MINIPANEL, REPRAPWORLD_KEYPAD)) +#if !(ALL(HAS_WIRED_LCD, IS_NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, WYH_L12864, MINIPANEL, REPRAPWORLD_KEYPAD)) #define HAS_FREE_AUX2_PINS 1 #endif @@ -69,7 +69,7 @@ #ifdef __MARLIN_DEPS__ #define NOT_TARGET(V...) 0 #else - #define NOT_TARGET(V...) NONE(V) + #define NOT_TARGET NONE #endif // @@ -77,738 +77,742 @@ // #if MB(RAMPS_OLD) - #include "ramps/pins_RAMPS_OLD.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_RAMPS_OLD.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(RAMPS_13_EFB, RAMPS_13_EEB, RAMPS_13_EFF, RAMPS_13_EEF, RAMPS_13_SF) - #include "ramps/pins_RAMPS_13.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_RAMPS_13.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(RAMPS_14_EFB, RAMPS_14_EEB, RAMPS_14_EFF, RAMPS_14_EEF, RAMPS_14_SF) - #include "ramps/pins_RAMPS.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_RAMPS.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(RAMPS_PLUS_EFB, RAMPS_PLUS_EEB, RAMPS_PLUS_EFF, RAMPS_PLUS_EEF, RAMPS_PLUS_SF) - #include "ramps/pins_RAMPS_PLUS.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_RAMPS_PLUS.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 // // RAMPS Derivatives - ATmega1280, ATmega2560 // #elif MB(3DRAG) - #include "ramps/pins_3DRAG.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_3DRAG.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(K8200) - #include "ramps/pins_K8200.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_K8200.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(K8400) - #include "ramps/pins_K8400.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_K8400.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(K8600) - #include "ramps/pins_K8600.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_K8600.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(K8800) - #include "ramps/pins_K8800.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_K8800.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(BAM_DICE) - #include "ramps/pins_RAMPS.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_RAMPS.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(BAM_DICE_DUE) - #include "ramps/pins_BAM_DICE_DUE.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_BAM_DICE_DUE.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(MKS_BASE) - #include "ramps/pins_MKS_BASE_10.h" // ATmega2560 env:mega2560 + #include "ramps/pins_MKS_BASE_10.h" // ATmega2560 env:mega2560 #elif MB(MKS_BASE_14) - #include "ramps/pins_MKS_BASE_14.h" // ATmega2560 env:mega2560 + #include "ramps/pins_MKS_BASE_14.h" // ATmega2560 env:mega2560 #elif MB(MKS_BASE_15) - #include "ramps/pins_MKS_BASE_15.h" // ATmega2560 env:mega2560 + #include "ramps/pins_MKS_BASE_15.h" // ATmega2560 env:mega2560 #elif MB(MKS_BASE_16) - #include "ramps/pins_MKS_BASE_16.h" // ATmega2560 env:mega2560 + #include "ramps/pins_MKS_BASE_16.h" // ATmega2560 env:mega2560 #elif MB(MKS_BASE_HEROIC) - #include "ramps/pins_MKS_BASE_HEROIC.h" // ATmega2560 env:mega2560 + #include "ramps/pins_MKS_BASE_HEROIC.h" // ATmega2560 env:mega2560 #elif MB(MKS_GEN_13) - #include "ramps/pins_MKS_GEN_13.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_MKS_GEN_13.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(MKS_GEN_L) - #include "ramps/pins_MKS_GEN_L.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_MKS_GEN_L.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(KFB_2) - #include "ramps/pins_BIQU_KFB_2.h" // ATmega2560 env:mega2560 + #include "ramps/pins_BIQU_KFB_2.h" // ATmega2560 env:mega2560 #elif MB(ZRIB_V20) - #include "ramps/pins_ZRIB_V20.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_ZRIB_V20.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(ZRIB_V52) - #include "ramps/pins_ZRIB_V52.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_ZRIB_V52.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(ZRIB_V53) - #include "ramps/pins_ZRIB_V53.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_ZRIB_V53.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(FELIX2) - #include "ramps/pins_FELIX2.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_FELIX2.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(RIGIDBOARD) - #include "ramps/pins_RIGIDBOARD.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_RIGIDBOARD.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(RIGIDBOARD_V2) - #include "ramps/pins_RIGIDBOARD_V2.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_RIGIDBOARD_V2.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(SAINSMART_2IN1) - #include "ramps/pins_SAINSMART_2IN1.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_SAINSMART_2IN1.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(ULTIMAKER) - #include "ramps/pins_ULTIMAKER.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_ULTIMAKER.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(ULTIMAKER_OLD) - #include "ramps/pins_ULTIMAKER_OLD.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "ramps/pins_ULTIMAKER_OLD.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(AZTEEG_X3) - #include "ramps/pins_AZTEEG_X3.h" // ATmega2560 env:mega2560 + #include "ramps/pins_AZTEEG_X3.h" // ATmega2560 env:mega2560 #elif MB(AZTEEG_X3_PRO) - #include "ramps/pins_AZTEEG_X3_PRO.h" // ATmega2560 env:mega2560 + #include "ramps/pins_AZTEEG_X3_PRO.h" // ATmega2560 env:mega2560 #elif MB(ULTIMAIN_2) - #include "ramps/pins_ULTIMAIN_2.h" // ATmega2560 env:mega2560ext + #include "ramps/pins_ULTIMAIN_2.h" // ATmega2560 env:mega2560ext #elif MB(FORMBOT_RAPTOR) - #include "ramps/pins_FORMBOT_RAPTOR.h" // ATmega2560 env:mega2560 + #include "ramps/pins_FORMBOT_RAPTOR.h" // ATmega2560 env:mega2560 #elif MB(FORMBOT_RAPTOR2) - #include "ramps/pins_FORMBOT_RAPTOR2.h" // ATmega2560 env:mega2560 + #include "ramps/pins_FORMBOT_RAPTOR2.h" // ATmega2560 env:mega2560 #elif MB(FORMBOT_TREX2PLUS) - #include "ramps/pins_FORMBOT_TREX2PLUS.h" // ATmega2560 env:mega2560 + #include "ramps/pins_FORMBOT_TREX2PLUS.h" // ATmega2560 env:mega2560 #elif MB(FORMBOT_TREX3) - #include "ramps/pins_FORMBOT_TREX3.h" // ATmega2560 env:mega2560 + #include "ramps/pins_FORMBOT_TREX3.h" // ATmega2560 env:mega2560 #elif MB(RUMBA) - #include "ramps/pins_RUMBA.h" // ATmega2560 env:mega2560 + #include "ramps/pins_RUMBA.h" // ATmega2560 env:mega2560 #elif MB(RUMBA_RAISE3D) - #include "ramps/pins_RUMBA_RAISE3D.h" // ATmega2560 env:mega2560 + #include "ramps/pins_RUMBA_RAISE3D.h" // ATmega2560 env:mega2560 #elif MB(RL200) - #include "ramps/pins_RL200.h" // ATmega2560 env:mega2560 + #include "ramps/pins_RL200.h" // ATmega2560 env:mega2560 #elif MB(BQ_ZUM_MEGA_3D) - #include "ramps/pins_BQ_ZUM_MEGA_3D.h" // ATmega2560 env:mega2560ext + #include "ramps/pins_BQ_ZUM_MEGA_3D.h" // ATmega2560 env:mega2560ext #elif MB(MAKEBOARD_MINI) - #include "ramps/pins_MAKEBOARD_MINI.h" // ATmega2560 env:mega2560 + #include "ramps/pins_MAKEBOARD_MINI.h" // ATmega2560 env:mega2560 #elif MB(TRIGORILLA_13) - #include "ramps/pins_TRIGORILLA_13.h" // ATmega2560 env:mega2560 + #include "ramps/pins_TRIGORILLA_13.h" // ATmega2560 env:mega2560 #elif MB(TRIGORILLA_14, TRIGORILLA_14_11) - #include "ramps/pins_TRIGORILLA_14.h" // ATmega2560 env:mega2560 + #include "ramps/pins_TRIGORILLA_14.h" // ATmega2560 env:mega2560 #elif MB(RAMPS_ENDER_4) - #include "ramps/pins_RAMPS_ENDER_4.h" // ATmega2560 env:mega2560 + #include "ramps/pins_RAMPS_ENDER_4.h" // ATmega2560 env:mega2560 #elif MB(RAMPS_CREALITY) - #include "ramps/pins_RAMPS_CREALITY.h" // ATmega2560 env:mega2560 + #include "ramps/pins_RAMPS_CREALITY.h" // ATmega2560 env:mega2560 #elif MB(DAGOMA_F5) - #include "ramps/pins_DAGOMA_F5.h" // ATmega2560 env:mega2560 + #include "ramps/pins_DAGOMA_F5.h" // ATmega2560 env:mega2560 #elif MB(FYSETC_F6_13) - #include "ramps/pins_FYSETC_F6_13.h" // ATmega2560 env:FYSETC_F6 + #include "ramps/pins_FYSETC_F6_13.h" // ATmega2560 env:FYSETC_F6 #elif MB(FYSETC_F6_14) - #include "ramps/pins_FYSETC_F6_14.h" // ATmega2560 env:FYSETC_F6 + #include "ramps/pins_FYSETC_F6_14.h" // ATmega2560 env:FYSETC_F6 #elif MB(DUPLICATOR_I3_PLUS) - #include "ramps/pins_DUPLICATOR_I3_PLUS.h" // ATmega2560 env:mega2560 + #include "ramps/pins_DUPLICATOR_I3_PLUS.h" // ATmega2560 env:mega2560 #elif MB(VORON) - #include "ramps/pins_VORON.h" // ATmega2560 env:mega2560 + #include "ramps/pins_VORON.h" // ATmega2560 env:mega2560 #elif MB(TRONXY_V3_1_0) - #include "ramps/pins_TRONXY_V3_1_0.h" // ATmega2560 env:mega2560 + #include "ramps/pins_TRONXY_V3_1_0.h" // ATmega2560 env:mega2560 #elif MB(Z_BOLT_X_SERIES) - #include "ramps/pins_Z_BOLT_X_SERIES.h" // ATmega2560 env:mega2560 + #include "ramps/pins_Z_BOLT_X_SERIES.h" // ATmega2560 env:mega2560 #elif MB(TT_OSCAR) - #include "ramps/pins_TT_OSCAR.h" // ATmega2560 env:mega2560 + #include "ramps/pins_TT_OSCAR.h" // ATmega2560 env:mega2560 #elif MB(TANGO) - #include "ramps/pins_TANGO.h" // ATmega2560 env:mega2560 + #include "ramps/pins_TANGO.h" // ATmega2560 env:mega2560 #elif MB(MKS_GEN_L_V2) - #include "ramps/pins_MKS_GEN_L_V2.h" // ATmega2560 env:mega2560 + #include "ramps/pins_MKS_GEN_L_V2.h" // ATmega2560 env:mega2560 #elif MB(COPYMASTER_3D) - #include "ramps/pins_COPYMASTER_3D.h" // ATmega2560 env:mega2560 + #include "ramps/pins_COPYMASTER_3D.h" // ATmega2560 env:mega2560 #elif MB(ORTUR_4) - #include "ramps/pins_ORTUR_4.h" // ATmega2560 env:mega2560 + #include "ramps/pins_ORTUR_4.h" // ATmega2560 env:mega2560 #elif MB(TENLOG_D3_HERO) - #include "ramps/pins_TENLOG_D3_HERO.h" // ATmega2560 env:mega2560 + #include "ramps/pins_TENLOG_D3_HERO.h" // ATmega2560 env:mega2560 #elif MB(TENLOG_MB1_V23) - #include "ramps/pins_TENLOG_MB1_V23.h" // ATmega2560 env:mega2560 + #include "ramps/pins_TENLOG_MB1_V23.h" // ATmega2560 env:mega2560 #elif MB(MKS_GEN_L_V21) - #include "ramps/pins_MKS_GEN_L_V21.h" // ATmega2560 env:mega2560 + #include "ramps/pins_MKS_GEN_L_V21.h" // ATmega2560 env:mega2560 #elif MB(RAMPS_S_12_EEFB, RAMPS_S_12_EEEB, RAMPS_S_12_EFFB) - #include "ramps/pins_RAMPS_S_12.h" // ATmega2560 env:mega2560 + #include "ramps/pins_RAMPS_S_12.h" // ATmega2560 env:mega2560 #elif MB(LONGER3D_LK1_PRO, LONGER3D_LKx_PRO) - #include "ramps/pins_LONGER3D_LKx_PRO.h" // ATmega2560 env:mega2560 + #include "ramps/pins_LONGER3D_LKx_PRO.h" // ATmega2560 env:mega2560 #elif MB(PXMALION_CORE_I3) - #include "ramps/pins_PXMALION_CORE_I3.h" // ATmega2560 env:mega2560 + #include "ramps/pins_PXMALION_CORE_I3.h" // ATmega2560 env:mega2560 // // RAMBo and derivatives // #elif MB(RAMBO) - #include "rambo/pins_RAMBO.h" // ATmega2560 env:rambo + #include "rambo/pins_RAMBO.h" // ATmega2560 env:rambo #elif MB(MINIRAMBO, MINIRAMBO_10A) - #include "rambo/pins_MINIRAMBO.h" // ATmega2560 env:rambo + #include "rambo/pins_MINIRAMBO.h" // ATmega2560 env:rambo #elif MB(EINSY_RAMBO) - #include "rambo/pins_EINSY_RAMBO.h" // ATmega2560 env:rambo + #include "rambo/pins_EINSY_RAMBO.h" // ATmega2560 env:rambo #elif MB(EINSY_RETRO) - #include "rambo/pins_EINSY_RETRO.h" // ATmega2560 env:rambo + #include "rambo/pins_EINSY_RETRO.h" // ATmega2560 env:rambo #elif MB(SCOOVO_X9H) - #include "rambo/pins_SCOOVO_X9H.h" // ATmega2560 env:rambo + #include "rambo/pins_SCOOVO_X9H.h" // ATmega2560 env:rambo #elif MB(RAMBO_THINKERV2) - #include "rambo/pins_RAMBO_THINKERV2.h" // ATmega2560 env:rambo + #include "rambo/pins_RAMBO_THINKERV2.h" // ATmega2560 env:rambo // // Other ATmega1280, ATmega2560 // #elif MB(CNCONTROLS_11) - #include "mega/pins_CNCONTROLS_11.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "mega/pins_CNCONTROLS_11.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(CNCONTROLS_12) - #include "mega/pins_CNCONTROLS_12.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "mega/pins_CNCONTROLS_12.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(CNCONTROLS_15) - #include "mega/pins_CNCONTROLS_15.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "mega/pins_CNCONTROLS_15.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(MIGHTYBOARD_REVE) - #include "mega/pins_MIGHTYBOARD_REVE.h" // ATmega2560, ATmega1280 env:mega2560ext env:MightyBoard1280 env:MightyBoard2560 + #include "mega/pins_MIGHTYBOARD_REVE.h" // ATmega2560, ATmega1280 env:mega2560ext env:MightyBoard1280 env:MightyBoard2560 #elif MB(CHEAPTRONIC) - #include "mega/pins_CHEAPTRONIC.h" // ATmega2560 env:mega2560 + #include "mega/pins_CHEAPTRONIC.h" // ATmega2560 env:mega2560 #elif MB(CHEAPTRONIC_V2) - #include "mega/pins_CHEAPTRONICv2.h" // ATmega2560 env:mega2560 + #include "mega/pins_CHEAPTRONICv2.h" // ATmega2560 env:mega2560 #elif MB(MEGATRONICS) - #include "mega/pins_MEGATRONICS.h" // ATmega2560 env:mega2560 + #include "mega/pins_MEGATRONICS.h" // ATmega2560 env:mega2560 #elif MB(MEGATRONICS_2) - #include "mega/pins_MEGATRONICS_2.h" // ATmega2560 env:mega2560 + #include "mega/pins_MEGATRONICS_2.h" // ATmega2560 env:mega2560 #elif MB(MEGATRONICS_3, MEGATRONICS_31, MEGATRONICS_32) - #include "mega/pins_MEGATRONICS_3.h" // ATmega2560 env:mega2560 + #include "mega/pins_MEGATRONICS_3.h" // ATmega2560 env:mega2560 #elif MB(ELEFU_3) - #include "mega/pins_ELEFU_3.h" // ATmega2560 env:mega2560 + #include "mega/pins_ELEFU_3.h" // ATmega2560 env:mega2560 #elif MB(LEAPFROG) - #include "mega/pins_LEAPFROG.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "mega/pins_LEAPFROG.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(MEGACONTROLLER) - #include "mega/pins_MEGACONTROLLER.h" // ATmega2560 env:mega2560 + #include "mega/pins_MEGACONTROLLER.h" // ATmega2560 env:mega2560 #elif MB(GT2560_REV_A) - #include "mega/pins_GT2560_REV_A.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "mega/pins_GT2560_REV_A.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(GT2560_REV_A_PLUS) - #include "mega/pins_GT2560_REV_A_PLUS.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 + #include "mega/pins_GT2560_REV_A_PLUS.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(GT2560_V3) - #include "mega/pins_GT2560_V3.h" // ATmega2560 env:mega2560 + #include "mega/pins_GT2560_V3.h" // ATmega2560 env:mega2560 #elif MB(GT2560_REV_B) - #include "mega/pins_GT2560_REV_B.h" // ATmega2560 env:mega2560 + #include "mega/pins_GT2560_REV_B.h" // ATmega2560 env:mega2560 #elif MB(GT2560_V4) - #include "mega/pins_GT2560_V4.h" // ATmega2560 env:mega2560 - #elif MB(GT2560_V4_A20) - #include "mega/pins_GT2560_V4_A20.h" // ATmega2560 env:mega2560 + #include "mega/pins_GT2560_V4.h" // ATmega2560 env:mega2560 +#elif MB(GT2560_V4_A20) + #include "mega/pins_GT2560_V4_A20.h" // ATmega2560 env:mega2560 #elif MB(GT2560_V3_MC2) - #include "mega/pins_GT2560_V3_MC2.h" // ATmega2560 env:mega2560 + #include "mega/pins_GT2560_V3_MC2.h" // ATmega2560 env:mega2560 #elif MB(GT2560_V3_A20) - #include "mega/pins_GT2560_V3_A20.h" // ATmega2560 env:mega2560 + #include "mega/pins_GT2560_V3_A20.h" // ATmega2560 env:mega2560 #elif MB(EINSTART_S) - #include "mega/pins_EINSTART-S.h" // ATmega2560, ATmega1280 env:mega2560ext env:mega1280 + #include "mega/pins_EINSTART-S.h" // ATmega2560, ATmega1280 env:mega2560ext env:mega1280 #elif MB(WANHAO_ONEPLUS) - #include "mega/pins_WANHAO_ONEPLUS.h" // ATmega2560 env:mega2560 + #include "mega/pins_WANHAO_ONEPLUS.h" // ATmega2560 env:mega2560 #elif MB(OVERLORD) - #include "mega/pins_OVERLORD.h" // ATmega2560 env:mega2560 + #include "mega/pins_OVERLORD.h" // ATmega2560 env:mega2560 #elif MB(HJC2560C_REV1) - #include "mega/pins_HJC2560C_REV2.h" // ATmega2560 env:mega2560 + #include "mega/pins_HJC2560C_REV2.h" // ATmega2560 env:mega2560 #elif MB(HJC2560C_REV2) - #include "mega/pins_HJC2560C_REV2.h" // ATmega2560 env:mega2560 + #include "mega/pins_HJC2560C_REV2.h" // ATmega2560 env:mega2560 #elif MB(LEAPFROG_XEED2015) - #include "mega/pins_LEAPFROG_XEED2015.h" // ATmega2560 env:mega2560 + #include "mega/pins_LEAPFROG_XEED2015.h" // ATmega2560 env:mega2560 #elif MB(PICA) - #include "mega/pins_PICA.h" // ATmega2560 env:mega2560 + #include "mega/pins_PICA.h" // ATmega2560 env:mega2560 #elif MB(PICA_REVB) - #include "mega/pins_PICAOLD.h" // ATmega2560 env:mega2560 + #include "mega/pins_PICAOLD.h" // ATmega2560 env:mega2560 #elif MB(INTAMSYS40) - #include "mega/pins_INTAMSYS40.h" // ATmega2560 env:mega2560 + #include "mega/pins_INTAMSYS40.h" // ATmega2560 env:mega2560 #elif MB(MALYAN_M180) - #include "mega/pins_MALYAN_M180.h" // ATmega2560 env:mega2560 + #include "mega/pins_MALYAN_M180.h" // ATmega2560 env:mega2560 #elif MB(PROTONEER_CNC_SHIELD_V3) - #include "mega/pins_PROTONEER_CNC_SHIELD_V3.h"// ATmega2560 env:mega2560 + #include "mega/pins_PROTONEER_CNC_SHIELD_V3.h" // ATmega2560 env:mega2560 #elif MB(WEEDO_62A) - #include "mega/pins_WEEDO_62A.h" // ATmega2560 env:mega2560 + #include "mega/pins_WEEDO_62A.h" // ATmega2560 env:mega2560 // // ATmega1281, ATmega2561 // #elif MB(MINITRONICS) - #include "mega/pins_MINITRONICS.h" // ATmega1281 env:mega1280 + #include "mega/pins_MINITRONICS.h" // ATmega1281 env:mega1280 #elif MB(SILVER_GATE) - #include "mega/pins_SILVER_GATE.h" // ATmega2561 env:mega2560 + #include "mega/pins_SILVER_GATE.h" // ATmega2561 env:mega2560 // // Sanguinololu and Derivatives - ATmega644P, ATmega1284P // #elif MB(SANGUINOLOLU_11) - #include "sanguino/pins_SANGUINOLOLU_11.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_SANGUINOLOLU_11.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(SANGUINOLOLU_12) - #include "sanguino/pins_SANGUINOLOLU_12.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_SANGUINOLOLU_12.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(MELZI) - #include "sanguino/pins_MELZI.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_MELZI.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(MELZI_V2) - #include "sanguino/pins_MELZI_V2.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_MELZI_V2.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(MELZI_MAKR3D) - #include "sanguino/pins_MELZI_MAKR3D.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_MELZI_MAKR3D.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(MELZI_CREALITY) - #include "sanguino/pins_MELZI_CREALITY.h" // ATmega1284P env:melzi_optiboot_optimized env:melzi_optiboot env:melzi_optimized env:melzi + #include "sanguino/pins_MELZI_CREALITY.h" // ATmega1284P env:melzi_optiboot_optimized env:melzi_optiboot env:melzi_optimized env:melzi #elif MB(MELZI_MALYAN) - #include "sanguino/pins_MELZI_MALYAN.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_MELZI_MALYAN.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(MELZI_TRONXY) - #include "sanguino/pins_MELZI_TRONXY.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_MELZI_TRONXY.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(STB_11) - #include "sanguino/pins_STB_11.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_STB_11.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(AZTEEG_X1) - #include "sanguino/pins_AZTEEG_X1.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_AZTEEG_X1.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(ZMIB_V2) - #include "sanguino/pins_ZMIB_V2.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_ZMIB_V2.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p // // Other ATmega644P, ATmega644, ATmega1284P // #elif MB(GEN3_MONOLITHIC) - #include "sanguino/pins_GEN3_MONOLITHIC.h" // ATmega644P env:sanguino644p + #include "sanguino/pins_GEN3_MONOLITHIC.h" // ATmega644P env:sanguino644p #elif MB(GEN3_PLUS) - #include "sanguino/pins_GEN3_PLUS.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_GEN3_PLUS.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(GEN6) - #include "sanguino/pins_GEN6.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_GEN6.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(GEN6_DELUXE) - #include "sanguino/pins_GEN6_DELUXE.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_GEN6_DELUXE.h" // ATmega644P, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(GEN7_CUSTOM) - #include "sanguino/pins_GEN7_CUSTOM.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_GEN7_CUSTOM.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(GEN7_12) - #include "sanguino/pins_GEN7_12.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_GEN7_12.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(GEN7_13) - #include "sanguino/pins_GEN7_13.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_GEN7_13.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(GEN7_14) - #include "sanguino/pins_GEN7_14.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_GEN7_14.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p #elif MB(OMCA_A) - #include "sanguino/pins_OMCA_A.h" // ATmega644 env:sanguino644p + #include "sanguino/pins_OMCA_A.h" // ATmega644 env:sanguino644p #elif MB(OMCA) - #include "sanguino/pins_OMCA.h" // ATmega644P, ATmega644 env:sanguino644p + #include "sanguino/pins_OMCA.h" // ATmega644P, ATmega644 env:sanguino644p #elif MB(ANET_10) - #include "sanguino/pins_ANET_10.h" // ATmega1284P env:sanguino1284p env:sanguino1284p_optimized env:melzi_optiboot + #include "sanguino/pins_ANET_10.h" // ATmega1284P env:sanguino1284p env:sanguino1284p_optimized env:melzi_optiboot #elif MB(SETHI) - #include "sanguino/pins_SETHI.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p + #include "sanguino/pins_SETHI.h" // ATmega644P, ATmega644, ATmega1284P env:sanguino1284p_optimized env:sanguino1284p env:sanguino644p // // Teensyduino - AT90USB1286, AT90USB1286P // #elif MB(TEENSYLU) - #include "teensy2/pins_TEENSYLU.h" // AT90USB1286, AT90USB1286P env:at90usb1286_cdc + #include "teensy2/pins_TEENSYLU.h" // AT90USB1286, AT90USB1286P env:at90usb1286_cdc #elif MB(PRINTRBOARD) - #include "teensy2/pins_PRINTRBOARD.h" // AT90USB1286 env:at90usb1286_dfu + #include "teensy2/pins_PRINTRBOARD.h" // AT90USB1286 env:at90usb1286_dfu #elif MB(PRINTRBOARD_REVF) - #include "teensy2/pins_PRINTRBOARD_REVF.h" // AT90USB1286 env:at90usb1286_dfu + #include "teensy2/pins_PRINTRBOARD_REVF.h" // AT90USB1286 env:at90usb1286_dfu #elif MB(BRAINWAVE) - #include "teensy2/pins_BRAINWAVE.h" // AT90USB646 env:at90usb1286_cdc + #include "teensy2/pins_BRAINWAVE.h" // AT90USB646 env:at90usb1286_cdc #elif MB(BRAINWAVE_PRO) - #include "teensy2/pins_BRAINWAVE_PRO.h" // AT90USB1286 env:at90usb1286_cdc + #include "teensy2/pins_BRAINWAVE_PRO.h" // AT90USB1286 env:at90usb1286_cdc #elif MB(SAV_MKI) - #include "teensy2/pins_SAV_MKI.h" // AT90USB1286 env:at90usb1286_cdc + #include "teensy2/pins_SAV_MKI.h" // AT90USB1286 env:at90usb1286_cdc #elif MB(TEENSY2) - #include "teensy2/pins_TEENSY2.h" // AT90USB1286 env:teensy20 + #include "teensy2/pins_TEENSY2.h" // AT90USB1286 env:teensy20 #elif MB(5DPRINT) - #include "teensy2/pins_5DPRINT.h" // AT90USB1286 env:at90usb1286_dfu + #include "teensy2/pins_5DPRINT.h" // AT90USB1286 env:at90usb1286_dfu // -// LPC1768 ARM Cortex M3 +// LPC1768 ARM Cortex-M3 // #elif MB(RAMPS_14_RE_ARM_EFB, RAMPS_14_RE_ARM_EEB, RAMPS_14_RE_ARM_EFF, RAMPS_14_RE_ARM_EEF, RAMPS_14_RE_ARM_SF) - #include "lpc1768/pins_RAMPS_RE_ARM.h" // LPC1768 env:LPC1768 + #include "lpc1768/pins_RAMPS_RE_ARM.h" // LPC1768 env:LPC1768 #elif MB(MKS_SBASE) - #include "lpc1768/pins_MKS_SBASE.h" // LPC1768 env:LPC1768 + #include "lpc1768/pins_MKS_SBASE.h" // LPC1768 env:LPC1768 #elif MB(MKS_SGEN_L) - #include "lpc1768/pins_MKS_SGEN_L.h" // LPC1768 env:LPC1768 + #include "lpc1768/pins_MKS_SGEN_L.h" // LPC1768 env:LPC1768 #elif MB(AZSMZ_MINI) - #include "lpc1768/pins_AZSMZ_MINI.h" // LPC1768 env:LPC1768 + #include "lpc1768/pins_AZSMZ_MINI.h" // LPC1768 env:LPC1768 #elif MB(BIQU_BQ111_A4) - #include "lpc1768/pins_BIQU_BQ111_A4.h" // LPC1768 env:LPC1768 + #include "lpc1768/pins_BIQU_BQ111_A4.h" // LPC1768 env:LPC1768 #elif MB(SELENA_COMPACT) - #include "lpc1768/pins_SELENA_COMPACT.h" // LPC1768 env:LPC1768 + #include "lpc1768/pins_SELENA_COMPACT.h" // LPC1768 env:LPC1768 #elif MB(BIQU_B300_V1_0) - #include "lpc1768/pins_BIQU_B300_V1.0.h" // LPC1768 env:LPC1768 + #include "lpc1768/pins_BIQU_B300_V1.0.h" // LPC1768 env:LPC1768 #elif MB(GMARSH_X6_REV1) - #include "lpc1768/pins_GMARSH_X6_REV1.h" // LPC1768 env:LPC1768 + #include "lpc1768/pins_GMARSH_X6_REV1.h" // LPC1768 env:LPC1768 #elif MB(BTT_SKR_V1_1) - #include "lpc1768/pins_BTT_SKR_V1_1.h" // LPC1768 env:LPC1768 + #include "lpc1768/pins_BTT_SKR_V1_1.h" // LPC1768 env:LPC1768 #elif MB(BTT_SKR_V1_3) - #include "lpc1768/pins_BTT_SKR_V1_3.h" // LPC1768 env:LPC1768 + #include "lpc1768/pins_BTT_SKR_V1_3.h" // LPC1768 env:LPC1768 #elif MB(BTT_SKR_V1_4) - #include "lpc1768/pins_BTT_SKR_V1_4.h" // LPC1768 env:LPC1768 + #include "lpc1768/pins_BTT_SKR_V1_4.h" // LPC1768 env:LPC1768 #elif MB(EMOTRONIC) - #include "lpc1768/pins_EMOTRONIC.h" // LPC1768 env:LPC1768 + #include "lpc1768/pins_EMOTRONIC.h" // LPC1768 env:LPC1768 // -// LPC1769 ARM Cortex M3 +// LPC1769 ARM Cortex-M3 // #elif MB(MKS_SGEN) - #include "lpc1769/pins_MKS_SGEN.h" // LPC1769 env:LPC1769 + #include "lpc1769/pins_MKS_SGEN.h" // LPC1769 env:LPC1769 #elif MB(AZTEEG_X5_GT) - #include "lpc1769/pins_AZTEEG_X5_GT.h" // LPC1769 env:LPC1769 + #include "lpc1769/pins_AZTEEG_X5_GT.h" // LPC1769 env:LPC1769 #elif MB(AZTEEG_X5_MINI) - #include "lpc1769/pins_AZTEEG_X5_MINI.h" // LPC1769 env:LPC1769 + #include "lpc1769/pins_AZTEEG_X5_MINI.h" // LPC1769 env:LPC1769 #elif MB(AZTEEG_X5_MINI_WIFI) - #include "lpc1769/pins_AZTEEG_X5_MINI_WIFI.h" // LPC1769 env:LPC1769 + #include "lpc1769/pins_AZTEEG_X5_MINI_WIFI.h" // LPC1769 env:LPC1769 #elif MB(COHESION3D_REMIX) - #include "lpc1769/pins_COHESION3D_REMIX.h" // LPC1769 env:LPC1769 + #include "lpc1769/pins_COHESION3D_REMIX.h" // LPC1769 env:LPC1769 #elif MB(COHESION3D_MINI) - #include "lpc1769/pins_COHESION3D_MINI.h" // LPC1769 env:LPC1769 + #include "lpc1769/pins_COHESION3D_MINI.h" // LPC1769 env:LPC1769 #elif MB(SMOOTHIEBOARD) - #include "lpc1769/pins_SMOOTHIEBOARD.h" // LPC1769 env:LPC1769 + #include "lpc1769/pins_SMOOTHIEBOARD.h" // LPC1769 env:LPC1769 #elif MB(TH3D_EZBOARD) - #include "lpc1769/pins_TH3D_EZBOARD.h" // LPC1769 env:LPC1769 + #include "lpc1769/pins_TH3D_EZBOARD.h" // LPC1769 env:LPC1769 #elif MB(BTT_SKR_V1_4_TURBO) - #include "lpc1769/pins_BTT_SKR_V1_4_TURBO.h" // LPC1769 env:LPC1769 + #include "lpc1769/pins_BTT_SKR_V1_4_TURBO.h" // LPC1769 env:LPC1769 #elif MB(MKS_SGEN_L_V2) - #include "lpc1769/pins_MKS_SGEN_L_V2.h" // LPC1769 env:LPC1769 + #include "lpc1769/pins_MKS_SGEN_L_V2.h" // LPC1769 env:LPC1769 #elif MB(BTT_SKR_E3_TURBO) - #include "lpc1769/pins_BTT_SKR_E3_TURBO.h" // LPC1769 env:LPC1769 + #include "lpc1769/pins_BTT_SKR_E3_TURBO.h" // LPC1769 env:LPC1769 #elif MB(FLY_CDY) - #include "lpc1769/pins_FLY_CDY.h" // LPC1769 env:LPC1769 + #include "lpc1769/pins_FLY_CDY.h" // LPC1769 env:LPC1769 // // Due (ATSAM) boards // #elif MB(DUE3DOM) - #include "sam/pins_DUE3DOM.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug + #include "sam/pins_DUE3DOM.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug #elif MB(DUE3DOM_MINI) - #include "sam/pins_DUE3DOM_MINI.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug + #include "sam/pins_DUE3DOM_MINI.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug #elif MB(RADDS) - #include "sam/pins_RADDS.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug + #include "sam/pins_RADDS.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug #elif MB(RURAMPS4D_11) - #include "sam/pins_RURAMPS4D_11.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug + #include "sam/pins_RURAMPS4D_11.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug #elif MB(RURAMPS4D_13) - #include "sam/pins_RURAMPS4D_13.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug + #include "sam/pins_RURAMPS4D_13.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug #elif MB(RAMPS_FD_V1) - #include "sam/pins_RAMPS_FD_V1.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug + #include "sam/pins_RAMPS_FD_V1.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug #elif MB(RAMPS_FD_V2) - #include "sam/pins_RAMPS_FD_V2.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug + #include "sam/pins_RAMPS_FD_V2.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug #elif MB(RAMPS_SMART_EFB, RAMPS_SMART_EEB, RAMPS_SMART_EFF, RAMPS_SMART_EEF, RAMPS_SMART_SF) - #include "sam/pins_RAMPS_SMART.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug + #include "sam/pins_RAMPS_SMART.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug #elif MB(RAMPS_DUO_EFB, RAMPS_DUO_EEB, RAMPS_DUO_EFF, RAMPS_DUO_EEF, RAMPS_DUO_SF) - #include "sam/pins_RAMPS_DUO.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug + #include "sam/pins_RAMPS_DUO.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug #elif MB(RAMPS4DUE_EFB, RAMPS4DUE_EEB, RAMPS4DUE_EFF, RAMPS4DUE_EEF, RAMPS4DUE_SF) - #include "sam/pins_RAMPS4DUE.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug + #include "sam/pins_RAMPS4DUE.h" // SAM3X8E env:DUE env:DUE_USB env:DUE_debug #elif MB(ULTRATRONICS_PRO) - #include "sam/pins_ULTRATRONICS_PRO.h" // SAM3X8E env:DUE env:DUE_debug + #include "sam/pins_ULTRATRONICS_PRO.h" // SAM3X8E env:DUE env:DUE_debug #elif MB(ARCHIM1) - #include "sam/pins_ARCHIM1.h" // SAM3X8E env:DUE_archim env:DUE_archim_debug + #include "sam/pins_ARCHIM1.h" // SAM3X8E env:DUE_archim env:DUE_archim_debug #elif MB(ARCHIM2) - #include "sam/pins_ARCHIM2.h" // SAM3X8E env:DUE_archim env:DUE_archim_debug + #include "sam/pins_ARCHIM2.h" // SAM3X8E env:DUE_archim env:DUE_archim_debug #elif MB(ALLIGATOR) - #include "sam/pins_ALLIGATOR_R2.h" // SAM3X8E env:DUE env:DUE_debug + #include "sam/pins_ALLIGATOR_R2.h" // SAM3X8E env:DUE env:DUE_debug #elif MB(CNCONTROLS_15D) - #include "sam/pins_CNCONTROLS_15D.h" // SAM3X8E env:DUE env:DUE_USB + #include "sam/pins_CNCONTROLS_15D.h" // SAM3X8E env:DUE env:DUE_USB #elif MB(KRATOS32) - #include "sam/pins_KRATOS32.h" // SAM3X8E env:DUE env:DUE_USB + #include "sam/pins_KRATOS32.h" // SAM3X8E env:DUE env:DUE_USB #elif MB(PRINTRBOARD_G2) - #include "sam/pins_PRINTRBOARD_G2.h" // SAM3X8C env:DUE_USB + #include "sam/pins_PRINTRBOARD_G2.h" // SAM3X8C env:DUE_USB #elif MB(ADSK) - #include "sam/pins_ADSK.h" // SAM3X8C env:DUE env:DUE_debug + #include "sam/pins_ADSK.h" // SAM3X8C env:DUE env:DUE_debug // // STM32 ARM Cortex-M0 // + #elif MB(MALYAN_M200_V2) - #include "stm32f0/pins_MALYAN_M200_V2.h" // STM32F0 env:STM32F070RB_malyan env:STM32F070CB_malyan + #include "stm32f0/pins_MALYAN_M200_V2.h" // STM32F0 env:STM32F070RB_malyan env:STM32F070CB_malyan #elif MB(MALYAN_M300) - #include "stm32f0/pins_MALYAN_M300.h" // STM32F070 env:malyan_M300 + #include "stm32f0/pins_MALYAN_M300.h" // STM32F0 env:malyan_M300 + +// +// STM32 ARM Cortex-M0+ +// + +#elif MB(BTT_EBB42_V1_1) + #include "stm32g0/pins_BTT_EBB42_V1_1.h" // STM32G0 env:BTT_EBB42_V1_1_filament_extruder +#elif MB(BTT_SKR_MINI_E3_V3_0) + #include "stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h" // STM32G0 env:STM32G0B1RE_btt env:STM32G0B1RE_btt_xfer +#elif MB(BTT_MANTA_M4P_V2_1) + #include "stm32g0/pins_BTT_MANTA_M4P_V2_1.h" // STM32G0 env:STM32G0B1RE_manta_btt env:STM32G0B1RE_manta_btt_xfer +#elif MB(BTT_MANTA_M5P_V1_0) + #include "stm32g0/pins_BTT_MANTA_M5P_V1_0.h" // STM32G0 env:STM32G0B1RE_manta_btt env:STM32G0B1RE_manta_btt_xfer +#elif MB(BTT_MANTA_E3_EZ_V1_0) + #include "stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h" // STM32G0 env:STM32G0B1RE_manta_btt env:STM32G0B1RE_manta_btt_xfer +#elif MB(BTT_MANTA_M8P_V1_0) + #include "stm32g0/pins_BTT_MANTA_M8P_V1_0.h" // STM32G0 env:STM32G0B1VE_btt env:STM32G0B1VE_btt_xfer +#elif MB(BTT_MANTA_M8P_V1_1) + #include "stm32g0/pins_BTT_MANTA_M8P_V1_1.h" // STM32G0 env:STM32G0B1VE_btt env:STM32G0B1VE_btt_xfer // // STM32 ARM Cortex-M3 // #elif MB(STM32F103RE) - #include "stm32f1/pins_STM32F1R.h" // STM32F103RE env:STM32F103RE env:STM32F103RE_maple + #include "stm32f1/pins_STM32F1R.h" // STM32F1 env:STM32F103RE env:STM32F103RE_maple #elif MB(MALYAN_M200) - #include "stm32f1/pins_MALYAN_M200.h" // STM32F103CB env:STM32F103CB_malyan env:STM32F103CB_malyan_maple + #include "stm32f1/pins_MALYAN_M200.h" // STM32F1 env:STM32F103CB_malyan env:STM32F103CB_malyan_maple #elif MB(STM3R_MINI) - #include "stm32f1/pins_STM3R_MINI.h" // STM32F103VE? env:STM32F103VE env:STM32F103RE_maple + #include "stm32f1/pins_STM3R_MINI.h" // STM32F1 env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_PRO_VB) - #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F103VE env:STM32F103VE env:STM32F103VE_GTM32_maple + #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F1 env:STM32F103VE env:STM32F103VE_GTM32_maple #elif MB(GTM32_PRO_VD) - #include "stm32f1/pins_GTM32_PRO_VD.h" // STM32F103VE env:STM32F103VE env:STM32F103VE_GTM32_maple + #include "stm32f1/pins_GTM32_PRO_VD.h" // STM32F1 env:STM32F103VE env:STM32F103VE_GTM32_maple #elif MB(GTM32_MINI) - #include "stm32f1/pins_GTM32_MINI.h" // STM32F103VE env:STM32F103VE env:STM32F103VE_GTM32_maple + #include "stm32f1/pins_GTM32_MINI.h" // STM32F1 env:STM32F103VE env:STM32F103VE_GTM32_maple #elif MB(GTM32_MINI_A30) - #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F103VE env:STM32F103VE env:STM32F103VE_GTM32_maple + #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F1 env:STM32F103VE env:STM32F103VE_GTM32_maple #elif MB(GTM32_REV_B) - #include "stm32f1/pins_GTM32_REV_B.h" // STM32F103VE env:STM32F103VE env:STM32F103VE_GTM32_maple + #include "stm32f1/pins_GTM32_REV_B.h" // STM32F1 env:STM32F103VE env:STM32F103VE_GTM32_maple #elif MB(MORPHEUS) - #include "stm32f1/pins_MORPHEUS.h" // STM32F103RE env:STM32F103RE env:STM32F103RE_maple + #include "stm32f1/pins_MORPHEUS.h" // STM32F1 env:STM32F103RE env:STM32F103RE_maple #elif MB(CHITU3D) - #include "stm32f1/pins_CHITU3D.h" // STM32F103ZE env:STM32F103ZE env:STM32F103RE_maple + #include "stm32f1/pins_CHITU3D.h" // STM32F1 env:STM32F103ZE env:STM32F103RE_maple #elif MB(MKS_ROBIN) - #include "stm32f1/pins_MKS_ROBIN.h" // STM32F1 env:mks_robin env:mks_robin_maple + #include "stm32f1/pins_MKS_ROBIN.h" // STM32F1 env:mks_robin env:mks_robin_maple #elif MB(MKS_ROBIN_MINI) - #include "stm32f1/pins_MKS_ROBIN_MINI.h" // STM32F1 env:mks_robin_mini env:mks_robin_mini_maple + #include "stm32f1/pins_MKS_ROBIN_MINI.h" // STM32F1 env:mks_robin_mini env:mks_robin_mini_maple #elif MB(MKS_ROBIN_NANO) - #include "stm32f1/pins_MKS_ROBIN_NANO.h" // STM32F1 env:mks_robin_nano_v1v2 env:mks_robin_nano_v1v2_maple env:mks_robin_nano_v1v2_usbmod + #include "stm32f1/pins_MKS_ROBIN_NANO.h" // STM32F1 env:mks_robin_nano_v1v2 env:mks_robin_nano_v1v2_maple env:mks_robin_nano_v1v2_usbmod #elif MB(MKS_ROBIN_NANO_V2) - #include "stm32f1/pins_MKS_ROBIN_NANO_V2.h" // STM32F1 env:mks_robin_nano_v1v2 env:mks_robin_nano_v1v2_maple + #include "stm32f1/pins_MKS_ROBIN_NANO_V2.h" // STM32F1 env:mks_robin_nano_v1v2 env:mks_robin_nano_v1v2_maple #elif MB(MKS_ROBIN_LITE) - #include "stm32f1/pins_MKS_ROBIN_LITE.h" // STM32F1 env:mks_robin_lite env:mks_robin_lite_maple + #include "stm32f1/pins_MKS_ROBIN_LITE.h" // STM32F1 env:mks_robin_lite env:mks_robin_lite_maple #elif MB(MKS_ROBIN_LITE3) - #include "stm32f1/pins_MKS_ROBIN_LITE3.h" // STM32F1 env:mks_robin_lite3 env:mks_robin_lite3_maple + #include "stm32f1/pins_MKS_ROBIN_LITE3.h" // STM32F1 env:mks_robin_lite3 env:mks_robin_lite3_maple #elif MB(MKS_ROBIN_PRO) - #include "stm32f1/pins_MKS_ROBIN_PRO.h" // STM32F1 env:mks_robin_pro env:mks_robin_pro_maple + #include "stm32f1/pins_MKS_ROBIN_PRO.h" // STM32F1 env:mks_robin_pro env:mks_robin_pro_maple #elif MB(MKS_ROBIN_E3) - #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 env:mks_robin_e3_maple + #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 env:mks_robin_e3_maple #elif MB(MKS_ROBIN_E3_V1_1) - #include "stm32f1/pins_MKS_ROBIN_E3_V1_1.h" // STM32F1 env:mks_robin_e3 + #include "stm32f1/pins_MKS_ROBIN_E3_V1_1.h" // STM32F1 env:mks_robin_e3 #elif MB(MKS_ROBIN_E3D) - #include "stm32f1/pins_MKS_ROBIN_E3D.h" // STM32F1 env:mks_robin_e3 + #include "stm32f1/pins_MKS_ROBIN_E3D.h" // STM32F1 env:mks_robin_e3 #elif MB(MKS_ROBIN_E3D_V1_1) - #include "stm32f1/pins_MKS_ROBIN_E3D_V1_1.h" // STM32F1 env:mks_robin_e3 + #include "stm32f1/pins_MKS_ROBIN_E3D_V1_1.h" // STM32F1 env:mks_robin_e3 env:mks_robin_e3_maple #elif MB(MKS_ROBIN_E3P) - #include "stm32f1/pins_MKS_ROBIN_E3P.h" // STM32F1 env:mks_robin_e3p env:mks_robin_e3p_maple -#elif MB(BTT_EBB42_V1_1) - #include "stm32g0/pins_BTT_EBB42_V1_1.h" // STM32G0 env:BTT_EBB42_V1_1_filament_extruder + #include "stm32f1/pins_MKS_ROBIN_E3P.h" // STM32F1 env:mks_robin_e3p env:mks_robin_e3p_maple #elif MB(BTT_SKR_MINI_V1_1) - #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple + #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_MINI_E3_V1_0) - #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple + #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_MINI_E3_V1_2) - #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 + #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 env:STM32G0B1RE_btt_xfer -#elif MB(BTT_MANTA_M4P_V1_0) - #include "stm32g0/pins_BTT_MANTA_M4P_V1_0.h" // STM32G0 env:STM32G0B1RE_manta_btt env:STM32G0B1RE_manta_btt_xfer -#elif MB(BTT_MANTA_M5P_V1_0) - #include "stm32g0/pins_BTT_MANTA_M5P_V1_0.h" // STM32G0 env:STM32G0B1RE_manta_btt env:STM32G0B1RE_manta_btt_xfer -#elif MB(BTT_MANTA_E3_EZ_V1_0) - #include "stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h" // STM32G0 env:STM32G0B1RE_manta_btt env:STM32G0B1RE_manta_btt_xfer -#elif MB(BTT_MANTA_M8P_V1_0) - #include "stm32g0/pins_BTT_MANTA_M8P_V1_0.h" // STM32G0 env:STM32G0B1VE_btt env:STM32G0B1VE_btt_xfer -#elif MB(BTT_MANTA_M8P_V1_1) - #include "stm32g0/pins_BTT_MANTA_M8P_V1_1.h" // STM32G0 env:STM32G0B1VE_btt env:STM32G0B1VE_btt_xfer -#elif MB(BTT_SKR_MINI_E3_V3_0_1) - #include "stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h"// STM32F4 env:STM32F401RC_btt + #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_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 + #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) - #include "stm32f1/pins_BTT_SKR_E3_DIP.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 + #include "stm32f1/pins_BTT_SKR_E3_DIP.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_CR6) - #include "stm32f1/pins_BTT_SKR_CR6.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple + #include "stm32f1/pins_BTT_SKR_CR6.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple #elif MB(JGAURORA_A5S_A1) - #include "stm32f1/pins_JGAURORA_A5S_A1.h" // STM32F1 env:jgaurora_a5s_a1 env:jgaurora_a5s_a1_maple + #include "stm32f1/pins_JGAURORA_A5S_A1.h" // STM32F1 env:jgaurora_a5s_a1 env:jgaurora_a5s_a1_maple #elif MB(FYSETC_AIO_II) - #include "stm32f1/pins_FYSETC_AIO_II.h" // STM32F1 env:STM32F103RC_fysetc env:STM32F103RC_fysetc_maple + #include "stm32f1/pins_FYSETC_AIO_II.h" // STM32F1 env:STM32F103RC_fysetc env:STM32F103RC_fysetc_maple #elif MB(FYSETC_CHEETAH) - #include "stm32f1/pins_FYSETC_CHEETAH.h" // STM32F1 env:STM32F103RC_fysetc env:STM32F103RC_fysetc_maple + #include "stm32f1/pins_FYSETC_CHEETAH.h" // STM32F1 env:STM32F103RC_fysetc env:STM32F103RC_fysetc_maple #elif MB(FYSETC_CHEETAH_V12) - #include "stm32f1/pins_FYSETC_CHEETAH_V12.h" // STM32F1 env:STM32F103RC_fysetc env:STM32F103RC_fysetc_maple + #include "stm32f1/pins_FYSETC_CHEETAH_V12.h" // STM32F1 env:STM32F103RC_fysetc env:STM32F103RC_fysetc_maple #elif MB(LONGER3D_LK) - #include "stm32f1/pins_LONGER3D_LK.h" // STM32F1 env:STM32F103VE_longer env:STM32F103VE_longer_maple + #include "stm32f1/pins_LONGER3D_LK.h" // STM32F1 env:STM32F103VE_longer env:STM32F103VE_longer_maple #elif MB(CCROBOT_MEEB_3DP) - #include "stm32f1/pins_CCROBOT_MEEB_3DP.h" // STM32F1 env:STM32F103RC_meeb_maple + #include "stm32f1/pins_CCROBOT_MEEB_3DP.h" // STM32F1 env:STM32F103RC_meeb_maple #elif MB(CHITU3D_V5) - #include "stm32f1/pins_CHITU3D_V5.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple env:chitu_v5_gpio_init env:chitu_v5_gpio_init_maple + #include "stm32f1/pins_CHITU3D_V5.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple env:chitu_v5_gpio_init env:chitu_v5_gpio_init_maple #elif MB(CHITU3D_V6) - #include "stm32f1/pins_CHITU3D_V6.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple + #include "stm32f1/pins_CHITU3D_V6.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple #elif MB(CHITU3D_V9) - #include "stm32f1/pins_CHITU3D_V9.h" // STM32F1 env:chitu_f103 env:chitu_f103_maple + #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:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple + #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple #elif MB(CREALITY_V4210) - #include "stm32f1/pins_CREALITY_V4210.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple + #include "stm32f1/pins_CREALITY_V4210.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple #elif MB(CREALITY_V425) - #include "stm32f1/pins_CREALITY_V425.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple + #include "stm32f1/pins_CREALITY_V425.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple #elif MB(CREALITY_V422) - #include "stm32f1/pins_CREALITY_V422.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple + #include "stm32f1/pins_CREALITY_V422.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple #elif MB(CREALITY_V423) - #include "stm32f1/pins_CREALITY_V423.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer + #include "stm32f1/pins_CREALITY_V423.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer #elif MB(CREALITY_V427) - #include "stm32f1/pins_CREALITY_V427.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple + #include "stm32f1/pins_CREALITY_V427.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_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:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple + #include "stm32f1/pins_CREALITY_V431.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple #elif MB(CREALITY_V452) - #include "stm32f1/pins_CREALITY_V452.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple + #include "stm32f1/pins_CREALITY_V452.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple #elif MB(CREALITY_V453) - #include "stm32f1/pins_CREALITY_V453.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple + #include "stm32f1/pins_CREALITY_V453.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple #elif MB(CREALITY_V24S1) - #include "stm32f1/pins_CREALITY_V24S1.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple + #include "stm32f1/pins_CREALITY_V24S1.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple #elif MB(CREALITY_V24S1_301) - #include "stm32f1/pins_CREALITY_V24S1_301.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple + #include "stm32f1/pins_CREALITY_V24S1_301.h" // STM32F1 env:STM32F103RE_creality env:STM32F103RE_creality_xfer env:STM32F103RC_creality env:STM32F103RC_creality_xfer env:STM32F103RE_creality_maple #elif MB(CREALITY_V25S1) - #include "stm32f1/pins_CREALITY_V25S1.h" // STM32F1 env:STM32F103RE_creality_smartPro env:STM32F103RE_creality_smartPro_maple + #include "stm32f1/pins_CREALITY_V25S1.h" // STM32F1 env:STM32F103RE_creality_smartPro env:STM32F103RE_creality_smartPro_maple #elif MB(CREALITY_V521) - #include "stm32f1/pins_CREALITY_V521.h" // STM32F103VE env:STM32F103VE_creality + #include "stm32f1/pins_CREALITY_V521.h" // STM32F1 env:STM32F103VE_creality #elif MB(TRIGORILLA_PRO) - #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro env:trigorilla_pro_maple env:trigorilla_pro_disk + #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro env:trigorilla_pro_maple env:trigorilla_pro_disk #elif MB(FLY_MINI) - #include "stm32f1/pins_FLY_MINI.h" // STM32F1 env:FLY_MINI env:FLY_MINI_maple + #include "stm32f1/pins_FLY_MINI.h" // STM32F1 env:FLY_MINI env:FLY_MINI_maple #elif MB(FLSUN_HISPEED) - #include "stm32f1/pins_FLSUN_HISPEED.h" // STM32F1 env:flsun_hispeedv1 + #include "stm32f1/pins_FLSUN_HISPEED.h" // STM32F1 env:flsun_hispeedv1 #elif MB(BEAST) - #include "stm32f1/pins_BEAST.h" // STM32F103VE? env:STM32F103VE env:STM32F103RE_maple + #include "stm32f1/pins_BEAST.h" // STM32F1 env:STM32F103VE env:STM32F103RE_maple #elif MB(MINGDA_MPX_ARM_MINI) - #include "stm32f1/pins_MINGDA_MPX_ARM_MINI.h" // STM32F1 env:mingda_mpx_arm_mini + #include "stm32f1/pins_MINGDA_MPX_ARM_MINI.h" // STM32F1 env:mingda_mpx_arm_mini #elif MB(ZONESTAR_ZM3E2) - #include "stm32f1/pins_ZM3E2_V1_0.h" // STM32F1 env:STM32F103RC_ZM3E2_USB env:STM32F103RC_ZM3E2_USB_maple + #include "stm32f1/pins_ZM3E2_V1_0.h" // STM32F1 env:STM32F103RC_ZM3E2_USB env:STM32F103RC_ZM3E2_USB_maple #elif MB(ZONESTAR_ZM3E4) - #include "stm32f1/pins_ZM3E4_V1_0.h" // STM32F1 env:STM32F103VC_ZM3E4_USB env:STM32F103VC_ZM3E4_USB_maple + #include "stm32f1/pins_ZM3E4_V1_0.h" // STM32F1 env:STM32F103VC_ZM3E4_USB env:STM32F103VC_ZM3E4_USB_maple #elif MB(ZONESTAR_ZM3E4V2) - #include "stm32f1/pins_ZM3E4_V2_0.h" // STM32F1 env:STM32F103VE_ZM3E4V2_USB env:STM32F103VE_ZM3E4V2_USB_maple + #include "stm32f1/pins_ZM3E4_V2_0.h" // STM32F1 env:STM32F103VE_ZM3E4V2_USB env:STM32F103VE_ZM3E4V2_USB_maple #elif MB(ERYONE_ERY32_MINI) - #include "stm32f1/pins_ERYONE_ERY32_MINI.h" // STM32F103VET6 env:ERYONE_ERY32_MINI_maple + #include "stm32f1/pins_ERYONE_ERY32_MINI.h" // STM32F1 env:ERYONE_ERY32_MINI_maple #elif MB(PANDA_PI_V29) - #include "stm32f1/pins_PANDA_PI_V29.h" // STM32F103RCT6 env:PANDA_PI_V29 + #include "stm32f1/pins_PANDA_PI_V29.h" // STM32F1 env:PANDA_PI_V29 #elif MB(SOVOL_V131) - #include "stm32f1/pins_SOVOL_V131.h" // GD32F1 env:GD32F103RET6_sovol_maple + #include "gd32f1/pins_SOVOL_V131.h" // GD32F1 env:GD32F103RET6_sovol_maple // // ARM Cortex-M4F // #elif MB(TEENSY31_32) - #include "teensy3/pins_TEENSY31_32.h" // TEENSY31_32 env:teensy31 + #include "teensy3/pins_TEENSY31_32.h" // TEENSY31_32 env:teensy31 #elif MB(TEENSY35_36) - #include "teensy3/pins_TEENSY35_36.h" // TEENSY35_36 env:teensy35 env:teensy36 + #include "teensy3/pins_TEENSY35_36.h" // TEENSY35_36 env:teensy35 env:teensy36 // // STM32 ARM Cortex-M4F // #elif MB(ARMED) - #include "stm32f4/pins_ARMED.h" // STM32F4 env:ARMED + #include "stm32f4/pins_ARMED.h" // STM32F4 env:ARMED #elif MB(RUMBA32_V1_0, RUMBA32_V1_1) - #include "stm32f4/pins_RUMBA32_AUS3D.h" // STM32F4 env:rumba32 + #include "stm32f4/pins_RUMBA32_AUS3D.h" // STM32F4 env:rumba32 #elif MB(RUMBA32_MKS) - #include "stm32f4/pins_RUMBA32_MKS.h" // STM32F4 env:rumba32 + #include "stm32f4/pins_RUMBA32_MKS.h" // STM32F4 env:rumba32 #elif MB(RUMBA32_BTT) - #include "stm32f4/pins_RUMBA32_BTT.h" // STM32F4 env:rumba32 + #include "stm32f4/pins_RUMBA32_BTT.h" // STM32F4 env:rumba32 #elif MB(BLACK_STM32F407VE) - #include "stm32f4/pins_BLACK_STM32F407VE.h" // STM32F4 env:STM32F407VE_black + #include "stm32f4/pins_BLACK_STM32F407VE.h" // STM32F4 env:STM32F407VE_black #elif MB(BTT_SKR_PRO_V1_1) - #include "stm32f4/pins_BTT_SKR_PRO_V1_1.h" // STM32F4 env:BIGTREE_SKR_PRO env:BIGTREE_SKR_PRO_usb_flash_drive + #include "stm32f4/pins_BTT_SKR_PRO_V1_1.h" // STM32F4 env:BIGTREE_SKR_PRO env:BIGTREE_SKR_PRO_usb_flash_drive #elif MB(BTT_SKR_PRO_V1_2) - #include "stm32f4/pins_BTT_SKR_PRO_V1_2.h" // STM32F4 env:BIGTREE_SKR_PRO env:BIGTREE_SKR_PRO_usb_flash_drive + #include "stm32f4/pins_BTT_SKR_PRO_V1_2.h" // STM32F4 env:BIGTREE_SKR_PRO env:BIGTREE_SKR_PRO_usb_flash_drive #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 + #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 env:BIGTREE_BTT002_VET6 + #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 + #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 env:BIGTREE_SKR_2_USB_debug + #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 env:BIGTREE_SKR_2_F429 env:BIGTREE_SKR_2_F429_USB env:BIGTREE_SKR_2_F429_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:STM32F446ZE_btt env:STM32F446ZE_btt_USB + #include "stm32f4/pins_BTT_OCTOPUS_V1_0.h" // STM32F4 env:STM32F446ZE_btt env:STM32F446ZE_btt_usb_flash_drive #elif MB(BTT_OCTOPUS_V1_1) - #include "stm32f4/pins_BTT_OCTOPUS_V1_1.h" // STM32F4 env:STM32F446ZE_btt env:STM32F446ZE_btt_USB env:STM32F429ZG_btt env:STM32F429ZG_btt_USB env:STM32F407ZE_btt env:STM32F407ZE_btt_USB + #include "stm32f4/pins_BTT_OCTOPUS_V1_1.h" // STM32F4 env:STM32F446ZE_btt env:STM32F446ZE_btt_usb_flash_drive env:STM32F429ZG_btt env:STM32F429ZG_btt_usb_flash_drive env:STM32F407ZE_btt env:STM32F407ZE_btt_usb_flash_drive #elif MB(BTT_OCTOPUS_PRO_V1_0) - #include "stm32f4/pins_BTT_OCTOPUS_PRO_V1_0.h" // STM32F4 env:STM32F446ZE_btt env:STM32F446ZE_btt_USB env:STM32F429ZG_btt env:STM32F429ZG_btt_USB env:STM32H723Zx_btt + #include "stm32f4/pins_BTT_OCTOPUS_PRO_V1_0.h" // STM32F4 env:STM32F446ZE_btt env:STM32F446ZE_btt_usb_flash_drive env:STM32F429ZG_btt env:STM32F429ZG_btt_usb_flash_drive env:STM32H723ZE_btt #elif MB(LERDGE_K) - #include "stm32f4/pins_LERDGE_K.h" // STM32F4 env:LERDGEK env:LERDGEK_usb_flash_drive + #include "stm32f4/pins_LERDGE_K.h" // STM32F4 env:LERDGEK env:LERDGEK_usb_flash_drive #elif MB(LERDGE_S) - #include "stm32f4/pins_LERDGE_S.h" // STM32F4 env:LERDGES env:LERDGES_usb_flash_drive + #include "stm32f4/pins_LERDGE_S.h" // STM32F4 env:LERDGES env:LERDGES_usb_flash_drive #elif MB(LERDGE_X) - #include "stm32f4/pins_LERDGE_X.h" // STM32F4 env:LERDGEX env:LERDGEX_usb_flash_drive -#elif MB(VAKE403D) - #include "stm32f4/pins_VAKE403D.h" // STM32F4 + #include "stm32f4/pins_LERDGE_X.h" // STM32F4 env:LERDGEX env:LERDGEX_usb_flash_drive #elif MB(FYSETC_S6) - #include "stm32f4/pins_FYSETC_S6.h" // STM32F4 env:FYSETC_S6 env:FYSETC_S6_8000 + #include "stm32f4/pins_FYSETC_S6.h" // STM32F4 env:FYSETC_S6 env:FYSETC_S6_8000 #elif MB(FYSETC_S6_V2_0) - #include "stm32f4/pins_FYSETC_S6_V2_0.h" // STM32F4 env:FYSETC_S6 env:FYSETC_S6_8000 + #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 + #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 + #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 + #include "stm32f4/pins_FLYF407ZG.h" // STM32F4 env:FLYF407ZG #elif MB(MKS_ROBIN2) - #include "stm32f4/pins_MKS_ROBIN2.h" // STM32F4 env:mks_robin2 + #include "stm32f4/pins_MKS_ROBIN2.h" // STM32F4 env:mks_robin2 #elif MB(MKS_ROBIN_PRO_V2) - #include "stm32f4/pins_MKS_ROBIN_PRO_V2.h" // STM32F4 env:mks_robin_pro2 + #include "stm32f4/pins_MKS_ROBIN_PRO_V2.h" // STM32F4 env:mks_robin_pro2 #elif MB(MKS_ROBIN_NANO_V3) - #include "stm32f4/pins_MKS_ROBIN_NANO_V3.h" // STM32F4 env:mks_robin_nano_v3 env:mks_robin_nano_v3_usb_flash_drive env:mks_robin_nano_v3_usb_flash_drive_msc + #include "stm32f4/pins_MKS_ROBIN_NANO_V3.h" // STM32F4 env:mks_robin_nano_v3 env:mks_robin_nano_v3_usb_flash_drive env:mks_robin_nano_v3_usb_flash_drive_msc #elif MB(MKS_ROBIN_NANO_V3_1) - #include "stm32f4/pins_MKS_ROBIN_NANO_V3.h" // STM32F4 env:mks_robin_nano_v3_1 env:mks_robin_nano_v3_1_usb_flash_drive env:mks_robin_nano_v3_1_usb_flash_drive_msc + #include "stm32f4/pins_MKS_ROBIN_NANO_V3.h" // STM32F4 env:mks_robin_nano_v3_1 env:mks_robin_nano_v3_1_usb_flash_drive env:mks_robin_nano_v3_1_usb_flash_drive_msc #elif MB(ANET_ET4) - #include "stm32f4/pins_ANET_ET4.h" // STM32F4 env:Anet_ET4_no_bootloader env:Anet_ET4_OpenBLT + #include "stm32f4/pins_ANET_ET4.h" // STM32F4 env:Anet_ET4_no_bootloader env:Anet_ET4_OpenBLT #elif MB(ANET_ET4P) - #include "stm32f4/pins_ANET_ET4P.h" // STM32F4 env:Anet_ET4_no_bootloader env:Anet_ET4_OpenBLT + #include "stm32f4/pins_ANET_ET4P.h" // STM32F4 env:Anet_ET4_no_bootloader env:Anet_ET4_OpenBLT #elif MB(FYSETC_CHEETAH_V20) - #include "stm32f4/pins_FYSETC_CHEETAH_V20.h" // STM32F4 env:FYSETC_CHEETAH_V20 + #include "stm32f4/pins_FYSETC_CHEETAH_V20.h" // STM32F4 env:FYSETC_CHEETAH_V20 #elif MB(MKS_MONSTER8_V1) - #include "stm32f4/pins_MKS_MONSTER8_V1.h" // STM32F4 env:mks_monster8 env:mks_monster8_usb_flash_drive env:mks_monster8_usb_flash_drive_msc + #include "stm32f4/pins_MKS_MONSTER8_V1.h" // STM32F4 env:mks_monster8 env:mks_monster8_usb_flash_drive env:mks_monster8_usb_flash_drive_msc #elif MB(MKS_MONSTER8_V2) - #include "stm32f4/pins_MKS_MONSTER8_V2.h" // STM32F4 env:mks_monster8 env:mks_monster8_usb_flash_drive env:mks_monster8_usb_flash_drive_msc + #include "stm32f4/pins_MKS_MONSTER8_V2.h" // STM32F4 env:mks_monster8 env:mks_monster8_usb_flash_drive env:mks_monster8_usb_flash_drive_msc #elif MB(TH3D_EZBOARD_V2) - #include "stm32f4/pins_TH3D_EZBOARD_V2.h" // STM32F4 env:TH3D_EZBoard_V2_no_bootloader env:TH3D_EZBoard_V2_OpenBLT + #include "stm32f4/pins_TH3D_EZBOARD_V2.h" // STM32F4 env:TH3D_EZBoard_V2_no_bootloader env:TH3D_EZBoard_V2_OpenBLT #elif MB(OPULO_LUMEN_REV3) - #include "stm32f4/pins_OPULO_LUMEN_REV3.h" // STM32F4 env:Opulo_Lumen_REV3 + #include "stm32f4/pins_OPULO_LUMEN_REV3.h" // STM32F4 env:Opulo_Lumen_REV3 #elif MB(MKS_ROBIN_NANO_V1_3_F4) - #include "stm32f4/pins_MKS_ROBIN_NANO_V1_3_F4.h" // STM32F4 env:mks_robin_nano_v1_3_f4 env:mks_robin_nano_v1_3_f4_usbmod + #include "stm32f4/pins_MKS_ROBIN_NANO_V1_3_F4.h" // STM32F4 env:mks_robin_nano_v1_3_f4 env:mks_robin_nano_v1_3_f4_usbmod #elif MB(MKS_EAGLE) - #include "stm32f4/pins_MKS_EAGLE.h" // STM32F4 env:mks_eagle + #include "stm32f4/pins_MKS_EAGLE.h" // STM32F4 env:mks_eagle env:mks_eagle_usb_flash_drive env:mks_eagle_usb_flash_drive_msc #elif MB(ARTILLERY_RUBY) - #include "stm32f4/pins_ARTILLERY_RUBY.h" // STM32F4 env:Artillery_Ruby + #include "stm32f4/pins_ARTILLERY_RUBY.h" // STM32F4 env:Artillery_Ruby #elif MB(CREALITY_V24S1_301F4) - #include "stm32f4/pins_CREALITY_V24S1_301F4.h" // STM32F4 env:STM32F401RC_creality env:STM32F401RC_creality_jlink env:STM32F401RC_creality_stlink + #include "stm32f4/pins_CREALITY_V24S1_301F4.h" // STM32F4 env:STM32F401RC_creality env:STM32F401RC_creality_nobootloader env:STM32F401RC_creality_jlink env:STM32F401RC_creality_stlink #elif MB(OPULO_LUMEN_REV4) - #include "stm32f4/pins_OPULO_LUMEN_REV4.h" // STM32F4 env:Opulo_Lumen_REV4 + #include "stm32f4/pins_OPULO_LUMEN_REV4.h" // STM32F4 env:Opulo_Lumen_REV4 #elif MB(FYSETC_SPIDER_KING407) - #include "stm32f4/pins_FYSETC_SPIDER_KING407.h" // STM32F4 env:FYSETC_SPIDER_KING407 + #include "stm32f4/pins_FYSETC_SPIDER_KING407.h" // STM32F4 env:FYSETC_SPIDER_KING407 #elif MB(MKS_SKIPR_V1) - #include "stm32f4/pins_MKS_SKIPR_V1_0.h" // STM32F4 env:mks_skipr_v1 env:mks_skipr_v1_nobootloader + #include "stm32f4/pins_MKS_SKIPR_V1_0.h" // STM32F4 env:mks_skipr_v1 env:mks_skipr_v1_nobootloader #elif MB(TRONXY_V10) - #include "stm32f4/pins_TRONXY_V10.h" // STM32F4 env:STM32F446_tronxy + #include "stm32f4/pins_TRONXY_V10.h" // STM32F4 env:STM32F446_tronxy +#elif MB(CREALITY_F401RE) + #include "stm32f4/pins_CREALITY_F401.h" // STM32F4 env:STM32F401RE_creality // -// ARM Cortex M7 +// ARM Cortex-M7 // #elif MB(REMRAM_V1) - #include "stm32f7/pins_REMRAM_V1.h" // STM32F7 env:REMRAM_V1 + #include "stm32f7/pins_REMRAM_V1.h" // STM32F7 env:REMRAM_V1 #elif MB(NUCLEO_F767ZI) - #include "stm32f7/pins_NUCLEO_F767ZI.h" // STM32F7 env:NUCLEO_F767ZI + #include "stm32f7/pins_NUCLEO_F767ZI.h" // STM32F7 env:NUCLEO_F767ZI #elif MB(BTT_SKR_SE_BX_V2) - #include "stm32h7/pins_BTT_SKR_SE_BX_V2.h" // STM32H7 env:BTT_SKR_SE_BX + #include "stm32h7/pins_BTT_SKR_SE_BX_V2.h" // STM32H7 env:BTT_SKR_SE_BX #elif MB(BTT_SKR_SE_BX_V3) - #include "stm32h7/pins_BTT_SKR_SE_BX_V3.h" // STM32H7 env:BTT_SKR_SE_BX + #include "stm32h7/pins_BTT_SKR_SE_BX_V3.h" // STM32H7 env:BTT_SKR_SE_BX #elif MB(BTT_SKR_V3_0) - #include "stm32h7/pins_BTT_SKR_V3_0.h" // STM32H7 env:STM32H723Vx_btt env:STM32H743Vx_btt + #include "stm32h7/pins_BTT_SKR_V3_0.h" // STM32H7 env:STM32H743VI_btt env:STM32H723VG_btt #elif MB(BTT_SKR_V3_0_EZ) - #include "stm32h7/pins_BTT_SKR_V3_0_EZ.h" // STM32H7 env:STM32H723Vx_btt env:STM32H743Vx_btt + #include "stm32h7/pins_BTT_SKR_V3_0_EZ.h" // STM32H7 env:STM32H743VI_btt env:STM32H723VG_btt #elif MB(BTT_OCTOPUS_MAX_EZ_V1_0) - #include "stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h" // STM32H7 env:STM32H723Vx_btt env:STM32H723Zx_btt + #include "stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h" // STM32H7 env:STM32H723ZE_btt #elif MB(TEENSY41) - #include "teensy4/pins_TEENSY41.h" // Teensy-4.x env:teensy41 + #include "teensy4/pins_TEENSY41.h" // Teensy-4.x env:teensy41 #elif MB(T41U5XBB) - #include "teensy4/pins_T41U5XBB.h" // Teensy-4.x env:teensy41 + #include "teensy4/pins_T41U5XBB.h" // Teensy-4.x env:teensy41 // // Espressif ESP32 // #elif MB(ESPRESSIF_ESP32) - #include "esp32/pins_ESP32.h" // ESP32 env:esp32 + #include "esp32/pins_ESP32.h" // ESP32 env:esp32 #elif MB(MRR_ESPA) - #include "esp32/pins_MRR_ESPA.h" // ESP32 env:esp32 + #include "esp32/pins_MRR_ESPA.h" // ESP32 env:esp32 #elif MB(MRR_ESPE) - #include "esp32/pins_MRR_ESPE.h" // ESP32 env:esp32 + #include "esp32/pins_MRR_ESPE.h" // ESP32 env:esp32 #elif MB(E4D_BOX) - #include "esp32/pins_E4D.h" // ESP32 env:esp32 + #include "esp32/pins_E4D.h" // ESP32 env:esp32 #elif MB(RESP32_CUSTOM) - #include "esp32/pins_RESP32_CUSTOM.h" // ESP32 env:esp32 + #include "esp32/pins_RESP32_CUSTOM.h" // ESP32 env:esp32 #elif MB(FYSETC_E4) - #include "esp32/pins_FYSETC_E4.h" // ESP32 env:FYSETC_E4 + #include "esp32/pins_FYSETC_E4.h" // ESP32 env:FYSETC_E4 #elif MB(PANDA_ZHU) - #include "esp32/pins_PANDA_ZHU.h" // ESP32 env:PANDA + #include "esp32/pins_PANDA_ZHU.h" // ESP32 env:PANDA #elif MB(PANDA_M4) - #include "esp32/pins_PANDA_M4.h" // ESP32 env:PANDA + #include "esp32/pins_PANDA_M4.h" // ESP32 env:PANDA #elif MB(MKS_TINYBEE) - #include "esp32/pins_MKS_TINYBEE.h" // ESP32 env:mks_tinybee + #include "esp32/pins_MKS_TINYBEE.h" // ESP32 env:mks_tinybee #elif MB(ENWI_ESPNP) - #include "esp32/pins_ENWI_ESPNP.h" // ESP32 env:esp32 + #include "esp32/pins_ENWI_ESPNP.h" // ESP32 env:esp32 // // Adafruit Grand Central M4 (SAMD51 ARM Cortex-M4) // #elif MB(AGCM4_RAMPS_144) - #include "samd/pins_RAMPS_144.h" // SAMD51 env:SAMD51_grandcentral_m4 + #include "samd/pins_RAMPS_144.h" // SAMD51 env:SAMD51_grandcentral_m4 #elif MB(BRICOLEMON_V1_0) - #include "samd/pins_BRICOLEMON_V1_0.h" // SAMD51 env:SAMD51_grandcentral_m4 + #include "samd/pins_BRICOLEMON_V1_0.h" // SAMD51 env:SAMD51_grandcentral_m4 #elif MB(BRICOLEMON_LITE_V1_0) - #include "samd/pins_BRICOLEMON_LITE_V1_0.h" // SAMD51 env:SAMD51_grandcentral_m4 + #include "samd/pins_BRICOLEMON_LITE_V1_0.h" // SAMD51 env:SAMD51_grandcentral_m4 // // ReprapWorld Minitronics (SAMD21) // #elif MB(MINITRONICS20) - #include "samd/pins_MINITRONICS20.h" // SAMD21 env:SAMD21_minitronics20 + #include "samd/pins_MINITRONICS20.h" // SAMD21 env:SAMD21_minitronics20 // // Custom board (with custom PIO env) // #elif MB(CUSTOM) - #include "pins_custom.h" // env:custom + #include "pins_custom.h" // env:custom // // Linux Native Debug board // #elif MB(SIMULATED) - #include "linux/pins_RAMPS_LINUX.h" // Native or Simulation lin:linux_native mac:simulator_macos_debug mac:simulator_macos_release win:simulator_windows lin:simulator_linux_debug lin:simulator_linux_release + #include "linux/pins_RAMPS_LINUX.h" // Native or Simulation lin:linux_native mac:simulator_macos_debug mac:simulator_macos_release win:simulator_windows lin:simulator_linux_debug lin:simulator_linux_release #else @@ -844,43 +848,45 @@ #define BOARD_BTT_SKR_SE_BX 99924 #define BOARD_MKS_MONSTER8 99925 #define BOARD_LINUX_RAMPS 99926 + #define BOARD_BTT_MANTA_M4P_V1_0 99927 + #define BOARD_VAKE403D 99928 #if MB(MKS_13) - #error "BOARD_MKS_13 has been renamed BOARD_MKS_GEN_13. Please update your configuration." + #error "BOARD_MKS_13 is now BOARD_MKS_GEN_13. Please update your configuration." #elif MB(TRIGORILLA) - #error "BOARD_TRIGORILLA has been renamed BOARD_TRIGORILLA_13. Please update your configuration." + #error "BOARD_TRIGORILLA is now BOARD_TRIGORILLA_13. Please update your configuration." #elif MB(RURAMPS4D) - #error "BOARD_RURAMPS4D has been renamed BOARD_RURAMPS4D_11. Please update your configuration." + #error "BOARD_RURAMPS4D is now BOARD_RURAMPS4D_11. Please update your configuration." #elif MB(FORMBOT_TREX2) - #error "FORMBOT_TREX2 has been renamed BOARD_FORMBOT_TREX2PLUS. Please update your configuration." + #error "FORMBOT_TREX2 is now BOARD_FORMBOT_TREX2PLUS. Please update your configuration." #elif MB(BIQU_SKR_V1_1) - #error "BOARD_BIQU_SKR_V1_1 has been renamed BOARD_BTT_SKR_V1_1. Please update your configuration." + #error "BOARD_BIQU_SKR_V1_1 is now BOARD_BTT_SKR_V1_1. Please update your configuration." #elif MB(BIGTREE_SKR_V1_1) - #error "BOARD_BIGTREE_SKR_V1_1 has been renamed BOARD_BTT_SKR_V1_1. Please update your configuration." + #error "BOARD_BIGTREE_SKR_V1_1 is now BOARD_BTT_SKR_V1_1. Please update your configuration." #elif MB(BIGTREE_SKR_V1_2) - #error "BOARD_BIGTREE_SKR_V1_2 has been renamed BOARD_BTT_SKR_V1_2. Please update your configuration." + #error "BOARD_BIGTREE_SKR_V1_2 is now BOARD_BTT_SKR_V1_2. Please update your configuration." #elif MB(BIGTREE_SKR_V1_3) - #error "BOARD_BIGTREE_SKR_V1_3 has been renamed BOARD_BTT_SKR_V1_3. Please update your configuration." + #error "BOARD_BIGTREE_SKR_V1_3 is now BOARD_BTT_SKR_V1_3. Please update your configuration." #elif MB(BIGTREE_SKR_V1_4) - #error "BOARD_BIGTREE_SKR_V1_4 has been renamed BOARD_BTT_SKR_V1_4. Please update your configuration." + #error "BOARD_BIGTREE_SKR_V1_4 is now BOARD_BTT_SKR_V1_4. Please update your configuration." #elif MB(BIGTREE_SKR_V1_4_TURBO) - #error "BOARD_BIGTREE_SKR_V1_4_TURBO has been renamed BOARD_BTT_SKR_V1_4_TURBO. Please update your configuration." + #error "BOARD_BIGTREE_SKR_V1_4_TURBO is now BOARD_BTT_SKR_V1_4_TURBO. Please update your configuration." #elif MB(BIGTREE_BTT002_V1_0) - #error "BOARD_BIGTREE_BTT002_V1_0 has been renamed BOARD_BTT_BTT002_V1_0. Please update your configuration." + #error "BOARD_BIGTREE_BTT002_V1_0 is now BOARD_BTT_BTT002_V1_0. Please update your configuration." #elif MB(BIGTREE_SKR_PRO_V1_1) - #error "BOARD_BIGTREE_SKR_PRO_V1_1 has been renamed BOARD_BTT_SKR_PRO_V1_1. Please update your configuration." + #error "BOARD_BIGTREE_SKR_PRO_V1_1 is now BOARD_BTT_SKR_PRO_V1_1. Please update your configuration." #elif MB(BIGTREE_SKR_MINI_V1_1) - #error "BOARD_BIGTREE_SKR_MINI_V1_1 has been renamed BOARD_BTT_SKR_MINI_V1_1. Please update your configuration." + #error "BOARD_BIGTREE_SKR_MINI_V1_1 is now BOARD_BTT_SKR_MINI_V1_1. Please update your configuration." #elif MB(BIGTREE_SKR_MINI_E3) - #error "BOARD_BIGTREE_SKR_MINI_E3 has been renamed BOARD_BTT_SKR_MINI_E3_V1_0. Please update your configuration." + #error "BOARD_BIGTREE_SKR_MINI_E3 is now BOARD_BTT_SKR_MINI_E3_V1_0. Please update your configuration." #elif MB(BIGTREE_SKR_E3_DIP) - #error "BOARD_BIGTREE_SKR_E3_DIP has been renamed BOARD_BTT_SKR_E3_DIP. Please update your configuration." + #error "BOARD_BIGTREE_SKR_E3_DIP is now BOARD_BTT_SKR_E3_DIP. Please update your configuration." #elif MB(STM32F1R) - #error "BOARD_STM32F1R has been renamed BOARD_STM32F103RE. Please update your configuration." + #error "BOARD_STM32F1R is now BOARD_STM32F103RE. Please update your configuration." #elif MB(STM32F103R) - #error "BOARD_STM32F103R has been renamed BOARD_STM32F103RE. Please update your configuration." + #error "BOARD_STM32F103R is now BOARD_STM32F103RE. Please update your configuration." #elif MOTHERBOARD == BOARD_ESP32 - #error "BOARD_ESP32 has been renamed BOARD_ESPRESSIF_ESP32. Please update your configuration." + #error "BOARD_ESP32 is now BOARD_ESPRESSIF_ESP32. Please update your configuration." #elif MB(STEVAL) #error "BOARD_STEVAL_3DP001V1 (BOARD_STEVAL) is no longer supported in Marlin." #elif MB(RUMBA32) @@ -901,6 +907,10 @@ #error "BOARD_MKS_MONSTER8 is now BOARD_MKS_MONSTER8_V1 or BOARD_MKS_MONSTER8_V2. Please update your configuration." #elif MB(LINUX_RAMPS) #error "BOARD_LINUX_RAMPS is now BOARD_SIMULATED. Please update your configuration." + #elif MB(BTT_MANTA_M4P_V1_0) + #error "BOARD_BTT_MANTA_M4P_V1_0 is now BOARD_BTT_MANTA_M4P_V2_1. Please update your configuration." + #elif MB(VAKE403D) + #error "BOARD_VAKE403D is no longer supported in Marlin." #elif defined(MOTHERBOARD) #error "Unknown MOTHERBOARD value set in Configuration.h." #else @@ -935,6 +945,8 @@ #undef BOARD_BTT_SKR_SE_BX #undef BOARD_MKS_MONSTER8 #undef BOARD_LINUX_RAMPS + #undef BOARD_BTT_MANTA_M4P_V1_0 + #undef BOARD_VAKE403D #endif diff --git a/Marlin/src/pins/pinsDebug.h b/Marlin/src/pins/pinsDebug.h index 56e1039c4eed..1abfd182d0bb 100644 --- a/Marlin/src/pins/pinsDebug.h +++ b/Marlin/src/pins/pinsDebug.h @@ -81,7 +81,6 @@ #define REPORT_NAME_DIGITAL(COUNTER, NAME) _ADD_PIN(NAME, COUNTER, true) #define REPORT_NAME_ANALOG(COUNTER, NAME) _ADD_PIN(analogInputToDigitalPin(NAME), COUNTER, false) - typedef struct { PGM_P const name; pin_t pin; @@ -100,7 +99,7 @@ const PinInfo pin_array[] PROGMEM = { */ #if SERIAL_IN_USE(0) - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) + #if ANY(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_0, 0, true }, { TXD_NAME_0, 1, true }, #elif AVR_ATmega1284_FAMILY @@ -113,7 +112,7 @@ const PinInfo pin_array[] PROGMEM = { #endif #if SERIAL_IN_USE(1) - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) + #if ANY(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_1, 19, true }, { TXD_NAME_1, 18, true }, #elif AVR_ATmega1284_FAMILY @@ -131,7 +130,7 @@ const PinInfo pin_array[] PROGMEM = { #endif #if SERIAL_IN_USE(2) - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) + #if ANY(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_2, 17, true }, { TXD_NAME_2, 16, true }, #elif defined(TARGET_LPC1768) @@ -146,7 +145,7 @@ const PinInfo pin_array[] PROGMEM = { #endif #if SERIAL_IN_USE(3) - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) + #if ANY(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_3, 15, true }, { TXD_NAME_3, 14, true }, #elif defined(TARGET_LPC1768) @@ -174,6 +173,8 @@ const PinInfo pin_array[] PROGMEM = { #define M43_NEVER_TOUCH(Q) false #endif +bool pin_is_protected(const pin_t pin); + static void print_input_or_output(const bool isout) { SERIAL_ECHOF(isout ? F("Output ") : F("Input ")); } @@ -204,13 +205,13 @@ inline void report_pin_state_extended(const pin_t pin, const bool ignore, const return true; }; - LOOP_L_N(x, COUNT(pin_array)) { // scan entire array and report all instances of this pin + for (uint8_t x = 0; x < COUNT(pin_array); ++x) { // scan entire array and report all instances of this pin if (GET_ARRAY_PIN(x) == pin) { if (!found) { // report digital and analog pin number only on the first time through if (start_string) SERIAL_ECHOF(start_string); SERIAL_ECHOPGM("PIN: "); PRINT_PIN(pin); - PRINT_PORT(pin); + print_port(pin); if (int8_t(DIGITAL_PIN_TO_ANALOG_PIN(pin)) >= 0) PRINT_PIN_ANALOG(pin); // analog pin number else SERIAL_ECHO_SP(8); // add padding if not an analog pin } @@ -258,7 +259,7 @@ inline void report_pin_state_extended(const pin_t pin, const bool ignore, const if (start_string) SERIAL_ECHOF(start_string); SERIAL_ECHOPGM("PIN: "); PRINT_PIN(pin); - PRINT_PORT(pin); + print_port(pin); if (int8_t(DIGITAL_PIN_TO_ANALOG_PIN(pin)) >= 0) PRINT_PIN_ANALOG(pin); // analog pin number else SERIAL_ECHO_SP(8); // add padding if not an analog pin SERIAL_ECHOPGM(""); diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 39e07c739a23..fa6cbf49b945 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -489,18 +489,27 @@ REPORT_NAME_DIGITAL(__LINE__, EXP3_10_PIN) #endif -#if _EXISTS(TMC_SW_MISO) - REPORT_NAME_DIGITAL(__LINE__, TMC_SW_MISO) +#if _EXISTS(TMC_SPI_MISO) + REPORT_NAME_DIGITAL(__LINE__, TMC_SPI_MISO) #endif -#if _EXISTS(TMC_SW_MOSI) - REPORT_NAME_DIGITAL(__LINE__, TMC_SW_MOSI) +#if _EXISTS(TMC_SPI_MOSI) + REPORT_NAME_DIGITAL(__LINE__, TMC_SPI_MOSI) #endif -#if _EXISTS(TMC_SW_SCK) - REPORT_NAME_DIGITAL(__LINE__, TMC_SW_SCK) +#if _EXISTS(TMC_SPI_SCK) + REPORT_NAME_DIGITAL(__LINE__, TMC_SPI_SCK) #endif #if _EXISTS(TFTGLCD_CS) REPORT_NAME_DIGITAL(__LINE__, TFTGLCD_CS) #endif +#if _EXISTS(TFTGLCD_SCK) + REPORT_NAME_DIGITAL(__LINE__, TFTGLCD_SCK) +#endif +#if _EXISTS(TFTGLCD_MISO) + REPORT_NAME_DIGITAL(__LINE__, TFTGLCD_MISO) +#endif +#if _EXISTS(TFTGLCD_MOSI) + REPORT_NAME_DIGITAL(__LINE__, TFTGLCD_MOSI) +#endif // // E Multiplexing @@ -730,8 +739,8 @@ // // Fans // -#if PIN_EXISTS(FAN) - REPORT_NAME_DIGITAL(__LINE__, FAN_PIN) +#if PIN_EXISTS(FAN0) + REPORT_NAME_DIGITAL(__LINE__, FAN0_PIN) #endif #if PIN_EXISTS(FAN1) REPORT_NAME_DIGITAL(__LINE__, FAN1_PIN) @@ -920,8 +929,8 @@ #if _EXISTS(LCD_PINS_D7) REPORT_NAME_DIGITAL(__LINE__, LCD_PINS_D7) #endif -#if _EXISTS(LCD_PINS_ENABLE) - REPORT_NAME_DIGITAL(__LINE__, LCD_PINS_ENABLE) +#if _EXISTS(LCD_PINS_EN) + REPORT_NAME_DIGITAL(__LINE__, LCD_PINS_EN) #endif #if _EXISTS(LCD_PINS_RS) REPORT_NAME_DIGITAL(__LINE__, LCD_PINS_RS) diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 6191532b1c11..199ddc335543 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -377,10 +377,9 @@ #undef W_SERIAL_RX_PIN #endif -#ifndef FAN_PIN - #define FAN_PIN -1 +#ifndef FAN0_PIN + #define FAN0_PIN -1 #endif -#define FAN0_PIN FAN_PIN #ifndef FAN1_PIN #define FAN1_PIN -1 #endif @@ -483,8 +482,20 @@ #define SUICIDE_PIN_STATE LOW #endif -#ifndef NUM_SERVO_PLUGS +#if PIN_EXISTS(SERVO5) + #define NUM_SERVO_PLUGS 6 +#elif PIN_EXISTS(SERVO4) + #define NUM_SERVO_PLUGS 5 +#elif PIN_EXISTS(SERVO3) #define NUM_SERVO_PLUGS 4 +#elif PIN_EXISTS(SERVO2) + #define NUM_SERVO_PLUGS 3 +#elif PIN_EXISTS(SERVO1) + #define NUM_SERVO_PLUGS 2 +#elif PIN_EXISTS(SERVO0) + #define NUM_SERVO_PLUGS 1 +#else + #define NUM_SERVO_PLUGS 0 #endif // Only used within pins files @@ -493,7 +504,7 @@ #undef NEEDS_Z_MINMAX // -// Assign endstop pins for boards with only 3 connectors +// Assign endstop pins, with handling for boards that have only 3 connectors // #ifdef X_STOP_PIN #if X_HOME_TO_MIN diff --git a/Marlin/src/pins/rambo/env_validate.h b/Marlin/src/pins/rambo/env_validate.h index 84cf8392cdfc..ce2818f596d3 100644 --- a/Marlin/src/pins/rambo/env_validate.h +++ b/Marlin/src/pins/rambo/env_validate.h @@ -19,8 +19,11 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino Mega 2560 or Rambo' in 'Tools > Board.'" #endif + +#endif diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index c28fbd059c60..ada4885752a3 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -118,21 +118,24 @@ // #define TEMP_0_PIN 0 // Analog Input, Header J2 #define TEMP_1_PIN 1 // Analog Input, Header J3 -#define TEMP_BOARD_PIN 91 // Onboard thermistor, 100k TDK NTCG104LH104JT1 #define TEMP_BED_PIN 2 // Analog Input, Header J6 #define TEMP_PROBE_PIN 3 // Analog Input, Header J15 +#ifndef TEMP_BOARD_PIN + #define TEMP_BOARD_PIN 91 // Onboard thermistor, 100k TDK NTCG104LH104JT1 +#endif + // // Heaters / Fans // #define HEATER_0_PIN 3 #define HEATER_BED_PIN 4 -#ifndef FAN_PIN +#ifndef FAN0_PIN #ifdef MK3_FAN_PINS - #define FAN_PIN 6 + #define FAN0_PIN 6 #else - #define FAN_PIN 8 + #define FAN0_PIN 8 #endif #endif @@ -186,10 +189,12 @@ // // M3/M4/M5 - Spindle/Laser Control // -// use P1 connector for spindle pins -#define SPINDLE_LASER_PWM_PIN EXP1_02_PIN // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 18 // Pullup! -#define SPINDLE_DIR_PIN 19 +#if HAS_CUTTER + // Use P1 connector for spindle pins + #define SPINDLE_LASER_PWM_PIN EXP1_02_PIN // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 18 // Pullup! + #define SPINDLE_DIR_PIN 19 +#endif // // Průša i3 MK2 Multiplexer Support @@ -203,6 +208,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL #define KILL_PIN 32 @@ -211,13 +217,13 @@ #if ENABLED(CR10_STOCKDISPLAY) #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN #else #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #define LCD_PINS_D5 EXP1_06_PIN #define LCD_PINS_D6 EXP1_07_PIN diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index dc91c47e9a1b..75d0974b0a36 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -135,8 +135,8 @@ #define HEATER_0_PIN 3 #define HEATER_BED_PIN 4 -#ifndef FAN_PIN - #define FAN_PIN 8 +#ifndef FAN0_PIN + #define FAN0_PIN 8 #endif #define FAN1_PIN 6 @@ -153,10 +153,12 @@ // // M3/M4/M5 - Spindle/Laser Control // -// use P1 connector for spindle pins -#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 18 // Pullup! -#define SPINDLE_DIR_PIN 19 +#if HAS_CUTTER + // Use P1 connector for spindle pins + #define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 18 // Pullup! + #define SPINDLE_DIR_PIN 19 +#endif // // Průša i3 MK2 Multiplexer Support @@ -167,9 +169,40 @@ #define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 #endif +// +// EXP Headers +// +#define EXP1_01_PIN 84 // PH2 +#define EXP1_02_PIN 9 // PH6 +#define EXP1_03_PIN 18 // TX1 +#define EXP1_04_PIN 82 // PD5 +#define EXP1_05_PIN 19 // RX1 +#define EXP1_06_PIN 70 // PG4 +#define EXP1_07_PIN 85 // PH7 +#define EXP1_08_PIN 71 // PG3 + +#define EXP2_01_PIN 50 // MISO +#define EXP2_02_PIN 52 // SCK +#define EXP2_03_PIN 72 // PJ2 +#define EXP2_04_PIN 53 // SDSS +#define EXP2_05_PIN 14 // TX3 +#define EXP2_06_PIN 51 // MOSI +#define EXP2_07_PIN 15 // RX3 +#define EXP2_08_PIN -1 // RESET + +#define EXP3_01_PIN 62 // PK0 (A8) +#define EXP3_02_PIN 76 // PJ5 +#define EXP3_03_PIN 20 // SDA +#define EXP3_04_PIN -1 // GND +#define EXP3_05_PIN 21 // SCL +#define EXP3_06_PIN 16 // RX2 +#define EXP3_07_PIN -1 // GND +#define EXP3_08_PIN 17 // TX2 + // // LCD / Controller // + #if ANY(HAS_WIRED_LCD, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) #define KILL_PIN 32 @@ -177,26 +210,26 @@ #if ANY(IS_ULTIPANEL, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS 85 - #define LCD_PINS_ENABLE 71 - #define LCD_PINS_D4 70 - #define BTN_EN1 18 - #define BTN_EN2 19 + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_EN EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN #else - #define LCD_PINS_RS 82 - #define LCD_PINS_ENABLE 18 // On 0.6b, use 61 - #define LCD_PINS_D4 19 // On 0.6b, use 59 - #define LCD_PINS_D5 70 - #define LCD_PINS_D6 85 - #define LCD_PINS_D7 71 - #define BTN_EN1 14 - #define BTN_EN2 72 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_EN EXP1_03_PIN // On 0.6b, use 61 + #define LCD_PINS_D4 EXP1_05_PIN // On 0.6b, use 59 + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN #endif - #define BTN_ENC 9 // AUX-2 - #define BEEPER_PIN 84 // AUX-4 + #define BTN_ENC EXP1_02_PIN // AUX-2 + #define BEEPER_PIN EXP1_01_PIN // AUX-4 - #define SD_DETECT_PIN 15 + #define SD_DETECT_PIN EXP2_07_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder diff --git a/Marlin/src/pins/rambo/pins_MINIRAMBO.h b/Marlin/src/pins/rambo/pins_MINIRAMBO.h index 353fbd664111..f176efcc7111 100644 --- a/Marlin/src/pins/rambo/pins_MINIRAMBO.h +++ b/Marlin/src/pins/rambo/pins_MINIRAMBO.h @@ -109,8 +109,8 @@ #endif #define HEATER_BED_PIN 4 -#ifndef FAN_PIN - #define FAN_PIN 8 +#ifndef FAN0_PIN + #define FAN0_PIN 8 #endif #define FAN1_PIN 6 @@ -126,10 +126,12 @@ // // M3/M4/M5 - Spindle/Laser Control // -// use P1 connector for spindle pins -#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 18 // Pullup! -#define SPINDLE_DIR_PIN 19 +#if HAS_CUTTER + // Use P1 connector for spindle pins + #define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 18 // Pullup! + #define SPINDLE_DIR_PIN 19 +#endif // // Průša i3 MK2 Multiplexer Support @@ -145,6 +147,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL #if !MB(MINIRAMBO_10A) @@ -162,7 +165,7 @@ #define BTN_ENC 21 #define LCD_PINS_RS 38 - #define LCD_PINS_ENABLE 5 + #define LCD_PINS_EN 5 #define LCD_PINS_D4 14 #define LCD_PINS_D5 15 #define LCD_PINS_D6 32 @@ -170,7 +173,7 @@ #define SD_DETECT_PIN 72 - #else // !MINIRAMBO_10A + #else // !MINIRAMBO_10A // AUX-4 #define BEEPER_PIN 84 @@ -181,7 +184,7 @@ #define BTN_ENC 9 #define LCD_PINS_RS 82 - #define LCD_PINS_ENABLE 18 + #define LCD_PINS_EN 18 #define LCD_PINS_D4 19 #define LCD_PINS_D5 70 #define LCD_PINS_D6 85 diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index 3a26811538c9..8ea3c15b4620 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -140,8 +140,8 @@ #define HEATER_2_PIN 6 #define HEATER_BED_PIN 3 -#ifndef FAN_PIN - #define FAN_PIN 8 +#ifndef FAN0_PIN + #define FAN0_PIN 8 #endif #ifndef FAN1_PIN #define FAN1_PIN 6 @@ -168,9 +168,11 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 31 // Pullup! -#define SPINDLE_DIR_PIN 32 +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 31 // Pullup! + #define SPINDLE_DIR_PIN 32 +#endif // // SPI for MAX Thermocouple @@ -197,6 +199,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL #define KILL_PIN 80 @@ -204,13 +207,13 @@ #if IS_ULTIPANEL || TOUCH_UI_ULTIPANEL #define LCD_PINS_RS 70 - #define LCD_PINS_ENABLE 71 + #define LCD_PINS_EN 71 #define LCD_PINS_D4 72 #define LCD_PINS_D5 73 #define LCD_PINS_D6 74 #define LCD_PINS_D7 75 - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define BEEPER_PIN 44 // NB: Panucatt's Viki 2.0 wiring diagram (v1.2) indicates that the // beeper/buzzer is connected to pin 33; however, the pin used in the @@ -230,7 +233,7 @@ #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 - #else // !VIKI2 && !miniVIKI + #else // !VIKI2 && !miniVIKI #define BEEPER_PIN 79 // AUX-4 @@ -251,7 +254,7 @@ #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif - #else // !IS_NEWPANEL - old style panel with shift register + #else // !IS_NEWPANEL - old style panel with shift register // No Beeper added #define BEEPER_PIN 33 @@ -264,7 +267,7 @@ //#define SHIFT_EN_PIN 17 #define LCD_PINS_RS 75 - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_EN 17 #define LCD_PINS_D4 23 #define LCD_PINS_D5 25 #define LCD_PINS_D6 27 diff --git a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h index ca073f5ab991..0d212010e065 100644 --- a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h +++ b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h @@ -105,8 +105,8 @@ #define HEATER_1_PIN 7 #define HEATER_BED_PIN 3 -#ifndef FAN_PIN - #define FAN_PIN 8 +#ifndef FAN0_PIN + #define FAN0_PIN 8 #endif #define FAN1_PIN 6 #define FAN2_PIN 2 @@ -126,7 +126,7 @@ // LCD / Controller // #define LCD_PINS_RS 70 // Ext2_5 -#define LCD_PINS_ENABLE 71 // Ext2_7 +#define LCD_PINS_EN 71 // Ext2_7 #define LCD_PINS_D4 72 // Ext2_9 ? #define LCD_PINS_D5 73 // Ext2_11 ? #define LCD_PINS_D6 74 // Ext2_13 @@ -143,7 +143,7 @@ #define HOME_PIN BTN_HOME -#if EITHER(VIKI2, miniVIKI) +#if ANY(VIKI2, miniVIKI) #define BEEPER_PIN 44 // Pins for DOGM SPI LCD Support #define DOGLCD_A0 70 diff --git a/Marlin/src/pins/ramps/env_validate.h b/Marlin/src/pins/ramps/env_validate.h index 6006a78f013c..86d7bce16c16 100644 --- a/Marlin/src/pins/ramps/env_validate.h +++ b/Marlin/src/pins/ramps/env_validate.h @@ -19,7 +19,8 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if ENABLED(ALLOW_SAM3X8E) #if NOT_TARGET(__SAM3X8E__, __AVR_ATmega2560__) @@ -33,3 +34,5 @@ #undef ALLOW_SAM3X8E #undef REQUIRE_MEGA2560 + +#endif diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 9929fa6e12a8..3a2d7ea19561 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -117,7 +117,7 @@ #define SPINDLE_LASER_PWM_PIN 46 // Hardware PWM #define SPINDLE_LASER_ENA_PIN 62 // Pullup! #define SPINDLE_DIR_PIN 48 - #elif !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // Use expansion header if no LCD in use + #elif !ALL(HAS_WIRED_LCD, IS_NEWPANEL) // Use expansion header if no LCD in use #define SPINDLE_LASER_ENA_PIN 16 // Pullup or pulldown! #define SPINDLE_DIR_PIN 17 #if !NUM_SERVOS // Use servo connector if possible @@ -131,12 +131,13 @@ // // LCD / Controller // + #if HAS_WIRED_LCD && IS_NEWPANEL #undef BEEPER_PIN // TODO: Remap EXP1/2 based on adapter #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 + #define LCD_PINS_EN 29 #define LCD_PINS_D4 37 #define LCD_PINS_D5 35 #define LCD_PINS_D6 33 diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h index 4d3722655df9..17581dca6241 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h @@ -54,7 +54,7 @@ #undef STAT_LED_RED_PIN #undef STAT_LED_BLUE_PIN -#if EITHER(VIKI2, miniVIKI) +#if ANY(VIKI2, miniVIKI) #undef DOGLCD_A0 #undef DOGLCD_CS diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h index 2c666a6f16a4..ddd56b28e859 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h @@ -56,8 +56,8 @@ #define Y_STOP_PIN 14 #define Z_STOP_PIN 18 -#ifndef FAN_PIN - #define FAN_PIN 6 +#ifndef FAN0_PIN + #define FAN0_PIN 6 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) @@ -145,7 +145,7 @@ #undef BEEPER_PIN #define BEEPER_PIN 33 -#if EITHER(VIKI2, miniVIKI) +#if ANY(VIKI2, miniVIKI) #undef SD_DETECT_PIN #define SD_DETECT_PIN 49 // For easy adapter board #undef BEEPER_PIN @@ -172,7 +172,7 @@ #undef SPINDLE_DIR_PIN #if HAS_CUTTER // EXP2 header - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define BTN_EN2 31 // Pin 7 needed for Spindle PWM #endif #define SPINDLE_LASER_PWM_PIN 7 // Hardware PWM diff --git a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h index f3439aa6bbba..cf237fb9c11e 100644 --- a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h +++ b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h @@ -37,9 +37,11 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 66 // Pullup or pulldown! -#define SPINDLE_DIR_PIN 67 -#define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 66 // Pullup or pulldown! + #define SPINDLE_DIR_PIN 67 +#endif // // Temperature Sensors diff --git a/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h b/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h index 6155e9842aad..aab66f0feacd 100644 --- a/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h +++ b/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h @@ -35,7 +35,6 @@ // // Heaters / Fans // -// Power outputs BEEF or BEFF -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN 7 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h index cd3ada25bf30..08d4492ccb5e 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -95,9 +95,11 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM -#define SPINDLE_DIR_PIN 42 +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! + #define SPINDLE_DIR_PIN 42 +#endif // // Misc. Functions @@ -121,9 +123,10 @@ #include "pins_RAMPS_13.h" // ... RAMPS // -// Used by the Hephestos 2 heated bed upgrade kit +// Hephestos 2 heated bed upgrade kit uses pin 8 // #if ENABLED(HEPHESTOS2_HEATED_BED_KIT) #undef HEATER_BED_PIN #define HEATER_BED_PIN 8 + #define HEATER_BED_INVERTING true #endif diff --git a/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h b/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h index 7e370a398bcd..83045bdfe02d 100644 --- a/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h +++ b/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h @@ -72,7 +72,7 @@ #define HEATER_0_PIN 4 // PG5 / PWM4 #define HEATER_BED_PIN 3 // PE5 / PWM3 -#define FAN_PIN 5 // PE3 / PWM5 +#define FAN0_PIN 5 // PE3 / PWM5 // // Misc. Functions @@ -85,12 +85,13 @@ #define SD_SCK_PIN 52 // PB1 // -// LCDs and Controllers +// LCD / Controller // + #if HAS_WIRED_LCD #if ENABLED(ZONESTAR_LCD) #define LCD_PINS_RS 2 - #define LCD_PINS_ENABLE 36 + #define LCD_PINS_EN 36 #define LCD_PINS_D4 37 #define LCD_PINS_D5 34 #define LCD_PINS_D6 35 diff --git a/Marlin/src/pins/ramps/pins_FELIX2.h b/Marlin/src/pins/ramps/pins_FELIX2.h index 48ef896e96b5..746de8581a67 100644 --- a/Marlin/src/pins/ramps/pins_FELIX2.h +++ b/Marlin/src/pins/ramps/pins_FELIX2.h @@ -35,24 +35,24 @@ // // Heaters / Fans // -// Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN 7 #include "pins_RAMPS.h" // // Misc. Functions // -#define SDPOWER_PIN 1 +#define SDPOWER_PIN 1 -#define PS_ON_PIN 12 +#define PS_ON_PIN 12 // // LCD / Controller // + #if HAS_WIRED_LCD && IS_NEWPANEL - #define SD_DETECT_PIN 6 + #define SD_DETECT_PIN 6 #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h index 7bed4c088433..f6ee06846dfd 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h @@ -116,7 +116,7 @@ #define TEMP_BED_PIN 14 // Analog Input // SPI for MAX Thermocouple -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) @@ -129,8 +129,8 @@ #define HEATER_1_PIN 7 #define HEATER_BED_PIN 8 -#ifndef FAN_PIN - #define FAN_PIN 9 +#ifndef FAN0_PIN + #define FAN0_PIN 9 #endif #ifndef FIL_RUNOUT_PIN @@ -174,7 +174,7 @@ #define SD_DETECT_PIN 49 #define KILL_PIN 41 #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_EN 17 #define LCD_PINS_D4 23 #define LCD_PINS_D5 25 #define LCD_PINS_D6 27 diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h index f0e86ac4a7f3..65828fd4fb62 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h @@ -29,7 +29,7 @@ #define BOARD_INFO_NAME "Formbot Raptor2" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME -#define FAN_PIN 6 +#define FAN0_PIN 6 #ifndef FIL_RUNOUT_PIN #define FIL_RUNOUT_PIN 22 @@ -44,12 +44,12 @@ // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !NUM_SERVOS // Try to use servo connector first - #define SPINDLE_LASER_ENA_PIN 6 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 6 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #elif !GREEDY_PANEL // Try to use AUX2 - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 65 #endif #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index a5ca7e86073f..fad3cc0f9de8 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -113,7 +113,7 @@ #define TEMP_BED_PIN 3 // Analog Input // SPI for MAX Thermocouple -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) @@ -126,7 +126,7 @@ #define HEATER_1_PIN 7 #define HEATER_BED_PIN 58 -#define FAN_PIN 9 +#define FAN0_PIN 9 #if HAS_FILAMENT_SENSOR #define FIL_RUNOUT_PIN 4 @@ -141,8 +141,8 @@ // #define SDSS 53 #ifndef LED_PIN - #define LED_PIN 13 // The Formbot v 1 board has almost no unassigned pins on it. The Board's LED -#endif // is a good place to get a signal to control the Max7219 LED Matrix. + #define LED_PIN 13 // The Formbot v 1 board has almost no unassigned pins. +#endif // The Board's LED is a good place to connect the Max7219 Matrix. // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector #define FILWIDTH_PIN 5 // Analog Input @@ -175,7 +175,7 @@ #endif #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_EN 17 #define LCD_PINS_D4 23 #define LCD_PINS_D5 25 #define LCD_PINS_D6 27 diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h index 2fa3d60f6722..fd799e0d49d0 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h @@ -119,7 +119,7 @@ #define TEMP_BED_PIN 14 // Analog Input // SPI for MAX Thermocouple -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) @@ -132,7 +132,7 @@ #define HEATER_1_PIN 7 #define HEATER_BED_PIN 8 -#define FAN_PIN 9 +#define FAN0_PIN 9 #define FAN1_PIN 12 #define FIL_RUNOUT_PIN 22 @@ -164,7 +164,7 @@ // #if IS_RRD_SC #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_EN 17 #define LCD_PINS_D4 23 #define LCD_PINS_D5 25 #define LCD_PINS_D6 27 diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index 9f23647c42b2..640d938245b9 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -185,14 +185,13 @@ #define HEATER_2_PIN 7 #define HEATER_BED_PIN 8 -#define FAN_PIN 44 +#define FAN0_PIN 44 #define FAN1_PIN 45 #define FAN2_PIN 46 // // Misc. Functions // -#define SDSS 53 #define LED_PIN 13 #define KILL_PIN 41 @@ -201,80 +200,104 @@ #endif /** - * ----- ----- - * 5V/D41 | · · | GND 5V | · · | GND - * RESET | · · | D49 (SD_DETECT) (LCD_D7) D29 | · · | D27 (LCD_D6) - * (MOSI) D51 | · · D33 (BTN_EN2) (LCD_D5) D25 | · · D23 (LCD_D4) - * (SD_SS) D53 | · · | D31 (BTN_EN1) (LCD_RS) D16 | · · | D17 (LCD_EN) - * (SCK) D52 | · · | D50 (MISO) (BTN_ENC) D35 | · · | D37 (BEEPER) - * ----- ----- - * EXP2 EXP1 + * ------ ------ + * (BEEPER) D37 | 1 2 | D35 (BTN_ENC) (MISO) D50 | 1 2 | D52 (SCK) + * (LCD_EN) D17 | 3 4 | D16 (LCD_RS) (BTN_EN1) D31 | 3 4 | D53 (SD_SS) + * (LCD_D4) D23 5 6 | D25 (LCD_D5) (BTN_EN2) D33 5 6 | D51 (MOSI) + * (LCD_D6) D27 | 7 8 | D29 (LCD_D7) (SD_DETECT) D49 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 5V / D41 + * ------ ------ + * EXP1 EXP2 */ +#define EXP1_01_PIN 37 // BEEPER +#define EXP1_02_PIN 35 // ENC +#define EXP1_03_PIN 17 // LCD_EN +#define EXP1_04_PIN 16 // LCD_RS +#define EXP1_05_PIN 23 // LCD_D4 +#define EXP1_06_PIN 25 // LCD_D5 +#define EXP1_07_PIN 27 // LCD_D6 +#define EXP1_08_PIN 29 // LCD_D7 + +#define EXP2_01_PIN 50 // MISO +#define EXP2_02_PIN 52 // SCK +#define EXP2_03_PIN 31 // EN1 +#define EXP2_04_PIN 53 // SD_SS +#define EXP2_05_PIN 33 // EN2 +#define EXP2_06_PIN 51 // MOSI +#define EXP2_07_PIN 49 // SD_DETECT +#define EXP2_08_PIN -1 // RESET + +// +// SD Card +// + +#define SDSS EXP2_04_PIN +#define SD_DETECT_PIN EXP2_07_PIN + // -// LCDs and Controllers +// LCD / Controller // -#define SD_DETECT_PIN 49 #if ENABLED(FYSETC_242_OLED_12864) - #define BTN_EN1 37 - #define BTN_EN2 29 - #define BTN_ENC 35 - #define BEEPER_PIN 31 - - #define LCD_PINS_DC 25 - #define LCD_PINS_RS 33 - #define DOGLCD_CS 16 - #define DOGLCD_MOSI 23 - #define DOGLCD_SCK 17 + #define BTN_EN1 EXP1_01_PIN + #define BTN_EN2 EXP1_08_PIN + #define BTN_ENC EXP1_02_PIN + #define BEEPER_PIN EXP2_03_PIN + + #define LCD_PINS_DC EXP1_06_PIN + #define LCD_PINS_RS EXP2_05_PIN + #define DOGLCD_CS EXP1_04_PIN + #define DOGLCD_MOSI EXP1_05_PIN + #define DOGLCD_SCK EXP1_03_PIN #define DOGLCD_A0 LCD_PINS_DC #undef KILL_PIN - #define NEOPIXEL_PIN 27 + #define NEOPIXEL_PIN EXP1_07_PIN #else - #define BEEPER_PIN 37 + #define BEEPER_PIN EXP1_01_PIN #if ENABLED(FYSETC_MINI_12864) // // See https://wiki.fysetc.com/Mini12864_Panel/ // - #define DOGLCD_A0 16 - #define DOGLCD_CS 17 + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_03_PIN #if ENABLED(FYSETC_GENERIC_12864_1_1) - #define LCD_BACKLIGHT_PIN 27 + #define LCD_BACKLIGHT_PIN EXP1_07_PIN #endif - #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. - // Seems to work best if left open. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. + // Seems to work best if left open. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 25 + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 27 + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 29 + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 25 + #define NEOPIXEL_PIN EXP1_06_PIN #endif #elif HAS_MARLINUI_U8GLIB || HAS_MARLINUI_HD44780 - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS 25 - #define DOGLCD_A0 27 + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_A0 EXP1_07_PIN #endif #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) @@ -284,9 +307,9 @@ #endif #if IS_NEWPANEL - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN #endif #endif diff --git a/Marlin/src/pins/ramps/pins_K8400.h b/Marlin/src/pins/ramps/pins_K8400.h index 56ec66191b32..abcffe484d5e 100644 --- a/Marlin/src/pins/ramps/pins_K8400.h +++ b/Marlin/src/pins/ramps/pins_K8400.h @@ -53,14 +53,19 @@ #define X_STOP_PIN 3 #define Y_STOP_PIN 14 -#if EITHER(BLTOUCH, TOUCH_MI_PROBE) +// +// Fans +// +#define FAN0_PIN 8 + +#if ANY(BLTOUCH, TOUCH_MI_PROBE) #define INVERTED_PROBE_STATE #endif #include "pins_3DRAG.h" // ... RAMPS // -// Heaters / Fans +// Heaters // #undef HEATER_1_PIN #define HEATER_1_PIN 11 diff --git a/Marlin/src/pins/ramps/pins_K8600.h b/Marlin/src/pins/ramps/pins_K8600.h index 3081b0436188..170401bf1c21 100644 --- a/Marlin/src/pins/ramps/pins_K8600.h +++ b/Marlin/src/pins/ramps/pins_K8600.h @@ -49,7 +49,7 @@ // Heaters / Fans // #define HEATER_BED_PIN -1 -#define FAN_PIN 8 +#define FAN0_PIN 8 // // Misc. Functions @@ -60,10 +60,11 @@ // // LCD / Controller // + #if HAS_WIRED_LCD && IS_NEWPANEL #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 + #define LCD_PINS_EN 29 #define LCD_PINS_D4 37 #define LCD_PINS_D5 35 #define LCD_PINS_D6 33 diff --git a/Marlin/src/pins/ramps/pins_K8800.h b/Marlin/src/pins/ramps/pins_K8800.h index a9669764cef1..826e1b206aad 100644 --- a/Marlin/src/pins/ramps/pins_K8800.h +++ b/Marlin/src/pins/ramps/pins_K8800.h @@ -74,7 +74,7 @@ // Heaters / Fans // #define HEATER_0_PIN 10 -#define FAN_PIN 8 +#define FAN0_PIN 8 #define CONTROLLER_FAN_PIN 9 // @@ -102,7 +102,7 @@ #define DOGLCD_A0 27 #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 + #define LCD_PINS_EN 29 #define LCD_PINS_D4 37 #define LCD_PINS_D5 35 #define LCD_PINS_D6 33 diff --git a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h index d9759153c334..cb28762adc55 100644 --- a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h +++ b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h @@ -127,20 +127,20 @@ // Aux-1 | D19 D18 GND 5V | J21 | D4 D5 D6 GND | J17 | D11 GND 24V | J18 | D7 GND 5V | // ------------------ ---------------- --------------- ------------- -#if BOTH(CR10_STOCKDISPLAY, LONGER_LK5) - /** CR-10 Stock Display - * ------ - * GND | 9 10 | 5V - * LCD_PINS_RS D5 | 7 8 | D4 LCD_PINS_ENABLE - * BTN_EN2 D19 | 5 6 D6 LCD_PINS_D4 - * BTN_EN1 D18 | 3 4 | GND - * BEEPER_PIN D11 | 1 2 | D15 BTN_ENC - * ------ +#if ALL(CR10_STOCKDISPLAY, LONGER_LK5) + /** CR-10 Stock Display + * ------ + * BEEPER D11 | 1 2 | D15 ENC + * EN1 D18 | 3 4 | GND + * EN2 D19 5 6 | D6 LCD_D4 + * LCD_RS D5 | 7 8 | D4 LCD_ENABLE + * GND | 9 10 | 5V + * ------ * Connected via provided custom cable to: * Aux-1, J21, J17 and Y-Max. */ #define LCD_PINS_RS 5 - #define LCD_PINS_ENABLE 4 + #define LCD_PINS_EN 4 #define LCD_PINS_D4 6 #define BTN_EN1 18 #define BTN_EN2 19 diff --git a/Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h b/Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h index 2ab463d681af..6a837a8fb8fd 100644 --- a/Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h +++ b/Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h @@ -28,8 +28,8 @@ // // Only 3 Limit Switch plugs on Micromake C1 // -#define X_STOP_PIN 2 -#define Y_STOP_PIN 15 -#define Z_STOP_PIN 19 +#define X_STOP_PIN 2 +#define Y_STOP_PIN 15 +#define Z_STOP_PIN 19 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_14.h b/Marlin/src/pins/ramps/pins_MKS_BASE_14.h index d302def795b1..9877877ffdfa 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_14.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_14.h @@ -33,11 +33,6 @@ #define BOARD_INFO_NAME "MKS BASE 1.4" #define MKS_BASE_VERSION 14 -// -// Heaters / Fans -// -#define FAN_PIN 9 // PH6 ** Pin18 ** PWM9 - // Other Mods #define SERVO3_PIN 12 // PB6 ** Pin25 ** D12 diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h index 765a601fd029..bb6def5ca46f 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h @@ -38,7 +38,7 @@ // // Servos // -#define SERVO1_PIN 12 // Digital 12 / Pin 25 +#define SERVO1_PIN 12 // // Omitted RAMPS pins diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_common.h b/Marlin/src/pins/ramps/pins_MKS_BASE_common.h index 7608745a4b1d..b0f0866bc66a 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_common.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_common.h @@ -34,8 +34,8 @@ // // Heaters / Fans // - // Power outputs EFBF or EFBE - #define MOSFET_D_PIN 7 + #define MOSFET_B_PIN 7 + #define FAN0_PIN 9 // // M3/M4/M5 - Spindle/Laser Control @@ -50,12 +50,9 @@ #define CASE_LIGHT_PIN 2 #endif -#endif - -// -// Microstepping pins -// -#if MKS_BASE_VERSION >= 14 // |===== 1.4 =====|===== 1.5+ =====| + // + // Microstepping pins + // |===== 1.4 =====|===== 1.5+ =====| #define X_MS1_PIN 5 // PE3 | Pin 5 | PWM5 | | D3 | SERVO2_PIN #define X_MS2_PIN 6 // PH3 | Pin 15 | PWM6 | Pin 14 | D6 | SERVO1_PIN #define Y_MS1_PIN 59 // PF5 | Pin 92 | A5 | | | diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h index 5c13288f8558..6ef77909d163 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h @@ -42,10 +42,8 @@ // // Heaters / Fans // -// Power outputs EFBF or EFBE -// #define MOSFET_B_PIN 7 -#define FAN_PIN 9 +#define FAN0_PIN 9 // // PSU / SERVO @@ -65,7 +63,8 @@ // // LCD / Controller // -#if EITHER(VIKI2, miniVIKI) + +#if ANY(VIKI2, miniVIKI) /** * VIKI2 Has two groups of wires with... * diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L.h index 9faacf24fc5c..73e7aa577d50 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L.h @@ -37,14 +37,11 @@ // // Heaters / Fans // -// Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 -// Hotend, Hotend, Bed + Fan on D9 -#if FET_ORDER_EEB - #define MOSFET_B_PIN 7 - #define FAN_PIN 9 -#endif +#define MOSFET_A_PIN 10 // HE0 +#define MOSFET_B_PIN 7 // HE1 or FAN Hotend Cooling +#define MOSFET_C_PIN 8 // HBED +#define FAN0_PIN 9 // FAN Part Cooling // // CS Pins wired to avoid conflict with the LCD @@ -52,11 +49,11 @@ // #ifndef X_CS_PIN - #define X_CS_PIN 59 + #define X_CS_PIN 59 #endif #ifndef Y_CS_PIN - #define Y_CS_PIN 63 + #define Y_CS_PIN 63 #endif #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h index d82c4353fd03..931843de7c73 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h @@ -37,8 +37,8 @@ // // Heaters / Fans // -// Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_B_PIN 7 +#define FAN0_PIN 9 // // CS Pins wired to avoid conflict with the LCD diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h index c2ab34c82560..6cea92c15b78 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h @@ -37,8 +37,8 @@ // // Heaters / Fans // -// Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_B_PIN 7 +#define FAN0_PIN 9 // // CS Pins wired to avoid conflict with the LCD diff --git a/Marlin/src/pins/ramps/pins_ORTUR_4.h b/Marlin/src/pins/ramps/pins_ORTUR_4.h index 7f0fe93084b7..e8a87911d1b7 100644 --- a/Marlin/src/pins/ramps/pins_ORTUR_4.h +++ b/Marlin/src/pins/ramps/pins_ORTUR_4.h @@ -79,11 +79,12 @@ // // LCD / Controller // + #if IS_RRD_FG_SC #define BEEPER_PIN 35 #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 23 + #define LCD_PINS_EN 23 #define LCD_PINS_D4 37 #define LCD_SDSS 53 diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 3d4e0426f6ad..0195f3a1bc9a 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -142,18 +142,18 @@ // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 +#define X_STEP_PIN 54 // (A0) +#define X_DIR_PIN 55 // (A1) #define X_ENABLE_PIN 38 #ifndef X_CS_PIN - #define X_CS_PIN 53 + #define X_CS_PIN AUX3_06 #endif #define Y_STEP_PIN 60 #define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_ENABLE_PIN 56 // (A2) #ifndef Y_CS_PIN - #define Y_CS_PIN 49 + #define Y_CS_PIN AUX3_02 #endif #ifndef Z_STEP_PIN @@ -166,7 +166,7 @@ #define Z_ENABLE_PIN 62 #endif #ifndef Z_CS_PIN - #define Z_CS_PIN 40 + #define Z_CS_PIN AUX2_06 #endif #ifndef E0_STEP_PIN @@ -179,7 +179,7 @@ #define E0_ENABLE_PIN 24 #endif #ifndef E0_CS_PIN - #define E0_CS_PIN 42 + #define E0_CS_PIN AUX2_08 #endif #ifndef E1_STEP_PIN @@ -192,7 +192,7 @@ #define E1_ENABLE_PIN 30 #endif #ifndef E1_CS_PIN - #define E1_CS_PIN 44 + #define E1_CS_PIN AUX2_07 #endif // @@ -212,7 +212,7 @@ // SPI for MAX Thermocouple // #ifndef TEMP_0_CS_PIN - #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card (SDSS) or 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN AUX2_09 // Don't use 53 if using Display/SD card (SDSS) or 49 (SD_DETECT_PIN) #endif // @@ -245,27 +245,29 @@ #define HEATER_BED_PIN MOSFET_C_PIN #endif #elif FET_ORDER_EFF // Hotend, Fan, Fan - #define FAN1_PIN MOSFET_C_PIN + #ifndef FAN1_PIN + #define FAN1_PIN MOSFET_C_PIN + #endif #elif DISABLED(FET_ORDER_SF) // Not Spindle, Fan (i.e., "EFBF" or "EFBE") #ifndef HEATER_BED_PIN #define HEATER_BED_PIN MOSFET_C_PIN #endif - #if EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) + #if ANY(HAS_MULTI_HOTEND, HEATERS_PARALLEL) #define HEATER_1_PIN MOSFET_D_PIN #else #define FAN1_PIN MOSFET_D_PIN #endif #endif -#ifndef FAN_PIN - #if EITHER(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan - #define FAN_PIN MOSFET_B_PIN - #elif EITHER(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan - #define FAN_PIN MOSFET_C_PIN +#ifndef FAN0_PIN + #if ANY(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan + #define FAN0_PIN MOSFET_B_PIN + #elif ANY(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan + #define FAN0_PIN MOSFET_C_PIN #elif FET_ORDER_EEB // Hotend, Hotend, Bed - #define FAN_PIN 4 // IO pin. Buffer needed + #define FAN0_PIN 4 // IO pin. Buffer needed #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") - #define FAN_PIN MOSFET_B_PIN + #define FAN0_PIN MOSFET_B_PIN #endif #endif @@ -273,12 +275,12 @@ // Misc. Functions // #ifndef SDSS - #define SDSS AUX3_06_PIN + #define SDSS AUX3_06 #endif #define LED_PIN 13 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 5 // Analog Input on AUX2 + #define FILWIDTH_PIN 5 // (A5) Analog Input AUX2_03 #endif // RAMPS 1.4 DIO 4 on the servos connector @@ -294,7 +296,7 @@ #if NUM_SERVOS <= 1 // Prefer the servo connector #define CASE_LIGHT_PIN 6 // Hardware PWM #elif HAS_FREE_AUX2_PINS - #define CASE_LIGHT_PIN 44 // Hardware PWM + #define CASE_LIGHT_PIN AUX2_07 // Hardware PWM #endif #endif @@ -303,15 +305,15 @@ // #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) #if NUM_SERVOS < 2 // Use servo connector if possible - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #ifndef SPINDLE_LASER_PWM_PIN #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM #endif + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #elif HAS_FREE_AUX2_PINS - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_DIR_PIN 65 + #define SPINDLE_LASER_PWM_PIN AUX2_07 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN AUX2_06 // Pullup or pulldown! + #define SPINDLE_DIR_PIN AUX2_10 #else #error "No auto-assignable Spindle/Laser pins available." #endif @@ -320,15 +322,15 @@ // // TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 66 +#if HAS_TMC_SPI + #ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI AUX2_09 #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO 44 + #ifndef TMC_SPI_MISO + #define TMC_SPI_MISO AUX2_07 #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK 64 + #ifndef TMC_SPI_SCK + #define TMC_SPI_SCK AUX2_05 #endif #endif @@ -339,8 +341,9 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below * - * Serial2 -- AUX-4 Pin 18 (D16 TX2) and AUX-4 Pin 17 (D17 RX2) - * Serial1 -- Pins D18 and D19 are used for Z-MIN and Z-MAX + * Serial1 -- TX1 = D18 RX1 = D19 (Z-MIN and Z-MAX on RAMPS) + * Serial2 -- TX2 = D16 RX2 = D17 (AUX4-18 and AUX4-17) + * Serial3 -- TX3 = D14 RX3 = D15 (Available on some RAMPS-like boards) */ //#define X_HARDWARE_SERIAL Serial1 //#define X2_HARDWARE_SERIAL Serial1 @@ -355,10 +358,10 @@ //#define E4_HARDWARE_SERIAL Serial1 #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN 40 + #define X_SERIAL_TX_PIN AUX2_06 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN 63 + #define X_SERIAL_RX_PIN AUX2_04 #endif #ifndef X2_SERIAL_TX_PIN #define X2_SERIAL_TX_PIN -1 @@ -368,10 +371,10 @@ #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN 59 + #define Y_SERIAL_TX_PIN AUX2_03 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN 64 + #define Y_SERIAL_RX_PIN AUX2_05 #endif #ifndef Y2_SERIAL_TX_PIN #define Y2_SERIAL_TX_PIN -1 @@ -381,10 +384,10 @@ #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN 42 + #define Z_SERIAL_TX_PIN AUX2_08 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN 65 + #define Z_SERIAL_RX_PIN AUX2_10 #endif #ifndef Z2_SERIAL_TX_PIN #define Z2_SERIAL_TX_PIN -1 @@ -394,10 +397,10 @@ #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN 44 + #define E0_SERIAL_TX_PIN AUX2_07 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN 66 + #define E0_SERIAL_RX_PIN AUX2_09 #endif #ifndef E1_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN -1 @@ -448,13 +451,13 @@ // #if HAS_PRUSA_MMU1 #ifndef E_MUX0_PIN - #define E_MUX0_PIN 40 // Z_CS_PIN + #define E_MUX0_PIN AUX2_06 // Z_CS_PIN #endif #ifndef E_MUX1_PIN - #define E_MUX1_PIN 42 // E0_CS_PIN + #define E_MUX1_PIN AUX2_08 // E0_CS_PIN #endif #ifndef E_MUX2_PIN - #define E_MUX2_PIN 44 // E1_CS_PIN + #define E_MUX2_PIN AUX2_07 // E1_CS_PIN #endif #endif @@ -464,10 +467,10 @@ // 1 3 5 7 // 5V GND A3 A4 // -#define AUX1_05_PIN 57 // (A3) -#define AUX1_06_PIN 2 -#define AUX1_07_PIN 58 // (A4) -#define AUX1_08_PIN 1 +#define AUX1_05 57 // (A3) +#define AUX1_06 2 +#define AUX1_07 58 // (A4) +#define AUX1_08 1 // // AUX2 GND A9 D40 D42 A11 @@ -475,14 +478,14 @@ // 1 3 5 7 9 // VCC A5 A10 D44 A12 // -#define AUX2_03_PIN 59 // (A5) -#define AUX2_04_PIN 63 // (A9) -#define AUX2_05_PIN 64 // (A10) -#define AUX2_06_PIN 40 -#define AUX2_07_PIN 44 -#define AUX2_08_PIN 42 -#define AUX2_09_PIN 66 // (A12) -#define AUX2_10_PIN 65 // (A11) +#define AUX2_03 59 // (A5) +#define AUX2_04 63 // (A9) +#define AUX2_05 64 // (A10) +#define AUX2_06 40 +#define AUX2_07 44 +#define AUX2_08 42 +#define AUX2_09 66 // (A12) +#define AUX2_10 65 // (A11) // // AUX3 GND D52 D50 5V @@ -490,31 +493,31 @@ // 8 6 4 2 // NC D53 D51 D49 // -#define AUX3_02_PIN 49 -#define AUX3_03_PIN 50 -#define AUX3_04_PIN 51 -#define AUX3_05_PIN 52 -#define AUX3_06_PIN 53 +#define AUX3_02 49 +#define AUX3_03 50 +#define AUX3_04 51 +#define AUX3_05 52 +#define AUX3_06 53 // // AUX4 5V GND D32 D47 D45 D43 D41 D39 D37 D35 D33 D31 D29 D27 D25 D23 D17 D16 // -#define AUX4_03_PIN 32 -#define AUX4_04_PIN 47 -#define AUX4_05_PIN 45 -#define AUX4_06_PIN 43 -#define AUX4_07_PIN 41 -#define AUX4_08_PIN 39 -#define AUX4_09_PIN 37 -#define AUX4_10_PIN 35 -#define AUX4_11_PIN 33 -#define AUX4_12_PIN 31 -#define AUX4_13_PIN 29 -#define AUX4_14_PIN 27 -#define AUX4_15_PIN 25 -#define AUX4_16_PIN 23 -#define AUX4_17_PIN 17 -#define AUX4_18_PIN 16 +#define AUX4_03 32 +#define AUX4_04 47 +#define AUX4_05 45 +#define AUX4_06 43 +#define AUX4_07 41 +#define AUX4_08 39 +#define AUX4_09 37 +#define AUX4_10 35 +#define AUX4_11 33 +#define AUX4_12 31 +#define AUX4_13 29 +#define AUX4_14 27 +#define AUX4_15 25 +#define AUX4_16 23 +#define AUX4_17 17 +#define AUX4_18 16 /** * LCD adapters come in different variants. The socket keys can be @@ -522,71 +525,75 @@ */ #ifndef EXP1_08_PIN - #define EXP1_03_PIN AUX4_17_PIN - #define EXP1_04_PIN AUX4_18_PIN - #define EXP1_05_PIN AUX4_16_PIN - #define EXP1_06_PIN AUX4_15_PIN - #define EXP1_07_PIN AUX4_14_PIN - #define EXP1_08_PIN AUX4_13_PIN + #define EXP1_03_PIN AUX4_17 // 17 + #define EXP1_04_PIN AUX4_18 // 16 + #define EXP1_05_PIN AUX4_16 // 23 + #define EXP1_06_PIN AUX4_15 // 25 + #define EXP1_07_PIN AUX4_14 // 27 + #define EXP1_08_PIN AUX4_13 // 29 - #define EXP2_01_PIN AUX3_03_PIN - #define EXP2_02_PIN AUX3_05_PIN - #define EXP2_04_PIN AUX3_06_PIN - #define EXP2_06_PIN AUX3_04_PIN - #define EXP2_07_PIN AUX3_02_PIN + #define EXP2_01_PIN AUX3_03 // 50 (MISO) + #define EXP2_02_PIN AUX3_05 // 52 + #define EXP2_04_PIN AUX3_06 // 53 + #define EXP2_06_PIN AUX3_04 // 51 + #define EXP2_07_PIN AUX3_02 // 49 #if ENABLED(G3D_PANEL) /** Gadgets3D Smart Adapter - * ------ ------ - * 4-11 | 1 2 | 4-12 (MISO) 3-03 | 1 2 | 3-05 (SCK) - * 4-17 | 3 4 | 4-18 4-10 | 3 4 | 3-06 - * 4-16 5 6 | 4-15 4-09 5 6 | 3-04 (MOSI) - * 4-14 | 7 8 | 4-13 3-02 | 7 8 | 4-07 - * (GND) 4-02 | 9 10 | 4-01 (5V) -- | 9 10 | -- - * ------ ------ - * EXP1 EXP2 + * ------ ------ + * 33 4-11 | 1 2 | 4-12 31 (MISO) 50 3-03 | 1 2 | 3-05 52 (SCK) + * 17 4-17 | 3 4 | 4-18 16 35 4-10 | 3 4 | 3-06 53 + * 23 4-16 5 6 | 4-15 25 37 4-09 5 6 | 3-04 51 (MOSI) + * 27 4-14 | 7 8 | 4-13 29 49 3-02 | 7 8 | 4-07 41 + * (GND) 4-02 | 9 10 | 4-01 (5V) -- | 9 10 | -- + * ------ ------ + * EXP1 EXP2 */ - #define EXP1_01_PIN AUX4_11_PIN - #define EXP1_02_PIN AUX4_12_PIN + #define EXP1_01_PIN AUX4_11 // 33 + #define EXP1_02_PIN AUX4_12 // 31 - #define EXP2_03_PIN AUX4_10_PIN - #define EXP2_05_PIN AUX4_09_PIN - #define EXP2_08_PIN AUX4_07_PIN + #define EXP2_03_PIN AUX4_10 // 35 + #define EXP2_05_PIN AUX4_09 // 37 + #define EXP2_08_PIN AUX4_07 // 41 #else /** Smart Adapter (c) RRD * ------ ------ - * 4-09 | 1 2 | 4-10 (MISO) 3-03 | 1 2 | 3-05 (SCK) - * 4-17 | 3 4 | 4-18 4-12 | 3 4 | 3-06 - * 4-16 5 6 | 4-15 4-11 5 6 | 3-04 (MOSI) - * 4-14 | 7 8 | 4-13 3-02 | 7 8 | 4-07 + * 37 4-09 | 1 2 | 4-10 (MISO) 3-03 | 1 2 | 3-05 52 (SCK) + * 17 4-17 | 3 4 | 4-18 31 4-12 | 3 4 | 3-06 53 + * 23 4-16 5 6 | 4-15 33 4-11 5 6 | 3-04 51 (MOSI) + * 27 4-14 | 7 8 | 4-13 49 3-02 | 7 8 | 4-07 41 * (GND) 3-07 | 9 10 | 3-01 (5V) (GND) 3-07 | 9 10 | -- * ------ ------ * EXP1 EXP2 */ - #define EXP1_01_PIN AUX4_09_PIN - #define EXP1_02_PIN AUX4_10_PIN + #define EXP1_01_PIN AUX4_09 // 37 + #define EXP1_02_PIN AUX4_10 // 35 - #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) - #define EXP2_03_PIN AUX4_11_PIN - #define EXP2_05_PIN AUX4_12_PIN + #if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) + #define EXP2_03_PIN AUX4_11 // 33 + #define EXP2_05_PIN AUX4_12 // 31 #define EXP2_08_PIN -1 // RESET #else - #define EXP2_03_PIN AUX4_12_PIN - #define EXP2_05_PIN AUX4_11_PIN - #define EXP2_08_PIN AUX4_07_PIN + #define EXP2_03_PIN AUX4_12 // 31 + #define EXP2_05_PIN AUX4_11 // 33 + #define EXP2_08_PIN AUX4_07 // 41 #endif #endif #endif -////////////////////////// -// LCDs and Controllers // -////////////////////////// +// +// LCD / Controller +// + +#ifdef LCD_PINS_DEFINED + + // LCD pins already defined by including header -#if HAS_WIRED_LCD && DISABLED(LCD_PINS_DEFINED) +#elif HAS_WIRED_LCD //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 @@ -596,17 +603,17 @@ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) #define LCD_PINS_RS EXP2_07_PIN // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE EXP2_06_PIN // SID (MOSI) + #define LCD_PINS_EN EXP2_06_PIN // SID (MOSI) #define LCD_PINS_D4 EXP2_02_PIN // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS AUX2_06_PIN - #define LCD_PINS_ENABLE AUX2_08_PIN - #define LCD_PINS_D4 AUX2_10_PIN - #define LCD_PINS_D5 AUX2_09_PIN - #define LCD_PINS_D6 AUX2_07_PIN - #define LCD_PINS_D7 AUX2_05_PIN + #define LCD_PINS_RS AUX2_06 + #define LCD_PINS_EN AUX2_08 + #define LCD_PINS_D4 AUX2_10 + #define LCD_PINS_D5 AUX2_09 + #define LCD_PINS_D6 AUX2_07 + #define LCD_PINS_D7 AUX2_05 #elif ENABLED(TFTGLCD_PANEL_SPI) @@ -617,7 +624,7 @@ #if ENABLED(CR10_STOCKDISPLAY) #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #if !IS_NEWPANEL @@ -630,12 +637,12 @@ #error "CAUTION! ZONESTAR_LCD on RAMPS requires wiring modifications. It plugs into AUX2 but GND and 5V need to be swapped. See 'pins_RAMPS.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" #endif - #define LCD_PINS_RS AUX2_05_PIN - #define LCD_PINS_ENABLE AUX2_07_PIN - #define LCD_PINS_D4 AUX2_04_PIN - #define LCD_PINS_D5 AUX2_06_PIN - #define LCD_PINS_D6 AUX2_08_PIN - #define LCD_PINS_D7 AUX2_10_PIN + #define LCD_PINS_RS AUX2_05 + #define LCD_PINS_EN AUX2_07 + #define LCD_PINS_D4 AUX2_04 + #define LCD_PINS_D5 AUX2_06 + #define LCD_PINS_D6 AUX2_08 + #define LCD_PINS_D7 AUX2_10 #elif ENABLED(AZSMZ_12864) @@ -643,7 +650,7 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) #define LCD_PINS_DC EXP1_06_PIN // Set as output on init #define LCD_PINS_RS EXP1_07_PIN // Pull low for 1s to init // DOGM SPI LCD Support @@ -653,7 +660,7 @@ #define DOGLCD_SCK EXP1_05_PIN #else #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #define LCD_PINS_D5 EXP1_06_PIN #define LCD_PINS_D6 EXP1_07_PIN @@ -671,8 +678,8 @@ // Buttons attached to a shift register // Not wired yet //#define SHIFT_CLK_PIN 38 - //#define SHIFT_LD_PIN AUX2_08_PIN - //#define SHIFT_OUT_PIN AUX2_06_PIN + //#define SHIFT_LD_PIN AUX2_08 + //#define SHIFT_OUT_PIN AUX2_06 //#define SHIFT_EN_PIN EXP1_03_PIN #endif @@ -706,30 +713,30 @@ #endif #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN AUX4_08_PIN + #define LCD_BACKLIGHT_PIN AUX4_08 #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define BTN_EN1 AUX2_05_PIN - #define BTN_EN2 AUX2_03_PIN - #define BTN_ENC AUX2_04_PIN + #define BTN_EN1 AUX2_05 + #define BTN_EN2 AUX2_03 + #define BTN_ENC AUX2_04 #ifndef SD_DETECT_PIN - #define SD_DETECT_PIN AUX2_08_PIN + #define SD_DETECT_PIN AUX2_08 #endif #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 AUX4_04_PIN - #define BTN_EN2 AUX4_06_PIN - #define BTN_ENC AUX4_03_PIN + #define BTN_EN1 AUX4_04 + #define BTN_EN2 AUX4_06 + #define BTN_ENC AUX4_03 #define LCD_SDSS SDSS #define KILL_PIN EXP2_08_PIN #elif ENABLED(LCD_I2C_VIKI) - #define BTN_EN1 AUX2_06_PIN // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains AUX2-06 and AUX2-08. - #define BTN_EN2 AUX2_08_PIN + #define BTN_EN1 AUX2_06 // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains AUX2-06 and AUX2-08. + #define BTN_EN2 AUX2_08 #define BTN_ENC -1 #define LCD_SDSS SDSS @@ -737,21 +744,21 @@ #define SD_DETECT_PIN EXP2_07_PIN #endif - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) - #define DOGLCD_CS AUX4_05_PIN - #define DOGLCD_A0 AUX2_07_PIN + #define DOGLCD_CS AUX4_05 + #define DOGLCD_A0 AUX2_07 #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #ifndef BEEPER_PIN #define BEEPER_PIN EXP2_05_PIN #endif - #define STAT_LED_RED_PIN AUX4_03_PIN + #define STAT_LED_RED_PIN AUX4_03 #define STAT_LED_BLUE_PIN EXP1_02_PIN #define BTN_EN1 22 #define BTN_EN2 7 - #define BTN_ENC AUX4_08_PIN + #define BTN_ENC AUX4_08 #ifndef SD_DETECT_PIN #define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board @@ -778,7 +785,7 @@ #endif #define KILL_PIN EXP2_08_PIN - #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) + #elif ANY(MKS_MINI_12864, FYSETC_MINI_12864) #define BTN_ENC EXP1_02_PIN #ifndef SD_DETECT_PIN @@ -815,7 +822,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif @@ -836,19 +843,19 @@ #ifndef BEEPER_PIN #define BEEPER_PIN AUX2_08_PIN #endif - #define LCD_BACKLIGHT_PIN AUX2_10_PIN + #define LCD_BACKLIGHT_PIN AUX2_10 - #define DOGLCD_A0 AUX2_07_PIN - #define DOGLCD_CS AUX2_09_PIN + #define DOGLCD_A0 AUX2_07 + #define DOGLCD_CS AUX2_09 - #define BTN_EN1 AUX2_06_PIN - #define BTN_EN2 AUX2_04_PIN - #define BTN_ENC AUX2_03_PIN + #define BTN_EN1 AUX2_06 + #define BTN_EN2 AUX2_04 + #define BTN_ENC AUX2_03 #ifndef SD_DETECT_PIN - #define SD_DETECT_PIN AUX3_02_PIN + #define SD_DETECT_PIN AUX3_02 #endif - #define KILL_PIN AUX2_05_PIN + #define KILL_PIN AUX2_05 #elif ENABLED(ZONESTAR_LCD) @@ -881,10 +888,10 @@ #define BEEPER_PIN EXP2_05_PIN #endif - #if ENABLED(PANEL_ONE) // Buttons connect directly to AUX-2 - #define BTN_EN1 AUX2_03_PIN - #define BTN_EN2 AUX2_04_PIN - #define BTN_ENC AUX3_02_PIN + #if ENABLED(PANEL_ONE) // Buttons connect directly to AUX-2 + #define BTN_EN1 AUX2_03 + #define BTN_EN2 AUX2_04 + #define BTN_ENC AUX3_02 #else #define BTN_EN1 EXP1_01_PIN #define BTN_EN2 EXP1_02_PIN @@ -901,21 +908,21 @@ #endif // HAS_WIRED_LCD && !LCD_PINS_DEFINED #if IS_RRW_KEYPAD && !HAS_ADC_BUTTONS - #define SHIFT_OUT_PIN AUX2_06_PIN - #define SHIFT_CLK_PIN AUX2_07_PIN - #define SHIFT_LD_PIN AUX2_08_PIN + #define SHIFT_OUT_PIN AUX2_06 + #define SHIFT_CLK_PIN AUX2_07 + #define SHIFT_LD_PIN AUX2_08 #ifndef BTN_EN1 - #define BTN_EN1 AUX2_05_PIN + #define BTN_EN1 AUX2_05 #endif #ifndef BTN_EN2 - #define BTN_EN2 AUX2_03_PIN + #define BTN_EN2 AUX2_03 #endif #ifndef BTN_ENC - #define BTN_ENC AUX2_04_PIN + #define BTN_ENC AUX2_04 #endif #endif -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_RAMPS.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" diff --git a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h index 5e4366e259cb..49a8c196d0a6 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h @@ -32,8 +32,8 @@ // // Heaters / Fans // -#define MOSFET_B_PIN 7 // For HEATER_1_PIN ("EEF" or "EEB") -#define FAN_PIN 9 +#define MOSFET_B_PIN 7 +#define FAN0_PIN 9 #define FIL_RUNOUT_PIN 2 #if NUM_RUNOUT_SENSORS >= 2 @@ -57,6 +57,8 @@ #define CASE_LIGHT_PIN 65 #endif +#define SERVO1_PIN 12 + #include "pins_RAMPS.h" #ifndef BEEPER_PIN diff --git a/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h b/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h index 3ffa940c482d..ece072b50953 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h @@ -36,7 +36,7 @@ // band (case light). Thus the hotend and controller fans are always-on. #if ENABLED(CASE_LIGHT_ENABLE) - #undef FAN_PIN + #undef FAN0_PIN #ifndef CASE_LIGHT_PIN #define CASE_LIGHT_PIN MOSFET_B_PIN #endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h index 526045c1558d..fa24dd35b3ca 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h @@ -76,7 +76,7 @@ #define TEMP_BED_PIN 1 // Analog Input // SPI for MAX Thermocouple -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card #else #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) @@ -88,14 +88,14 @@ #if ENABLED(RAMPS_V_1_0) #define HEATER_0_PIN 12 #define HEATER_BED_PIN -1 - #ifndef FAN_PIN - #define FAN_PIN 11 + #ifndef FAN0_PIN + #define FAN0_PIN 11 #endif -#else // RAMPS_V_1_1 or RAMPS_V_1_2 +#else // RAMPS_V_1_1 or RAMPS_V_1_2 #define HEATER_0_PIN 10 #define HEATER_BED_PIN 8 - #ifndef FAN_PIN - #define FAN_PIN 9 + #ifndef FAN0_PIN + #define FAN0_PIN 9 #endif #endif @@ -113,6 +113,8 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 41 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM -#define SPINDLE_DIR_PIN 43 +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 41 // Pullup or pulldown! + #define SPINDLE_DIR_PIN 43 +#endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h index f93c6919d960..a7f5a790094c 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h @@ -22,7 +22,7 @@ #pragma once /** - * Arduino Mega with RAMPS v1.4Plus, also known as 3DYMY version, pin assignments + * Arduino Mega with RAMPS v1.4Plus, aka 3DYMY version * ATmega2560, ATmega1280 * * Applies to the following boards: @@ -64,32 +64,32 @@ #define E1_ENABLE_PIN 24 #define E1_CS_PIN -1 -/** 3DYMY Expansion Headers - * ------ ------ - * 37 | 1 2 | 35 (MISO) 50 | 1 2 | 52 (SCK) - * 31 | 3 4 | 41 29 | 3 4 | 53 - * 33 5 6 | 23 25 5 6 | 51 (MOSI) - * 42 | 7 8 | 44 49 | 7 8 | 27 - * GND | 9 10 | 5V GND | 9 10 | -- - * ------ ------ - * EXP1 EXP2 +/** 3DYMY Expansion Headers + * ------ ------ + * (BEEP) 37 | 1 2 | 35 (ENC) (MISO) 50 | 1 2 | 52 (SCK) + * (LCD_EN) 31 | 3 4 | 41 (LCD_RS) (EN1) 29 | 3 4 | 53 (SDSS) + * (LCD_D4) 33 5 6 | 23 (LCD_D5) (EN2) 25 5 6 | 51 (MOSI) + * (LCD_D6) 42 | 7 8 | 44 (LCD_D7) (SD_DET) 49 | 7 8 | 27 (KILL) + * GND | 9 10 | 5V GND | 9 10 | -- + * ------ ------ + * EXP1 EXP2 */ -#define EXP1_01_PIN 37 -#define EXP1_02_PIN 35 -#define EXP1_03_PIN 31 -#define EXP1_04_PIN 41 -#define EXP1_05_PIN 33 -#define EXP1_06_PIN 23 -#define EXP1_07_PIN 42 -#define EXP1_08_PIN 44 +#define EXP1_01_PIN 37 // BEEPER +#define EXP1_02_PIN 35 // ENC +#define EXP1_03_PIN 31 // LCD_EN +#define EXP1_04_PIN 41 // LCD_RS +#define EXP1_05_PIN 33 // LCD_D4 +#define EXP1_06_PIN 23 // LCD_D5 +#define EXP1_07_PIN 42 // LCD_D6 +#define EXP1_08_PIN 44 // LCD_D7 -#define EXP2_01_PIN 50 -#define EXP2_02_PIN 52 -#define EXP2_03_PIN 29 -#define EXP2_04_PIN 53 -#define EXP2_05_PIN 25 -#define EXP2_06_PIN 51 -#define EXP2_07_PIN 49 -#define EXP2_08_PIN 27 +#define EXP2_01_PIN 50 // MISO +#define EXP2_02_PIN 52 // SCK +#define EXP2_03_PIN 29 // EN1 +#define EXP2_04_PIN 53 // SDSS +#define EXP2_05_PIN 25 // EN2 +#define EXP2_06_PIN 51 // MOSI +#define EXP2_07_PIN 49 // SD_DET +#define EXP2_08_PIN 27 // KILL #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h index 4f3de969f7e8..9565adad2f3b 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h @@ -172,12 +172,12 @@ #if MB(RAMPS_S_12_EEFB) // Hotend0, Hotend1, Fan, Bed #define HEATER_1_PIN RAMPS_S_HE_1 - #define FAN_PIN RAMPS_S_HE_2 + #define FAN0_PIN RAMPS_S_HE_2 #elif MB(RAMPS_S_12_EEEB) // Hotend0, Hotend1, Hotend2, Bed #define HEATER_1_PIN RAMPS_S_HE_1 #define HEATER_2_PIN RAMPS_S_HE_2 #elif MB(RAMPS_S_12_EFFB) // Hotend, Fan0, Fan1, Bed - #define FAN_PIN RAMPS_S_HE_1 + #define FAN0_PIN RAMPS_S_HE_1 #define FAN1_PIN RAMPS_S_HE_2 #endif @@ -211,24 +211,22 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #endif // // TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 51 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO 50 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK 53 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI 51 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO 50 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK 53 #endif // @@ -246,17 +244,14 @@ #endif #endif -////////////////////////// -// LCDs and Controllers // -////////////////////////// - // -// LCD Display output pins +// LCD / Controller // + #if HAS_WIRED_LCD #define BEEPER_PIN 45 #define LCD_PINS_RS 19 - #define LCD_PINS_ENABLE 49 + #define LCD_PINS_EN 49 #define LCD_PINS_D4 18 #define LCD_PINS_D5 30 #define LCD_PINS_D6 41 diff --git a/Marlin/src/pins/ramps/pins_RIGIDBOARD.h b/Marlin/src/pins/ramps/pins_RIGIDBOARD.h index d1824d3813a0..afd31eeead66 100644 --- a/Marlin/src/pins/ramps/pins_RIGIDBOARD.h +++ b/Marlin/src/pins/ramps/pins_RIGIDBOARD.h @@ -72,7 +72,7 @@ // SPI for MAX Thermocouple #undef TEMP_0_CS_PIN -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 53 // Don't use pin 53 if there is even the remote possibility of using Display/SD card #else #define TEMP_0_CS_PIN 49 // Don't use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present @@ -84,8 +84,8 @@ #undef HEATER_BED_PIN #define HEATER_BED_PIN 10 -#ifndef FAN_PIN - #define FAN_PIN 8 // Same as RAMPS_13_EEF +#ifndef FAN0_PIN + #define FAN0_PIN 8 // Same as RAMPS_13_EEF #endif // diff --git a/Marlin/src/pins/ramps/pins_RUMBA.h b/Marlin/src/pins/ramps/pins_RUMBA.h index 6b1f4c569170..9a4a384e4ab5 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA.h +++ b/Marlin/src/pins/ramps/pins_RUMBA.h @@ -53,9 +53,6 @@ #ifndef X_MIN_PIN #define X_MIN_PIN 37 #endif -#ifndef X_MIN_PIN - #define X_MIN_PIN 37 -#endif #ifndef X_MAX_PIN #define X_MAX_PIN 36 #endif @@ -159,8 +156,8 @@ #define HEATER_3_PIN 8 #define HEATER_BED_PIN 9 -#ifndef FAN_PIN - #define FAN_PIN 7 +#ifndef FAN0_PIN + #define FAN0_PIN 7 #endif #ifndef FAN1_PIN #define FAN1_PIN 8 @@ -193,7 +190,8 @@ // // LCD / Controller // -#if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + +#if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) #define LCD_PINS_DC 38 // Set as output on init #define LCD_PINS_RS 41 // Pull low for 1s to init // DOGM SPI LCD Support @@ -212,7 +210,7 @@ #define LCD_RESET_PIN 18 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN 41 #endif @@ -228,7 +226,7 @@ #else #define LCD_PINS_RS 19 - #define LCD_PINS_ENABLE 42 + #define LCD_PINS_EN 42 #define LCD_PINS_D4 18 #define LCD_PINS_D5 38 #define LCD_PINS_D6 41 @@ -241,7 +239,7 @@ // #define BEEPER_PIN 44 -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #define SDSS 53 #define SD_DETECT_PIN 49 #endif diff --git a/Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h b/Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h index 57ee32ab2969..cc3ce76ac33e 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h +++ b/Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h @@ -27,7 +27,7 @@ #define DEFAULT_MACHINE_NAME "Raise3D N Series" // Raise3D uses thermocouples on the standard input pins -#define TEMP_0_PIN 15 // Analog Input -#define TEMP_1_PIN 14 // Analog Input +#define TEMP_0_PIN 15 // Analog Input +#define TEMP_1_PIN 14 // Analog Input #include "pins_RUMBA.h" diff --git a/Marlin/src/pins/ramps/pins_TANGO.h b/Marlin/src/pins/ramps/pins_TANGO.h index 936751e9ebf7..54dd4433998f 100644 --- a/Marlin/src/pins/ramps/pins_TANGO.h +++ b/Marlin/src/pins/ramps/pins_TANGO.h @@ -30,7 +30,7 @@ #define BOARD_INFO_NAME "Tango" -#define FAN_PIN 8 +#define FAN0_PIN 8 #define FAN1_PIN -1 #ifndef E0_AUTO_FAN_PIN diff --git a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h index dd6fb2fa7036..f68b9ef8a6f7 100644 --- a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h +++ b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h @@ -125,7 +125,7 @@ #define TEMP_BED_PIN 14 // Analog Input // SPI for MAX Thermocouple -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN -1 // Don't use 53 if using Display/SD card #else #define TEMP_0_CS_PIN -1 // Don't use 49 (SD_DETECT_PIN) @@ -138,7 +138,7 @@ #define HEATER_1_PIN 11 #define HEATER_BED_PIN 8 -#define FAN_PIN 9 +#define FAN0_PIN 9 #define FAN1_PIN 5 // Normally this would be a servo pin // XXX Runout support unknown? @@ -169,7 +169,7 @@ //#if IS_RRD_SC #define LCD_PINS_RS -1 -#define LCD_PINS_ENABLE -1 +#define LCD_PINS_EN -1 #define LCD_PINS_D4 -1 #define LCD_PINS_D5 -1 #define LCD_PINS_D6 -1 diff --git a/Marlin/src/pins/ramps/pins_TENLOG_MB1_V23.h b/Marlin/src/pins/ramps/pins_TENLOG_MB1_V23.h index 780ab8daa49e..1197874d7168 100644 --- a/Marlin/src/pins/ramps/pins_TENLOG_MB1_V23.h +++ b/Marlin/src/pins/ramps/pins_TENLOG_MB1_V23.h @@ -95,7 +95,7 @@ #define HEATER_1_PIN 10 #define HEATER_BED_PIN 8 -#define FAN_PIN 9 +#define FAN0_PIN 9 #define FAN2_PIN 5 // Normally this would be a servo pin //#define NUM_RUNOUT_SENSORS 0 @@ -139,7 +139,7 @@ //#endif #define LCD_PINS_RS -1 -#define LCD_PINS_ENABLE -1 +#define LCD_PINS_EN -1 #define LCD_PINS_D4 -1 #define LCD_PINS_D5 -1 #define LCD_PINS_D6 -1 diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h index a286c13a30a5..83dac111cbbe 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h @@ -28,17 +28,17 @@ #define BOARD_INFO_NAME "Anycubic RAMPS 1.3" -#define MOSFET_B_PIN 44 +#define MOSFET_B_PIN 44 -#define E1_STEP_PIN -1 -#define E1_DIR_PIN -1 -#define E1_ENABLE_PIN -1 -#define E1_CS_PIN -1 +#define E1_STEP_PIN -1 +#define E1_DIR_PIN -1 +#define E1_ENABLE_PIN -1 +#define E1_CS_PIN -1 -#define FAN2_PIN 9 +#define FAN2_PIN 9 #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 9 + #define E0_AUTO_FAN_PIN 9 #endif #include "pins_RAMPS_13.h" // ... RAMPS diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index ce2a9e4cdc72..d3c921a5f654 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -46,7 +46,7 @@ // // Heaters / Fans // -#define FAN_PIN 9 // FAN0 +#define FAN0_PIN 9 // FAN0 #define FAN1_PIN 7 // FAN1 #define FAN2_PIN 44 // FAN2 #ifndef E0_AUTO_FAN_PIN @@ -69,38 +69,39 @@ * IIC : 12V GND D21 D20 GND 5V * (SCL SDA) * + * TX2 RX2 RX3 TX3 * END STOPS : D19 D18 D15 D14 D2 D3 * GND GND GND GND GND GND * 5V 5V 5V 5V 5V 5V */ -/** Expansion Headers - * ------ ------ - * 37 | 1 2 | 35 (MISO) 50 | 1 2 | 52 (SCK) - * 17 | 3 4 | 16 31 | 3 4 | 53 - * 23 5 6 | 25 33 5 6 | 51 (MOSI) - * 27 | 7 8 | 29 49 | 7 8 | 41 - * (GND) | 9 10 | (5V) (GND) | 9 10 | RESET - * ------ ------ - * EXP1 EXP2 +/** Expansion Headers + * ------ ------ + * (BEEP) 37 | 1 2 | 35 (ENC) (MISO) 50 | 1 2 | 52 (SCK) + * (LCD_EN) 17 | 3 4 | 16 (LCD_RS) (EN1) 31 | 3 4 | 53 (SDSS) + * (LCD_D4) 23 5 6 | 25 (LCD_D5) (EN2) 33 5 6 | 51 (MOSI) + * (LCD_D6) 27 | 7 8 | 29 (LCD_D7) (SD_DET) 49 | 7 8 | 41 (KILL) + * GND | 9 10 | 5V GND | 9 10 | RESET + * ------ ------ + * EXP1 EXP2 */ -#define EXP1_01_PIN 37 -#define EXP1_02_PIN 35 -#define EXP1_03_PIN 17 -#define EXP1_04_PIN 16 -#define EXP1_05_PIN 23 -#define EXP1_06_PIN 25 -#define EXP1_07_PIN 27 -#define EXP1_08_PIN 29 +#define EXP1_01_PIN 37 // BEEPER +#define EXP1_02_PIN 35 // ENC +#define EXP1_03_PIN 17 // LCD_EN +#define EXP1_04_PIN 16 // LCD_RS +#define EXP1_05_PIN 23 // LCD_D4 +#define EXP1_06_PIN 25 // LCD_D5 +#define EXP1_07_PIN 27 // LCD_D6 +#define EXP1_08_PIN 29 // LCD_D7 #define EXP2_01_PIN 50 // MISO #define EXP2_02_PIN 52 // SCK -#define EXP2_03_PIN 31 -#define EXP2_04_PIN 53 -#define EXP2_05_PIN 33 +#define EXP2_03_PIN 31 // EN1 +#define EXP2_04_PIN 53 // SDSS +#define EXP2_05_PIN 33 // EN2 #define EXP2_06_PIN 51 // MOSI -#define EXP2_07_PIN 49 -#define EXP2_08_PIN 41 +#define EXP2_07_PIN 49 // SD_DET +#define EXP2_08_PIN 41 // KILL // // AnyCubic pin mappings @@ -114,11 +115,13 @@ #if ENABLED(ANYCUBIC_4_MAX_PRO_ENDSTOPS) #define X_MAX_PIN 43 // AUX (2) #define Y_STOP_PIN 19 // Z+ -#elif EITHER(TRIGORILLA_MAPPING_CHIRON, TRIGORILLA_MAPPING_I3MEGA) +#elif ANY(TRIGORILLA_MAPPING_CHIRON, TRIGORILLA_MAPPING_I3MEGA) // Chiron uses AUX header for Y and Z endstops #define Y_STOP_PIN 42 // AUX (1) #define Z_STOP_PIN 43 // AUX (2) - #define Z2_MIN_PIN 18 // Z- + #ifndef Z2_STOP_PIN + #define Z2_STOP_PIN 18 // Z- + #endif #ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN 2 // X+ @@ -142,7 +145,7 @@ #define FIL_RUNOUT_PIN 19 // Z+ #endif - #if EITHER(TRIGORILLA_MAPPING_CHIRON, SWAP_Z_MOTORS) + #if ANY(TRIGORILLA_MAPPING_CHIRON, SWAP_Z_MOTORS) // Chiron and some Anycubic i3 MEGAs swap Z steppers #define Z_STEP_PIN 36 #define Z_DIR_PIN 34 @@ -156,7 +159,7 @@ #endif #endif -#if EITHER(ANYCUBIC_LCD_CHIRON, ANYCUBIC_LCD_I3MEGA) +#if ANY(ANYCUBIC_LCD_CHIRON, ANYCUBIC_LCD_I3MEGA) #ifndef BEEPER_PIN #define BEEPER_PIN EXP2_03_PIN // Chiron Standard Adapter #endif diff --git a/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h b/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h index 0104dadf7ff2..17b9f24711a3 100644 --- a/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h +++ b/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h @@ -38,7 +38,7 @@ // // Servos // -#define SERVO1_PIN 12 // 2560 PIN 25/PB6 +#define SERVO1_PIN 12 // 2560 PIN 25/PB6 // // Import RAMPS 1.4 pins diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 430d7b3ec06b..ed4f373c541d 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -21,7 +21,11 @@ */ #pragma once -// ATmega2560 +/** + * TT OSCAR by YM Tech.LTD + * + * ATmega2560 + */ #include "env_validate.h" @@ -73,12 +77,12 @@ #define Z_STEP_PIN 46 #define Z_DIR_PIN 48 #define Z_ENABLE_PIN 62 -#define Z_CS_PIN 53 +#define Z_CS_PIN 53 // EXP2-4 #define E0_STEP_PIN 26 #define E0_DIR_PIN 28 #define E0_ENABLE_PIN 24 -#define E0_CS_PIN 49 +#define E0_CS_PIN 49 // EXP2-7 #define E1_STEP_PIN 36 #define E1_DIR_PIN 34 @@ -152,16 +156,14 @@ // // Default pins for TMC software SPI // -//#if ENABLED(TMC_USE_SW_SPI) -// #ifndef TMC_SW_MOSI -// #define TMC_SW_MOSI 66 -// #endif -// #ifndef TMC_SW_MISO -// #define TMC_SW_MISO 44 -// #endif -// #ifndef TMC_SW_SCK -// #define TMC_SW_SCK 64 -// #endif +//#ifndef TMC_SPI_MOSI +// #define TMC_SPI_MOSI 66 +//#endif +//#ifndef TMC_SPI_MISO +// #define TMC_SPI_MISO 44 +//#endif +//#ifndef TMC_SPI_SCK +// #define TMC_SPI_SCK 64 //#endif // @@ -180,7 +182,7 @@ #endif // SPI for MAX Thermocouple -//#if DISABLED(SDSUPPORT) +//#if !HAS_MEDIA // #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card //#else // #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) @@ -194,7 +196,7 @@ #define HEATER_2_PIN 44 #define HEATER_BED_PIN 8 -#define FAN_PIN 9 +#define FAN0_PIN 9 #if EXTRUDERS >= 5 #define HEATER_4_PIN 6 @@ -211,11 +213,11 @@ // // Misc. Functions // -#define SDSS 53 +#define SDSS 53 // EXP2-4 #define LED_PIN 13 //#ifndef FILWIDTH_PIN -// #define FILWIDTH_PIN 5 // Analog Input +// #define FILWIDTH_PIN 5 // Analog Input //#endif // DIO 4 (Servos plug) for the runout sensor. @@ -230,12 +232,12 @@ // #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 + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #elif HAS_FREE_AUX2_PINS // Try to use AUX 2 - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_DIR_PIN 65 #endif #endif @@ -259,16 +261,52 @@ #define E_MUX0_PIN 58 // Y_CS_PIN #endif #ifndef E_MUX1_PIN - #define E_MUX1_PIN 53 // Z_CS_PIN + #define E_MUX1_PIN 53 // EXP2-4 #endif #ifndef E_MUX2_PIN - #define E_MUX2_PIN 49 // En_CS_PIN + #define E_MUX2_PIN 49 // EXP2-7 #endif #endif -////////////////////////// -// LCDs and Controllers // -////////////////////////// +/** TT OSCAR Expansion Headers + * ------ + * -- | 1 2 | -- + * -- 3 4 | -- + * -- 5 6 | -- + * 49 | 7 8 | -- + * ------ + * AUX1 + * + * ------ ------ + * 37 | 1 2 | 35 (MISO) 44 | 1 2 | 52 (SCK) + * 17 | 3 4 | 41? 35 | 3 4 | 53 + * 23 5 6 | 25 31 5 6 | 51 (MOSI) + * 27 | 7 8 | 29 49 | 7 8 | 41 + * GND | 9 10 | 5V GND | 9 10 | -- + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_01_PIN 37 // BEEPER +#define EXP1_02_PIN 35 // ENC +#define EXP1_03_PIN 17 // ENC1 +#define EXP1_04_PIN 41 // RESET +#define EXP1_05_PIN 23 // ENC2 +#define EXP1_06_PIN 25 // D4 +#define EXP1_07_PIN 27 // RS +#define EXP1_08_PIN 29 // EN + +#define EXP2_01_PIN 44 // MISO +#define EXP2_02_PIN 52 // SCK +#define EXP2_03_PIN 35 // EN2 / EN1 +#define EXP2_04_PIN 53 // SDSS +#define EXP2_05_PIN 31 // EN1 / EN2 +#define EXP2_06_PIN 51 // MOSI +#define EXP2_07_PIN 49 // SD_DET +#define EXP2_08_PIN 41 // KILL / RESET + +// +// LCD / Controller +// #if HAS_WIRED_LCD @@ -277,14 +315,14 @@ // #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS EXP2_07_PIN // CS chip select /SS chip slave select + #define LCD_PINS_EN EXP2_06_PIN // SID (MOSI) + #define LCD_PINS_D4 EXP2_02_PIN // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) #define LCD_PINS_RS 40 - #define LCD_PINS_ENABLE 42 + #define LCD_PINS_EN 42 #define LCD_PINS_D4 65 #define LCD_PINS_D5 66 #define LCD_PINS_D6 44 @@ -293,7 +331,7 @@ #elif ENABLED(ZONESTAR_LCD) #define LCD_PINS_RS 64 - #define LCD_PINS_ENABLE 44 + #define LCD_PINS_EN 44 #define LCD_PINS_D4 63 #define LCD_PINS_D5 40 #define LCD_PINS_D6 42 @@ -305,7 +343,7 @@ #if ENABLED(CR10_STOCKDISPLAY) #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 + #define LCD_PINS_EN 29 #define LCD_PINS_D4 25 #if !IS_NEWPANEL @@ -314,7 +352,7 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) #define LCD_PINS_DC 25 // Set as output on init #define LCD_PINS_RS 27 // Pull low for 1s to init // DOGM SPI LCD Support @@ -324,7 +362,7 @@ #define DOGLCD_A0 LCD_PINS_DC #else #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_EN 17 #define LCD_PINS_D4 23 #define LCD_PINS_D5 25 #define LCD_PINS_D6 27 @@ -371,7 +409,7 @@ #endif #define BTN_ENC 35 - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN EXP2_07_PIN //#define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) @@ -390,7 +428,7 @@ #define BTN_EN1 47 #define BTN_EN2 43 #define BTN_ENC 32 - #define LCD_SDSS 53 + #define LCD_SDSS EXP2_04_PIN //#define KILL_PIN 41 #elif ENABLED(LCD_I2C_VIKI) @@ -399,10 +437,10 @@ #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. #define BTN_ENC -1 - #define LCD_SDSS 53 - #define SD_DETECT_PIN 49 + #define LCD_SDSS EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #define DOGLCD_CS 45 #define DOGLCD_A0 44 @@ -415,7 +453,7 @@ #define BTN_EN2 7 #define BTN_ENC 39 - #define SDSS 53 + #define SDSS EXP2_04_PIN #define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board //#define KILL_PIN 31 @@ -433,8 +471,8 @@ #define BTN_EN2 37 #define BTN_ENC 31 - #define LCD_SDSS 53 - #define SD_DETECT_PIN 49 + #define LCD_SDSS EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN //#define KILL_PIN 41 #elif ENABLED(MKS_MINI_12864) @@ -449,8 +487,8 @@ #define BTN_EN1 31 #define BTN_EN2 33 #define BTN_ENC 35 - //#define SDSS 53 - #define SD_DETECT_PIN 49 + //#define SDSS EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN //#define KILL_PIN 64 //#define LCD_CONTRAST_INIT 190 @@ -469,8 +507,8 @@ #define BTN_EN2 63 #define BTN_ENC 59 - #define SDSS 53 - #define SD_DETECT_PIN 49 + #define SDSS EXP2_04_PIN + #define SD_DETECT_PIN EXP2_07_PIN //#define KILL_PIN 64 //#define LCD_CONTRAST_INIT 190 @@ -500,7 +538,7 @@ #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN EXP2_07_PIN //#define KILL_PIN 41 #endif diff --git a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h index 4ee0a6950d39..049e8bc5d80c 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h @@ -112,8 +112,8 @@ #define HEATER_1_PIN 3 #define HEATER_BED_PIN 4 -#ifndef FAN_PIN - #define FAN_PIN 7 +#ifndef FAN0_PIN + #define FAN0_PIN 7 #endif #ifndef E0_AUTO_FAN_PIN @@ -135,7 +135,7 @@ #define BEEPER_PIN 18 #define LCD_PINS_RS 20 -#define LCD_PINS_ENABLE 15 +#define LCD_PINS_EN 15 #define LCD_PINS_D4 14 #define LCD_PINS_D5 21 #define LCD_PINS_D6 5 @@ -151,9 +151,9 @@ // #if HAS_CUTTER // use the LED_PIN for spindle speed control or case light #undef LED_PIN - #define SPINDLE_DIR_PIN 16 - #define SPINDLE_LASER_ENA_PIN 17 // Pullup! #define SPINDLE_LASER_PWM_PIN 8 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 17 // Pullup! + #define SPINDLE_DIR_PIN 16 #else #undef LED_PIN #define CASE_LIGHT_PIN 8 diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER.h b/Marlin/src/pins/ramps/pins_ULTIMAKER.h index e3e91428dfa7..b4eea9d4885c 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER.h @@ -99,8 +99,8 @@ #define HEATER_1_PIN 3 #define HEATER_BED_PIN 4 -#ifndef FAN_PIN - #define FAN_PIN 7 +#ifndef FAN0_PIN + #define FAN0_PIN 7 #endif // @@ -118,6 +118,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #define BEEPER_PIN 18 @@ -125,7 +126,7 @@ #if IS_NEWPANEL #define LCD_PINS_RS 20 - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_EN 17 #define LCD_PINS_D4 16 #define LCD_PINS_D5 21 #define LCD_PINS_D6 5 @@ -138,7 +139,7 @@ #define SD_DETECT_PIN 38 - #else // !IS_NEWPANEL - Old style panel with shift register + #else // !IS_NEWPANEL - Old style panel with shift register // Buttons attached to a shift register #define SHIFT_CLK_PIN 38 @@ -147,7 +148,7 @@ #define SHIFT_EN_PIN 17 #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 5 + #define LCD_PINS_EN 5 #define LCD_PINS_D4 6 #define LCD_PINS_D5 21 #define LCD_PINS_D6 20 @@ -162,6 +163,8 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 10 // Pullup! -#define SPINDLE_DIR_PIN 11 // use the EXP3 PWM header +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 10 // Pullup! + #define SPINDLE_DIR_PIN 11 // use the EXP3 PWM header +#endif diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h index 25cc278adab8..5cf143a09cf6 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h @@ -116,7 +116,7 @@ // // Z Probe (when not Z_MIN_PIN) // -#if !defined(Z_MIN_PROBE_PIN) && !BOTH(HAS_CUTTER, BOARD_REV_1_0) +#if !defined(Z_MIN_PROBE_PIN) && !ALL(HAS_CUTTER, BOARD_REV_1_0) #define Z_MIN_PROBE_PIN Z_MAX_PIN #endif @@ -135,7 +135,7 @@ #define Z_DIR_PIN 39 #define Z_ENABLE_PIN 35 -#if BOTH(HAS_CUTTER, BOARD_REV_1_1_TO_1_3) && EXTRUDERS == 1 +#if ALL(HAS_CUTTER, BOARD_REV_1_1_TO_1_3) && EXTRUDERS == 1 // Move E0 to the spare and get Spindle/Laser signals from E0 #define E0_STEP_PIN 49 #define E0_DIR_PIN 47 @@ -166,23 +166,24 @@ // // LCD / Controller // -#if EITHER(BOARD_REV_1_0, BOARD_REV_1_1_TO_1_3) + +#if ANY(BOARD_REV_1_0, BOARD_REV_1_1_TO_1_3) #define LCD_PINS_RS 24 - #define LCD_PINS_ENABLE 22 + #define LCD_PINS_EN 22 #define LCD_PINS_D4 36 #define LCD_PINS_D5 34 #define LCD_PINS_D6 32 #define LCD_PINS_D7 30 -#elif BOTH(BOARD_REV_1_5, HAS_WIRED_LCD) +#elif ALL(BOARD_REV_1_5, HAS_WIRED_LCD) #define BEEPER_PIN 18 #if IS_NEWPANEL #define LCD_PINS_RS 20 - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_EN 17 #define LCD_PINS_D4 16 #define LCD_PINS_D5 21 #define LCD_PINS_D6 5 @@ -195,7 +196,7 @@ #define SD_DETECT_PIN 38 - #else // !IS_NEWPANEL - Old style panel with shift register + #else // !IS_NEWPANEL - Old style panel with shift register // Buttons attached to a shift register #define SHIFT_CLK_PIN 38 @@ -204,7 +205,7 @@ #define SHIFT_EN_PIN 17 #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 5 + #define LCD_PINS_EN 5 #define LCD_PINS_D4 6 #define LCD_PINS_D5 21 #define LCD_PINS_D6 20 @@ -225,10 +226,10 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER - #if EITHER(BOARD_REV_1_0, BOARD_REV_1_5) // Use the last three SW positions - #define SPINDLE_DIR_PIN 10 // 1.0: SW4 1.5: EXP3-6 ("10") + #if ANY(BOARD_REV_1_0, BOARD_REV_1_5) // Use the last three SW positions #define SPINDLE_LASER_PWM_PIN 9 // 1.0: SW5 1.5: EXP3-7 ( "9") .. MUST BE HARDWARE PWM #define SPINDLE_LASER_ENA_PIN 8 // 1.0: SW6 1.5: EXP3-8 ( "8") .. Pin should have a pullup! + #define SPINDLE_DIR_PIN 10 // 1.0: SW4 1.5: EXP3-6 ("10") #elif ENABLED(BOARD_REV_1_1_TO_1_3) /** * Only four hardware PWMs physically connected to anything on these boards: @@ -242,14 +243,14 @@ * They have an LED and resistor pullup to +24V which could damage 3.3V-5V ICs. */ #if EXTRUDERS == 1 - #define SPINDLE_DIR_PIN 43 #define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM #define SPINDLE_LASER_ENA_PIN 41 // Pullup! + #define SPINDLE_DIR_PIN 43 #elif TEMP_SENSOR_BED == 0 // Can't use E0 so see if HEATER_BED_PIN is available #undef HEATER_BED_PIN - #define SPINDLE_DIR_PIN 38 // Probably pin 4 on 10 pin connector closest to the E0 socket #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM - Special precautions usually needed. #define SPINDLE_LASER_ENA_PIN 40 // Pullup! (Probably pin 6 on the 10-pin + #define SPINDLE_DIR_PIN 38 // Probably pin 4 on 10 pin connector closest to the E0 socket // connector closest to the E0 socket) #endif #endif diff --git a/Marlin/src/pins/ramps/pins_VORON.h b/Marlin/src/pins/ramps/pins_VORON.h index f56b0cb8fcfb..ee3d7f0185bf 100644 --- a/Marlin/src/pins/ramps/pins_VORON.h +++ b/Marlin/src/pins/ramps/pins_VORON.h @@ -29,15 +29,11 @@ #define BOARD_INFO_NAME "VORON Design v2" -#define MOSFET_C_PIN 11 - -#include "pins_RAMPS.h" - // // Heaters / Fans // -#undef FAN_PIN -#define FAN_PIN 5 // Using the pin for the controller fan since controller fan is always on. +#define MOSFET_C_PIN 11 +#define FAN0_PIN 5 // Using the pin for the controller fan since controller fan is always on. #define CONTROLLER_FAN_PIN 8 // @@ -50,7 +46,9 @@ #define E1_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan (same pin for both extruders since it's the same fan) #endif +#include "pins_RAMPS.h" + // -// LCDs and Controllers +// LCD / Controller // #undef BEEPER_PIN diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V20.h b/Marlin/src/pins/ramps/pins_ZRIB_V20.h index 127fffa7944b..d1c80f6a4afc 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V20.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V20.h @@ -53,7 +53,7 @@ #if ENABLED(ZONESTAR_LCD) #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_EN 17 #define LCD_PINS_D4 23 #define LCD_PINS_D5 25 #define LCD_PINS_D6 27 diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V52.h b/Marlin/src/pins/ramps/pins_ZRIB_V52.h index 34eee07c95db..5eada31c9cf9 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V52.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V52.h @@ -39,8 +39,6 @@ // // Heaters / Fans // -#define HEATER_1_PIN 7 -#define FAN_PIN 9 // PH6 ** Pin18 ** PWM9 #define FAN1_PIN 6 // diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V53.h b/Marlin/src/pins/ramps/pins_ZRIB_V53.h index 050516791e40..85420bdec3f2 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V53.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V53.h @@ -164,7 +164,7 @@ #define HEATER_0_PIN 10 #define HEATER_1_PIN 7 -#define FAN_PIN 9 +#define FAN0_PIN 9 #define HEATER_BED_PIN 8 #define FAN1_PIN 6 @@ -329,16 +329,16 @@ #define EXP2_08_PIN 41 #endif -////////////////////////// -// LCDs and Controllers // -////////////////////////// +// +// LCD / Controller +// #if ENABLED(ZONESTAR_12864LCD) #define LCDSCREEN_NAME "ZONESTAR LCD12864" #define LCD_SDSS 16 - #define LCD_PINS_RS 16 // ST7920_CS_PIN LCD_PIN_RS (PIN4 of LCD module) - #define LCD_PINS_ENABLE 23 // ST7920_DAT_PIN LCD_PIN_R/W (PIN5 of LCD module) - #define LCD_PINS_D4 17 // ST7920_CLK_PIN LCD_PIN_ENABLE (PIN6 of LCD module) + #define LCD_PINS_RS 16 // ST7920 CS (LCD-4) + #define LCD_PINS_EN 23 // ST7920 DAT LCD-R/W (LCD-5) + #define LCD_PINS_D4 17 // ST7920 CLK LCD-ENA (LCD-6) #define BTN_EN2 25 #define BTN_EN1 27 #define BTN_ENC 29 @@ -347,9 +347,9 @@ #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define LCDSCREEN_NAME "Reprap LCD12864" // Use EXP1 & EXP2 connector - #define LCD_PINS_RS 16 // ST7920_CS_PIN LCD_PIN_RS - #define LCD_PINS_ENABLE 17 // ST7920_DAT_PIN LCD_PIN_ENABLE - #define LCD_PINS_D4 23 // ST7920_CLK_PIN LCD_PIN_R/W + #define LCD_PINS_RS 16 // ST7920 CS + #define LCD_PINS_EN 17 // ST7920 DAT + #define LCD_PINS_D4 23 // ST7920 CLK LCD-R/W #define BTN_EN1 31 #define BTN_EN2 33 #define BTN_ENC 35 @@ -361,7 +361,7 @@ // OLED 128x64 //================================================================================ -#if EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) +#if ANY(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) #define LCDSCREEN_NAME "ZONESTAR 12864OLED" #define LCD_SDSS 16 #define LCD_PINS_RS 23 // RESET Pull low for 1s to init @@ -372,9 +372,9 @@ #define BTN_ENC 29 #define BEEPER_PIN -1 #define KILL_PIN -1 - #if EITHER(OLED_HW_IIC, OLED_HW_SPI) + #if ANY(OLED_HW_IIC, OLED_HW_SPI) #error "Oops! You must choose SW SPI for ZRIB V53 board and connect the OLED screen to EXP1 connector." - #else // SW_SPI + #else // SW_SPI #define DOGLCD_A0 LCD_PINS_DC #define DOGLCD_MOSI 35 // SDA #define DOGLCD_SCK 37 // SCK @@ -388,7 +388,7 @@ #if ENABLED(ZONESTAR_LCD) #define LCDSCREEN_NAME "LCD2004 ADCKEY" #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #define LCD_PINS_D5 EXP1_06_PIN #define LCD_PINS_D6 EXP1_07_PIN diff --git a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h index 69fa55f0dcbe..f63ca83723f3 100644 --- a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h +++ b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h @@ -136,7 +136,7 @@ #define HEATER_3_PIN 5 #define HEATER_BED_PIN 8 -#define FAN_PIN 9 +#define FAN0_PIN 9 // // Misc. Functions @@ -170,12 +170,12 @@ // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // Prefer the servo connector - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #elif HAS_FREE_AUX2_PINS - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_DIR_PIN 65 #endif #endif @@ -183,16 +183,14 @@ // // TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 66 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO 44 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK 64 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI 66 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO 44 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK 64 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/sam/env_validate.h b/Marlin/src/pins/sam/env_validate.h index 09bcd1364921..c51583f0a13c 100644 --- a/Marlin/src/pins/sam/env_validate.h +++ b/Marlin/src/pins/sam/env_validate.h @@ -19,9 +19,10 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H -#if BOTH(ALLOW_MEGA1280, ALLOW_MEGA2560) && NOT_TARGET(__SAM3X8E__, __AVR_ATmega1280__, __AVR_ATmega2560__) +#if ALL(ALLOW_MEGA1280, ALLOW_MEGA2560) && NOT_TARGET(__SAM3X8E__, __AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino Due or Mega' in 'Tools > Board.'" #elif ENABLED(ALLOW_MEGA2560) && NOT_TARGET(__SAM3X8E__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino Due or Mega' in 'Tools > Board.'" @@ -31,3 +32,5 @@ #undef ALLOW_MEGA1280 #undef ALLOW_MEGA2560 + +#endif diff --git a/Marlin/src/pins/sam/pins_ADSK.h b/Marlin/src/pins/sam/pins_ADSK.h index 425d6d45afb3..c264ffb50e98 100644 --- a/Marlin/src/pins/sam/pins_ADSK.h +++ b/Marlin/src/pins/sam/pins_ADSK.h @@ -116,7 +116,7 @@ A stepper for E0 extruder // #define HEATER_0_PIN 55 // "Hold": Analog pin 1, Digital pin 55 #define HEATER_BED_PIN 57 // "CoolEn": Analog pin 3, Digital pin 57 -#define FAN_PIN 54 // "Abort": Analog pin 0, Digital pin 54 +#define FAN0_PIN 54 // "Abort": Analog pin 0, Digital pin 54 #undef E0_AUTO_FAN_PIN #define E0_AUTO_FAN_PIN 56 // "Resume": Analog pin 2, Digital pin 56 @@ -160,7 +160,7 @@ A stepper for E0 extruder // // LCD / Controller // - #define LCD_PINS_ENABLE 14 + #define LCD_PINS_EN 14 #define LCD_PINS_RS 15 #define LCD_PINS_D4 16 #define LCD_PINS_D5 17 diff --git a/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h b/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h index 76431937a712..ceaeb8a587b5 100644 --- a/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h +++ b/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h @@ -113,8 +113,8 @@ #define HEATER_3_PIN 97 // PC20 on piggy #define HEATER_BED_PIN 69 // PA0 -#ifndef FAN_PIN - #define FAN_PIN 92 // PA5 +#ifndef FAN0_PIN + #define FAN0_PIN 92 // PA5 #endif #define FAN1_PIN 31 // PA7 @@ -148,12 +148,12 @@ // // LCD / Controller // + #if IS_RRD_FG_SC #define LCD_PINS_RS 18 - #define LCD_PINS_ENABLE 15 + #define LCD_PINS_EN 15 #define LCD_PINS_D4 19 #define BEEPER_PIN 64 - #undef UI_VOLTAGE_LEVEL #define UI_VOLTAGE_LEVEL 1 #endif diff --git a/Marlin/src/pins/sam/pins_ARCHIM1.h b/Marlin/src/pins/sam/pins_ARCHIM1.h index d9f1dcbf9427..e7530f981ba6 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM1.h +++ b/Marlin/src/pins/sam/pins_ARCHIM1.h @@ -153,8 +153,8 @@ #define HEATER_2_PIN 8 // D8 PC22 FET_PWM5 #define HEATER_BED_PIN 9 // D9 PC21 BED_PWM -#ifndef FAN_PIN - #define FAN_PIN 4 // D4 PC26 FET_PWM1 +#ifndef FAN0_PIN + #define FAN0_PIN 4 // D4 PC26 FET_PWM1 #endif #define FAN1_PIN 5 // D5 PC25 FET_PWM2 @@ -180,10 +180,11 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #define BEEPER_PIN 23 // D24 PA15_CTS1 #define LCD_PINS_RS 17 // D17 PA12_RXD1 - #define LCD_PINS_ENABLE 24 // D23 PA14_RTS1 + #define LCD_PINS_EN 24 // D23 PA14_RTS1 #define LCD_PINS_D4 69 // D69 PA0_CANTX0 #define LCD_PINS_D5 54 // D54 PA16_SCK1 #define LCD_PINS_D6 68 // D68 PA1_CANRX0 diff --git a/Marlin/src/pins/sam/pins_ARCHIM2.h b/Marlin/src/pins/sam/pins_ARCHIM2.h index 310dd8e2ac27..31ed50194cc2 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM2.h +++ b/Marlin/src/pins/sam/pins_ARCHIM2.h @@ -145,19 +145,17 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers. +// SPI pins for TMC2130 stepper drivers. // Required for the Archim2 board. // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 28 // PD3 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO 26 // PD1 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK 27 // PD2 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI 28 // PD3 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO 26 // PD1 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK 27 // PD2 #endif // @@ -176,8 +174,8 @@ #define HEATER_2_PIN 8 // D8 PC22 FET_PWM5 #define HEATER_BED_PIN 9 // D9 PC21 BED_PWM -#ifndef FAN_PIN - #define FAN_PIN 4 // D4 PC26 FET_PWM1 +#ifndef FAN0_PIN + #define FAN0_PIN 4 // D4 PC26 FET_PWM1 #endif #define FAN1_PIN 5 // D5 PC25 FET_PWM2 @@ -237,10 +235,11 @@ // // LCD / Controller // + #if ANY(HAS_WIRED_LCD, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) #define BEEPER_PIN 23 // D24 PA15_CTS1 #define LCD_PINS_RS 17 // D17 PA12_RXD1 - #define LCD_PINS_ENABLE 24 // D23 PA14_RTS1 + #define LCD_PINS_EN 24 // D23 PA14_RTS1 #define LCD_PINS_D4 69 // D69 PA0_CANTX0 #define LCD_PINS_D5 54 // D54 PA16_SCK1 #define LCD_PINS_D6 68 // D68 PA1_CANRX0 diff --git a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h index d44f6490da63..3d15f37e47fa 100644 --- a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h +++ b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h @@ -91,7 +91,7 @@ // // Fans // -//#define FAN_PIN 8 +//#define FAN0_PIN 8 // // Auto fans diff --git a/Marlin/src/pins/sam/pins_DUE3DOM.h b/Marlin/src/pins/sam/pins_DUE3DOM.h index 81eca3e4b14a..66aa581271a2 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM.h @@ -83,7 +83,7 @@ #define TEMP_BED_PIN 1 // Analog Input (BED thermistor) // SPI for MAX Thermocouple -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN -1 #else #define TEMP_0_CS_PIN -1 @@ -96,8 +96,8 @@ #define HEATER_1_PIN 8 // HOTEND1 MOSFET #define HEATER_BED_PIN 39 // BED MOSFET -#ifndef FAN_PIN - #define FAN_PIN 11 // FAN1 header on board - PRINT FAN +#ifndef FAN0_PIN + #define FAN0_PIN 11 // FAN1 header on board - PRINT FAN #endif #define FAN1_PIN 9 // FAN2 header on board - CONTROLLER FAN #define FAN2_PIN 12 // FAN3 header on board - EXTRUDER0 FAN @@ -111,10 +111,11 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #define LCD_PINS_RS 42 - #define LCD_PINS_ENABLE 43 + #define LCD_PINS_EN 43 #define LCD_PINS_D4 44 #define LCD_PINS_D5 45 #define LCD_PINS_D6 46 @@ -154,7 +155,7 @@ #elif ENABLED(SPARK_FULL_GRAPHICS) #define LCD_PINS_D4 29 - #define LCD_PINS_ENABLE 27 + #define LCD_PINS_EN 27 #define LCD_PINS_RS 25 #define BTN_EN1 35 diff --git a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h index 7754fa9329f9..b9f73adfe9c1 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h @@ -69,10 +69,13 @@ #define TEMP_0_PIN 0 // Analog Input (HOTEND0 thermistor) #define TEMP_1_PIN 2 // Analog Input (unused) #define TEMP_BED_PIN 1 // Analog Input (BED thermistor) -#define TEMP_BOARD_PIN 5 // Analog Input (OnBoard thermistor beta 3950) + +#ifndef TEMP_BOARD_PIN + #define TEMP_BOARD_PIN 5 // Analog Input (OnBoard thermistor beta 3950) +#endif // SPI for MAX Thermocouple -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 53 #else #define TEMP_0_CS_PIN 53 @@ -84,8 +87,8 @@ #define HEATER_0_PIN 13 // HOTEND0 MOSFET #define HEATER_BED_PIN 7 // BED MOSFET -#ifndef FAN_PIN - #define FAN_PIN 11 // FAN1 header on board - PRINT FAN +#ifndef FAN0_PIN + #define FAN0_PIN 11 // FAN1 header on board - PRINT FAN #endif #define FAN1_PIN 12 // FAN2 header on board - CONTROLLER FAN #define FAN2_PIN 9 // FAN3 header on board - EXTRUDER0 FAN @@ -100,10 +103,11 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #define LCD_PINS_RS 42 - #define LCD_PINS_ENABLE 43 + #define LCD_PINS_EN 43 #define LCD_PINS_D4 44 #define LCD_PINS_D5 45 #define LCD_PINS_D6 46 @@ -147,7 +151,7 @@ #elif ENABLED(SPARK_FULL_GRAPHICS) #define LCD_PINS_D4 29 - #define LCD_PINS_ENABLE 27 + #define LCD_PINS_EN 27 #define LCD_PINS_RS 25 #define BTN_EN1 35 diff --git a/Marlin/src/pins/sam/pins_KRATOS32.h b/Marlin/src/pins/sam/pins_KRATOS32.h index f7867f9b2607..bebe2b82a35d 100644 --- a/Marlin/src/pins/sam/pins_KRATOS32.h +++ b/Marlin/src/pins/sam/pins_KRATOS32.h @@ -32,7 +32,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x1F400 // 16K #endif @@ -126,8 +126,8 @@ #define HEATER_3_PIN 10 #define HEATER_BED_PIN 7 // BED -#ifndef FAN_PIN - #define FAN_PIN 9 +#ifndef FAN0_PIN + #define FAN0_PIN 9 #endif #define FAN1_PIN 8 @@ -145,6 +145,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #define BTN_EN1 48 @@ -160,7 +161,7 @@ #if IS_RRD_FG_SC #define LCD_PINS_RS 42 - #define LCD_PINS_ENABLE 43 + #define LCD_PINS_EN 43 #define LCD_PINS_D4 44 #define BTN_BACK 52 diff --git a/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h b/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h index aa01a9227fb3..8fd1843ab59e 100644 --- a/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h +++ b/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h @@ -138,8 +138,8 @@ #define HEATER_0_PIN 40 // PA5 #define HEATER_BED_PIN 41 // PB24 -#ifndef FAN_PIN - #define FAN_PIN 13 // PB27 Fan1A +#ifndef FAN0_PIN + #define FAN0_PIN 13 // PB27 Fan1A #endif #define FAN1_PIN 58 // PA6 Fan1B diff --git a/Marlin/src/pins/sam/pins_RADDS.h b/Marlin/src/pins/sam/pins_RADDS.h index af24014614c1..4f713391fc96 100644 --- a/Marlin/src/pins/sam/pins_RADDS.h +++ b/Marlin/src/pins/sam/pins_RADDS.h @@ -32,7 +32,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x2000 // 8K #endif @@ -180,7 +180,7 @@ #define TEMP_BED_PIN 4 // Analog Input // SPI for MAX Thermocouple -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 53 #else #define TEMP_0_CS_PIN 49 @@ -196,8 +196,8 @@ #define HEATER_BED_PIN 7 // BED #endif -#ifndef FAN_PIN - #define FAN_PIN 9 +#ifndef FAN0_PIN + #define FAN0_PIN 9 #endif #define FAN1_PIN 8 @@ -224,12 +224,13 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #if ENABLED(RADDS_DISPLAY) #define LCD_PINS_RS 42 - #define LCD_PINS_ENABLE 43 + #define LCD_PINS_EN 43 #define LCD_PINS_D4 44 #define LCD_PINS_D5 45 #define LCD_PINS_D6 46 @@ -252,7 +253,7 @@ // an adapter such as https://www.thingiverse.com/thing:1740725 #define LCD_PINS_RS 42 - #define LCD_PINS_ENABLE 43 + #define LCD_PINS_EN 43 #define LCD_PINS_D4 44 #define BEEPER_PIN 41 @@ -276,7 +277,7 @@ #elif ENABLED(SPARK_FULL_GRAPHICS) #define LCD_PINS_D4 29 - #define LCD_PINS_ENABLE 27 + #define LCD_PINS_EN 27 #define LCD_PINS_RS 25 #define BTN_EN1 35 diff --git a/Marlin/src/pins/sam/pins_RAMPS4DUE.h b/Marlin/src/pins/sam/pins_RAMPS4DUE.h index 6d9d06a17561..408242e065e2 100644 --- a/Marlin/src/pins/sam/pins_RAMPS4DUE.h +++ b/Marlin/src/pins/sam/pins_RAMPS4DUE.h @@ -45,8 +45,8 @@ // // Temperature Sensors // -#define TEMP_0_PIN 9 // Analog Input -#define TEMP_1_PIN -1 // Analog Input -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN 9 // Analog Input +#define TEMP_1_PIN -1 // Analog Input +#define TEMP_BED_PIN 10 // Analog Input #include "../ramps/pins_RAMPS.h" diff --git a/Marlin/src/pins/sam/pins_RAMPS_DUO.h b/Marlin/src/pins/sam/pins_RAMPS_DUO.h index 5b2b2f0b6615..6b7bf514669e 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_DUO.h +++ b/Marlin/src/pins/sam/pins_RAMPS_DUO.h @@ -45,24 +45,19 @@ #define BOARD_INFO_NAME "RAMPS Duo" -#define ALLOW_SAM3X8E -#include "../ramps/pins_RAMPS.h" - // // Temperature Sensors // -#undef TEMP_0_PIN #define TEMP_0_PIN 9 // Analog Input - -#undef TEMP_1_PIN #define TEMP_1_PIN 11 // Analog Input - -#undef TEMP_BED_PIN #define TEMP_BED_PIN 10 // Analog Input +#define ALLOW_SAM3X8E +#include "../ramps/pins_RAMPS.h" + // SPI for MAX Thermocouple #undef TEMP_0_CS_PIN -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 69 // Don't use 53 if using Display/SD card #else #define TEMP_0_CS_PIN 69 // Don't use 49 (SD_DETECT_PIN) @@ -71,9 +66,10 @@ // // LCD / Controller // + #if HAS_WIRED_LCD - #if BOTH(IS_NEWPANEL, PANEL_ONE) + #if ALL(IS_NEWPANEL, PANEL_ONE) #undef LCD_PINS_D4 #define LCD_PINS_D4 68 diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h index 00eba994a8d9..2b9c8fd7eb79 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h @@ -110,7 +110,7 @@ #define TEMP_BED_PIN 0 // Analog Input // SPI for MAX Thermocouple -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 53 #else #define TEMP_0_CS_PIN 49 @@ -124,8 +124,8 @@ #define HEATER_2_PIN 11 #define HEATER_BED_PIN 8 -#ifndef FAN_PIN - #define FAN_PIN 12 +#ifndef FAN0_PIN + #define FAN0_PIN 12 #endif // @@ -134,7 +134,9 @@ #define SDSS 4 #define LED_PIN 13 -/** ------ ------ +/** + * RAMPS-FD LCD adapter + * ------ ------ * 37 | 1 2 | 35 (MISO) 50 | 1 2 | 76 (SCK) * 29 | 3 4 | 27 (EN2) 31 | 3 4 | 4 (SD_SS) * 25 5 6 | 23 (EN1) 33 5 6 | 75 (MOSI) @@ -164,23 +166,25 @@ // // LCD / Controller // + #if HAS_WIRED_LCD - // ramps-fd lcd adaptor #define BEEPER_PIN EXP1_01_PIN - #define BTN_EN1 EXP2_05_PIN - #define BTN_EN2 EXP2_03_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN2 EXP2_03_PIN + #define BTN_EN1 EXP2_05_PIN + #define SD_DETECT_PIN EXP2_07_PIN #if IS_NEWPANEL #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #endif #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS LCD_PINS_ENABLE - #define DOGLCD_A0 LCD_PINS_RS + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN #define DOGLCD_SCK EXP2_02_PIN #define DOGLCD_MOSI EXP2_06_PIN @@ -189,7 +193,7 @@ #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_05_PIN #endif @@ -217,7 +221,7 @@ #endif - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define DOGLCD_A0 EXP1_07_PIN #define KILL_PIN 51 #define STAT_LED_BLUE_PIN EXP1_03_PIN @@ -258,7 +262,7 @@ // M3/M4/M5 - Spindle/Laser Control // #if HOTENDS < 3 && HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) - #define SPINDLE_LASER_ENA_PIN 45 // Use E2 ENA #define SPINDLE_LASER_PWM_PIN 12 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 45 // Use E2 ENA #define SPINDLE_DIR_PIN 47 // Use E2 DIR #endif diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V2.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V2.h index 55a42b2a4709..57c7732de871 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V2.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V2.h @@ -31,7 +31,7 @@ #define BOARD_INFO_NAME "RAMPS-FD v2" #ifndef E0_CS_PIN - #define E0_CS_PIN 69 // moved from A13 to A15 on v2.2, if not earlier + #define E0_CS_PIN 69 // moved from A13 to A15 on v2.2, if not earlier #endif #include "pins_RAMPS_FD_V1.h" @@ -44,9 +44,9 @@ #define MARLIN_EEPROM_SIZE 0x10000 // 64K in a 24C512 #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN 12 #endif #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 5 // Analog Input on AUX2 + #define FILWIDTH_PIN 5 // Analog Input on AUX2 #endif diff --git a/Marlin/src/pins/sam/pins_RAMPS_SMART.h b/Marlin/src/pins/sam/pins_RAMPS_SMART.h index b02ddef16628..90e9b9969790 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_SMART.h +++ b/Marlin/src/pins/sam/pins_RAMPS_SMART.h @@ -82,7 +82,7 @@ #define TEMP_BED_PIN 11 // Analog Input // SPI for MAX Thermocouple -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 67 // Don't use 53 if using Display/SD card #else #define TEMP_0_CS_PIN 67 // Don't use 49 (SD_DETECT_PIN) @@ -95,6 +95,7 @@ // // LCD / Controller // + #if ENABLED(AZSMZ_12864) // Support for AZSMZ 12864 LCD with SD Card 3D printer smart controller control panel diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index 35279bf2e513..f083f01d4f12 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -122,8 +122,8 @@ #define HEATER_2_PIN 11 #define HEATER_BED_PIN 7 // BED H1 -#ifndef FAN_PIN - #define FAN_PIN 9 +#ifndef FAN0_PIN + #define FAN0_PIN 9 #endif #define FAN1_PIN 8 #define CONTROLLER_FAN_PIN -1 @@ -145,7 +145,7 @@ // SPI for MAX Thermocouple /* -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN EXP1_08_PIN #else #define TEMP_0_CS_PIN 49 @@ -195,27 +195,28 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_01_PIN 62 -#define EXP1_02_PIN 40 -#define EXP1_03_PIN 64 -#define EXP1_04_PIN 63 -#define EXP1_05_PIN 48 -#define EXP1_06_PIN 50 -#define EXP1_07_PIN 52 -#define EXP1_08_PIN 53 +#define EXP1_01_PIN 62 // BEEPER +#define EXP1_02_PIN 40 // ENC +#define EXP1_03_PIN 64 // LCD_EN +#define EXP1_04_PIN 63 // LCD_RS +#define EXP1_05_PIN 48 // LCD_D4 / RESET +#define EXP1_06_PIN 50 // LCD_D5 +#define EXP1_07_PIN 52 // LCD_D6 +#define EXP1_08_PIN 53 // LCD_D7 / ENABLE #define EXP2_01_PIN 74 // MISO #define EXP2_02_PIN 76 // SCK -#define EXP2_03_PIN 44 -#define EXP2_04_PIN 10 -#define EXP2_05_PIN 42 +#define EXP2_03_PIN 44 // EN1 +#define EXP2_04_PIN 10 // SDSS +#define EXP2_05_PIN 42 // EN2 #define EXP2_06_PIN 75 // MOSI -#define EXP2_07_PIN 51 +#define EXP2_07_PIN 51 // SD DET #define EXP2_08_PIN -1 // RESET // // LCD / Controller // + #if HAS_WIRED_LCD #if ANY(RADDS_DISPLAY, IS_RRD_SC, IS_RRD_FG_SC) @@ -227,15 +228,15 @@ #define SD_DETECT_PIN EXP2_07_PIN #endif - #if EITHER(RADDS_DISPLAY, IS_RRD_SC) + #if ANY(RADDS_DISPLAY, IS_RRD_SC) #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #elif IS_RRD_FG_SC #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #elif HAS_U8GLIB_I2C_OLED @@ -254,7 +255,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN // D5 #endif @@ -273,7 +274,7 @@ //http://doku.radds.org/dokumentation/other-electronics/sparklcd/ #error "Oops! SPARK_FULL_GRAPHICS not supported with RURAMPS4D." //#define LCD_PINS_D4 29 //? - //#define LCD_PINS_ENABLE 27 //? + //#define LCD_PINS_EN 27 //? //#define LCD_PINS_RS 25 //? //#define BTN_EN1 35 //? //#define BTN_EN2 33 //? diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 78cf3f6e1065..fa27868ff940 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -114,7 +114,7 @@ #define HEATER_2_PIN 11 #define HEATER_BED_PIN 7 // BED H1 -#define FAN_PIN 9 +#define FAN0_PIN 9 #define FAN1_PIN 8 #define CONTROLLER_FAN_PIN -1 @@ -135,7 +135,7 @@ // SPI for MAX Thermocouple /* -#if DISABLED(SDSUPPORT) +#if !HAS_MEDIA #define TEMP_0_CS_PIN 53 #else #define TEMP_0_CS_PIN 49 @@ -206,6 +206,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #if ANY(RADDS_DISPLAY, IS_RRD_SC, IS_RRD_FG_SC) @@ -217,15 +218,15 @@ #define SD_DETECT_PIN EXP2_07_PIN #endif - #if EITHER(RADDS_DISPLAY, IS_RRD_SC) + #if ANY(RADDS_DISPLAY, IS_RRD_SC) #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #elif IS_RRD_FG_SC #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #elif HAS_U8GLIB_I2C_OLED @@ -244,7 +245,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN // D5 #endif diff --git a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h index 616f47f8562a..f3ec7806e620 100644 --- a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h +++ b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h @@ -120,8 +120,8 @@ #define HEATER_3_PIN 9 #define HEATER_BED_PIN 2 -#ifndef FAN_PIN - #define FAN_PIN 6 +#ifndef FAN0_PIN + #define FAN0_PIN 6 #endif #define FAN2_PIN 5 @@ -166,7 +166,7 @@ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) #define LCD_PINS_RS A8 // CS chip select / SS chip slave select - #define LCD_PINS_ENABLE MOSI // SID (MOSI) + #define LCD_PINS_EN MOSI // SID (MOSI) #define LCD_PINS_D4 SCK // SCK (CLK) clock #define BTN_EN1 20 diff --git a/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h b/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h index 9901b78c4663..6f41bd6848c9 100644 --- a/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h +++ b/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h @@ -102,7 +102,7 @@ // #define HEATER_0_PIN 6 #define HEATER_BED_PIN 7 -#define FAN_PIN 8 +#define FAN0_PIN 8 #define FAN1_PIN 9 // @@ -130,25 +130,25 @@ * 5B | . . | 5V * ------ * - *- Special mapping of EXP1 to EXP3 to work with Ender displays. + *- Special mapping of EXP1 to work with Ender displays. * - * Enable CR10_STOCKDISPLAY in Configuration.h and connect EXP1 to the display EXP3 with this mapping. * ------ - * VCC | 1 2 | GND - * LCDDE | 3 4 | LCDRS - * LCDD4 | 5 6 BTN_EN2 - * RESET | 7 8 | BTN_EN1 - * BTN_ENCODER | 9 10 | BEEPER + * BEEPER | 1 2 | ENC + * EN1 | 3 4 | RESET + * EN2 5 6 | LCD_D4 + * LCD_RS | 7 8 | LCD_EN + * GND | 9 10 | 5V * ------ + * EXP1 * *- Digital pinout reference of the Bricolemon for advanced users/configurations. * * ------ ------ - * VCC | 1 2 | GND D49 | 1 2 | GND - * D39 | 3 4 | D38 RST | 3 4 | D44 - * D37 | 5 6 D36 D51 | 5 6 D42 - * D34 | 7 8 | D35 D53 | 7 8 | D43 - * D40 | 9 10 | D41 D52 | 9 10 | D50 + * D41 | 1 2 | D40 D50 | 1 2 | D52 + * D35 | 3 4 | D34 D43 | 3 4 | D53 + * D36 5 6 | D37 D42 5 6 | D51 + * D38 | 7 8 | D39 D44 | 7 8 | RST + * GND | 9 10 | VCC GND | 9 10 | D49 * ------ ------ * EXP1 EXP2 * @@ -235,14 +235,14 @@ // TO TEST //#define LCD_PINS_RS EXP2_10_PIN // CS chip select /SS chip slave select - //#define LCD_PINS_ENABLE EXP2_06_PIN // SID (MOSI) + //#define LCD_PINS_EN EXP2_06_PIN // SID (MOSI) //#define LCD_PINS_D4 EXP2_02_PIN // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) // TO TEST //#define LCD_PINS_RS EXP1_02_PIN - //#define LCD_PINS_ENABLE EXP2_05_PIN + //#define LCD_PINS_EN EXP2_05_PIN //#define LCD_PINS_D4 57 // Mega/Due:65 - AGCM4:57 //#define LCD_PINS_D5 58 // Mega/Due:66 - AGCM4:58 //#define LCD_PINS_D6 EXP2_07_PIN @@ -254,7 +254,7 @@ // TO TEST #define LCD_PINS_RS EXP3_04_PIN - #define LCD_PINS_ENABLE EXP3_03_PIN + #define LCD_PINS_EN EXP3_03_PIN #define LCD_PINS_D4 EXP3_05_PIN #if !IS_NEWPANEL @@ -266,7 +266,7 @@ // TO TEST //#define LCD_PINS_RS 56 // Mega/Due:64 - AGCM4:56 - //#define LCD_PINS_ENABLE EXP2_07_PIN + //#define LCD_PINS_EN EXP2_07_PIN //#define LCD_PINS_D4 55 // Mega/Due:63 - AGCM4:55 //#define LCD_PINS_D5 EXP1_02_PIN //#define LCD_PINS_D6 EXP2_05_PIN @@ -274,7 +274,7 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) // TO TEST //#define LCD_PINS_DC 25 // Set as output on init //#define LCD_PINS_RS 27 // Pull low for 1s to init @@ -284,11 +284,10 @@ //#define DOGLCD_SCK 23 //#define DOGLCD_A0 LCD_PINS_DC - #else // Definitions for any standard Display #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #define LCD_PINS_D5 EXP1_06_PIN #define LCD_PINS_D6 EXP1_07_PIN @@ -373,7 +372,7 @@ //#define LCD_SDSS SDSS //#define SD_DETECT_PIN EXP2_10_PIN - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) // TO TEST //#define DOGLCD_CS 45 @@ -408,7 +407,7 @@ //#define SD_DETECT_PIN EXP2_10_PIN //#define KILL_PIN EXP1_01_PIN - #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) + #elif ANY(MKS_MINI_12864, FYSETC_MINI_12864) // TO TEST //#define BEEPER_PIN EXP1_06_PIN @@ -453,7 +452,7 @@ //#define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN // TO TEST //#define RGB_LED_R_PIN 25 diff --git a/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h b/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h index 1c73926781ac..699f10ed481e 100644 --- a/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h +++ b/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h @@ -152,7 +152,7 @@ #define HEATER_BED_PIN 7 // The board has 4 PWM fans, use and configure as desired -#define FAN_PIN 8 +#define FAN0_PIN 8 #define FAN1_PIN 9 #define FAN2_PIN 30 #define FAN3_PIN 31 @@ -182,25 +182,25 @@ * 5B | . . | 5V * ------ * - *- Special mapping of EXP1 to EXP3 to work with Ender displays. + *- Special mapping of EXP1 to work with Ender displays. * - * Enable CR10_STOCKDISPLAY in Configuration.h and connect EXP1 to the display EXP3 with this mapping. * ------ - * VCC | 1 2 | GND - * LCDDE | 3 4 | LCDRS - * LCDD4 | 5 6 BTN_EN2 - * RESET | 7 8 | BTN_EN1 - * BTN_ENCODER | 9 10 | BEEPER + * BEEPER | 1 2 | ENC + * EN1 | 3 4 | RESET + * EN2 5 6 | LCD_D4 + * LCD_RS | 7 8 | LCD_EN + * GND | 9 10 | 5V * ------ + * EXP1 * *- Digital pinout reference of the Bricolemon for advanced users/configurations. * * ------ ------ - * VCC | 1 2 | GND D49 | 1 2 | GND - * D39 | 3 4 | D38 RST | 3 4 | D44 - * D37 | 5 6 D36 D51 | 5 6 D42 - * D34 | 7 8 | D35 D53 | 7 8 | D43 - * D40 | 9 10 | D41 D52 | 9 10 | D50 + * D41 | 1 2 | D40 D50 | 1 2 | D52 + * D35 | 3 4 | D34 D43 | 3 4 | D53 + * D36 5 6 | D37 D42 5 6 | D51 + * D38 | 7 8 | D39 D44 | 7 8 | RST + * GND | 9 10 | VCC GND | 9 10 | D49 * ------ ------ * EXP1 EXP2 * @@ -288,14 +288,14 @@ // TO TEST //#define LCD_PINS_RS EXP2_10_PIN // CS chip select /SS chip slave select - //#define LCD_PINS_ENABLE EXP2_06_PIN // SID (MOSI) + //#define LCD_PINS_EN EXP2_06_PIN // SID (MOSI) //#define LCD_PINS_D4 EXP2_02_PIN // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) // TO TEST //#define LCD_PINS_RS EXP1_02_PIN - //#define LCD_PINS_ENABLE EXP2_05_PIN + //#define LCD_PINS_EN EXP2_05_PIN //#define LCD_PINS_D4 57 // Mega/Due:65 - AGCM4:57 //#define LCD_PINS_D5 58 // Mega/Due:66 - AGCM4:58 //#define LCD_PINS_D6 EXP2_07_PIN @@ -307,7 +307,7 @@ // TO TEST #define LCD_PINS_RS EXP3_04_PIN - #define LCD_PINS_ENABLE EXP3_03_PIN + #define LCD_PINS_EN EXP3_03_PIN #define LCD_PINS_D4 EXP3_05_PIN #if !IS_NEWPANEL @@ -319,7 +319,7 @@ // TO TEST //#define LCD_PINS_RS 56 // Mega/Due:64 - AGCM4:56 - //#define LCD_PINS_ENABLE EXP2_07_PIN + //#define LCD_PINS_EN EXP2_07_PIN //#define LCD_PINS_D4 55 // Mega/Due:63 - AGCM4:55 //#define LCD_PINS_D5 EXP1_02_PIN //#define LCD_PINS_D6 EXP2_05_PIN @@ -327,7 +327,7 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) // TO TEST //#define LCD_PINS_DC 25 // Set as output on init //#define LCD_PINS_RS 27 // Pull low for 1s to init @@ -340,7 +340,7 @@ #else // Definitions for any standard Display #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #define LCD_PINS_D5 EXP1_06_PIN #define LCD_PINS_D6 EXP1_07_PIN @@ -424,7 +424,7 @@ //#define LCD_SDSS SDSS //#define SD_DETECT_PIN EXP2_10_PIN - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) // TO TEST //#define DOGLCD_CS 45 @@ -459,7 +459,7 @@ //#define SD_DETECT_PIN EXP2_10_PIN //#define KILL_PIN EXP1_01_PIN - #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) + #elif ANY(MKS_MINI_12864, FYSETC_MINI_12864) // TO TEST //#define BEEPER_PIN EXP1_06_PIN @@ -504,7 +504,7 @@ //#define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN // TO TEST //#define RGB_LED_R_PIN 25 diff --git a/Marlin/src/pins/samd/pins_MINITRONICS20.h b/Marlin/src/pins/samd/pins_MINITRONICS20.h index ed83c835469a..2a450698d12a 100644 --- a/Marlin/src/pins/samd/pins_MINITRONICS20.h +++ b/Marlin/src/pins/samd/pins_MINITRONICS20.h @@ -60,8 +60,9 @@ #define Z_STOP_PIN 4 /** - * NOTE: Useful if extra TMC2209 are to be used as independent axes. - * We need to configure the new digital PIN, for this we could configure on the board the extra pin of this stepper, for example as a MIN_PIN/MAX_PIN. This pin is the D14. + * NOTE: For extra TMC2209 used as independent axes a new digital PIN is needed. + * We can configure on the board the extra pin of this stepper, + * e.g., as a MIN_PIN/MAX_PIN. This pin is D14. */ //#define Z2_STOP_PIN 14 //#define X2_STOP_PIN 14 @@ -105,7 +106,7 @@ // This board have the option to use an extra TMC2209 stepper, one of the use could be as a second extruder. #if EXTRUDERS < 2 - // TODO: Corregir aquí que cuando tenemos dos extrusores o lo que sea, utiliza los endstop que le sobran, osea los max, no hay Z2_endstop + // TODO: Correct here that when we have two extruders (or whatever), use the extra endstops. i.e., The max, there is no Z2_endstop. #if NUM_Z_STEPPERS > 1 #define Z2_STOP_PIN 14 #endif @@ -117,8 +118,8 @@ #undef Z3_DRIVER_TYPE #undef Z4_DRIVER_TYPE - // Si tenemos más de un extrusor lo que hacemos es definir el nuevo extrusor así como sus pines - // Acordarse de definir el #define TEMP_SENSOR_1, ya que este contiene el tipo de sonda del extrusor E1 + // For more than one extruder define the new extruder and its pins. + // Remember to #define TEMP_SENSOR_1, since this contains the E1 sensor type. #define FIL_RUNOUT2_PIN 14 @@ -149,7 +150,7 @@ #define SPINDLE_LASER_PWM_PIN 6 // The board has 4 PWM fans, use and configure as desired -#define FAN_PIN 24 +#define FAN0_PIN 24 // // LCD / Controller @@ -166,13 +167,9 @@ #define EXP3_08_PIN EXP1_08_PIN #endif -/************************************/ -/***** Configurations Section ******/ -/************************************/ - /** - * This sections starts with the pins_RAMPS_144.h as example, after if you need any new - * display, you could use normal duponts and connect it with with the scheme showed before. + * This section is based on pins_RAMPS_144.h. To use a new display, you + * could use normal duponts and connect with the scheme shown before. * Tested: * - Ender-3 Old display (Character LCD) * - Ender-3 New Serial DWING Display @@ -190,18 +187,18 @@ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) #define LCD_PINS_RS 18 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE MOSI // SID (MOSI) + #define LCD_PINS_EN MOSI // SID (MOSI) #define LCD_PINS_D4 SCK // SCK (CLK) clock #define BTN_ENC 23 #define BTN_EN1 27 #define BTN_EN2 33 - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) // TO TEST //#define LCD_PINS_RS EXP1_02_PIN - //#define LCD_PINS_ENABLE EXP2_05_PIN + //#define LCD_PINS_EN EXP2_05_PIN //#define LCD_PINS_D4 57 // Mega/Due:65 - AGCM4:57 //#define LCD_PINS_D5 58 // Mega/Due:66 - AGCM4:58 //#define LCD_PINS_D6 EXP2_07_PIN @@ -212,9 +209,9 @@ #if ENABLED(CR10_STOCKDISPLAY) // TO TEST - //#define LCD_PINS_RS EXP3_04_PIN - //#define LCD_PINS_ENABLE EXP3_03_PIN - //#define LCD_PINS_D4 EXP3_05_PIN + //#define LCD_PINS_RS EXP3_04_PIN + //#define LCD_PINS_EN EXP3_03_PIN + //#define LCD_PINS_D4 EXP3_05_PIN #if !IS_NEWPANEL // TO TEST @@ -225,7 +222,7 @@ // TO TEST //#define LCD_PINS_RS 56 // Mega/Due:64 - AGCM4:56 - //#define LCD_PINS_ENABLE EXP2_07_PIN + //#define LCD_PINS_EN EXP2_07_PIN //#define LCD_PINS_D4 55 // Mega/Due:63 - AGCM4:55 //#define LCD_PINS_D5 EXP1_02_PIN //#define LCD_PINS_D6 EXP2_05_PIN @@ -233,7 +230,7 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) // TO TEST //#define LCD_PINS_DC 25 // Set as output on init //#define LCD_PINS_RS 27 // Pull low for 1s to init @@ -246,7 +243,7 @@ #else // Definitions for any standard Display #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #define LCD_PINS_D5 EXP1_06_PIN #define LCD_PINS_D6 EXP1_07_PIN @@ -278,7 +275,7 @@ #if IS_RRD_SC - //#define BEEPER_PIN EXP1_01_PIN + //#define BEEPER_PIN EXP1_01_PIN #if ENABLED(CR10_STOCKDISPLAY) // TO TEST @@ -297,7 +294,7 @@ #ifndef SD_DETECT_PIN #define SD_DETECT_PIN EXP2_07_PIN #endif - //#define KILL_PIN EXP2_10_PIN + //#define KILL_PIN EXP2_10_PIN #if ENABLED(BQ_LCD_SMART_CONTROLLER) //#define LCD_BACKLIGHT_PIN EXP1_08_PIN // TO TEST @@ -322,7 +319,7 @@ //#define LCD_SDSS SDSS //#define SD_DETECT_PIN EXP2_10_PIN - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) // TO TEST //#define DOGLCD_CS 45 @@ -357,7 +354,7 @@ //#define SD_DETECT_PIN EXP2_10_PIN //#define KILL_PIN EXP1_01_PIN - #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) + #elif ANY(MKS_MINI_12864, FYSETC_MINI_12864) // TO TEST //#define BEEPER_PIN EXP1_06_PIN @@ -402,7 +399,7 @@ //#define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN // TO TEST //#define RGB_LED_R_PIN 25 @@ -427,7 +424,7 @@ // TO TEST //#define BEEPER_PIN EXP2_05_PIN // not connected to a pin - //#define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) + //#define LCD_BACKLIGHT_PIN 57 // Backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) //#define DOGLCD_A0 EXP2_07_PIN //#define DOGLCD_CS 58 // Mega/Due:66 - AGCM4:58 @@ -502,8 +499,8 @@ #if HAS_TMC_UART /** - * Address for the UART Configuration of the TMC2209. Override in Configuration files. - * To test TMC2209 Steppers enable TMC_DEBUG in Configuration_adv.h and test the M122 command with voltage on the steppers. + * TMC2209 UART Address. Override in Configuration files. + * To test TMC2209 Steppers enable TMC_DEBUG and test M122 with voltage on the steppers. */ #ifndef X_SLAVE_ADDRESS #define X_SLAVE_ADDRESS 0b00 @@ -523,8 +520,8 @@ /** * TMC2208/TMC2209 stepper drivers - * It seems to work perfectly fine on Software Serial, if an advanced user wants to test, you could use the SAMD51 Serial1 and Serial 2. Be careful with the Sercom configurations. - * Steppers 1,2,3,4 (X,Y,Z,E0) are on the Serial1, Sercom (RX = 0, TX = 1), extra stepper 5 (E1 or any axis you want) is on Serial2, Sercom (RX = 17, TX = 16) + * Seems to work fine with Software Serial. If you want to test, use SAMD51 Serial1 and Serial2. Be careful with the Sercom configurations. + * Steppers 1,2,3,4 (X,Y,Z,E0) are on Serial1, Sercom (RX=0, TX=1), extra stepper 5 (E1 or any axis you want) is on Serial2, Sercom (RX=17, TX=16) */ //#define X_HARDWARE_SERIAL Serial1 diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index 7adb2404c158..39061efb2d6f 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -48,6 +48,21 @@ #define I2C_EEPROM // EEPROM on I2C-0 #define MARLIN_EEPROM_SIZE 0x8000 // 32K (24lc256) +// +// Foam Cutter requirements +// + +#if ENABLED(FOAMCUTTER_XYUV) + #define MOSFET_C_PIN -1 + #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) && NUM_SERVOS < 2 + #define SPINDLE_LASER_PWM_PIN 8 // Hardware PWM + #endif + #define Z_MIN_PIN -1 + #define Z_MAX_PIN -1 + #define I_STOP_PIN 18 + #define J_STOP_PIN 19 +#endif + // // Limit Switches // @@ -123,7 +138,7 @@ #else #define HEATER_1_PIN 8 #endif -#define FAN_PIN 9 +#define FAN0_PIN 9 #define FAN1_PIN 7 #define FAN2_PIN 12 @@ -155,8 +170,8 @@ // #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) #if !NUM_SERVOS // Use servo connector if possible - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #else #error "No auto-assignable Spindle/Laser pins available." @@ -164,18 +179,16 @@ #endif // -// TMC software SPI +// TMC SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 58 // Mega/Due:66 - AGCM4:58 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO 44 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK 56 // Mega/Due:64 - AGCM4:56 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI 58 // Mega/Due:66 - AGCM4:58 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO 44 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK 56 // Mega/Due:64 - AGCM4:56 #endif #if HAS_TMC_UART @@ -262,79 +275,233 @@ #define SDSS 53 #endif -////////////////////////// -// LCDs and Controllers // -////////////////////////// +// +// Průša i3 MK2 Multiplexer Support +// +#if HAS_PRUSA_MMU1 + #ifndef E_MUX0_PIN + #define E_MUX0_PIN AUX2_06 // Z_CS_PIN + #endif + #ifndef E_MUX1_PIN + #define E_MUX1_PIN AUX2_08 // E0_CS_PIN + #endif + #ifndef E_MUX2_PIN + #define E_MUX2_PIN AUX2_07 // E1_CS_PIN + #endif +#endif + +// +// AUX1 VCC GND D2 D1 +// 2 4 6 8 +// 1 3 5 7 +// VCC GND A3 A4 +// +#define AUX1_05 57 // (A3) +#define AUX1_06 2 +#define AUX1_07 58 // (A4) +#define AUX1_08 1 + +// +// AUX2 GND A9 D40 D42 A11 +// 2 4 6 8 10 +// 1 3 5 7 9 +// VCC A5 A10 D44 A12 +// +#define AUX2_03 59 // (A5) +#define AUX2_04 63 // (A9) +#define AUX2_05 64 // (A10) +#define AUX2_06 40 +#define AUX2_07 44 +#define AUX2_08 42 +#define AUX2_09 66 // (A12) +#define AUX2_10 65 // (A11) -#if HAS_WIRED_LCD +// +// AUX3 +// SCK MISO +// RST GND D52 D50 VCC +// 9 7 5 3 1 +// 10 8 6 4 2 +// NC 5V D53 D51 D49 +// MOSI +// +#define AUX3_02 49 +#define AUX3_03 50 +#define AUX3_04 51 +#define AUX3_05 52 +#define AUX3_06 53 + +// +// AUX4 VCC GND D32 D47 D45 D43 D41 D39 D37 D35 D33 D31 D29 D27 D25 D23 D17 D16 +// +#define AUX4_03 32 +#define AUX4_04 47 +#define AUX4_05 45 +#define AUX4_06 43 +#define AUX4_07 41 +#define AUX4_08 39 +#define AUX4_09 37 +#define AUX4_10 35 +#define AUX4_11 33 +#define AUX4_12 31 +#define AUX4_13 29 +#define AUX4_14 27 +#define AUX4_15 25 +#define AUX4_16 23 +#define AUX4_17 17 +#define AUX4_18 16 + +/** + * LCD adapters come in different variants. The socket keys can be + * on either side, and may be backwards on some boards / displays. + */ +#ifndef EXP1_08_PIN + + #define EXP1_03_PIN AUX4_17 + #define EXP1_04_PIN AUX4_18 + #define EXP1_05_PIN AUX4_16 + #define EXP1_06_PIN AUX4_15 + #define EXP1_07_PIN AUX4_14 + #define EXP1_08_PIN AUX4_13 + + #define EXP2_01_PIN AUX3_03 + #define EXP2_02_PIN AUX3_05 + #define EXP2_04_PIN AUX3_06 + #define EXP2_06_PIN AUX3_04 + #define EXP2_07_PIN AUX3_02 + + #if ENABLED(G3D_PANEL) + /** Gadgets3D Smart Adapter + * ------ ------ + * 4-11 | 1 2 | 4-12 (MISO) 3-03 | 1 2 | 3-05 (SCK) + * 4-17 | 3 4 | 4-18 4-10 | 3 4 | 3-06 + * 4-16 5 6 | 4-15 4-09 5 6 | 3-04 (MOSI) + * 4-14 | 7 8 | 4-13 3-02 | 7 8 | 4-07 + * (GND) 4-02 | 9 10 | 4-01 (5V) -- | 9 10 | -- + * ------ ------ + * EXP1 EXP2 + */ + #define EXP1_01_PIN AUX4_11 + #define EXP1_02_PIN AUX4_12 + + #define EXP2_03_PIN AUX4_10 + #define EXP2_05_PIN AUX4_09 + #define EXP2_08_PIN AUX4_07 + + #else + + /** Smart Adapter (c) RRD + * ------ ------ + * 4-09 | 1 2 | 4-10 (MISO) 3-03 | 1 2 | 3-05 (SCK) + * 4-17 | 3 4 | 4-18 4-12 | 3 4 | 3-06 + * 4-16 5 6 | 4-15 4-11 5 6 | 3-04 (MOSI) + * 4-14 | 7 8 | 4-13 3-02 | 7 8 | 4-07 + * (GND) 3-07 | 9 10 | 3-01 (5V) (GND) 3-07 | 9 10 | -- + * ------ ------ + * EXP1 EXP2 + */ + #define EXP1_01_PIN AUX4_09 + #define EXP1_02_PIN AUX4_10 + + #if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) + #define EXP2_03_PIN AUX4_11 + #define EXP2_05_PIN AUX4_12 + #define EXP2_08_PIN -1 // RESET + #else + #define EXP2_03_PIN AUX4_12 + #define EXP2_05_PIN AUX4_11 + #define EXP2_08_PIN AUX4_07 + #endif + + #endif + +#endif + +// +// LCD / Controller +// + +#ifdef LCD_PINS_DEFINED + + // LCD pins already defined by including header + +#elif HAS_WIRED_LCD + + //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 // // LCD Display output pins // #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - // TO TEST - //#define LCD_PINS_RS 49 // CS chip select /SS chip slave select - //#define LCD_PINS_ENABLE 51 // SID (MOSI) - //#define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS EXP2_07_PIN // CS chip select /SS chip slave select + #define LCD_PINS_EN EXP2_06_PIN // SID (MOSI) + #define LCD_PINS_D4 EXP2_02_PIN // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) - // TO TEST - //#define LCD_PINS_RS 40 - //#define LCD_PINS_ENABLE 42 - //#define LCD_PINS_D4 57 // Mega/Due:65 - AGCM4:57 - //#define LCD_PINS_D5 58 // Mega/Due:66 - AGCM4:58 - //#define LCD_PINS_D6 44 - //#define LCD_PINS_D7 56 // Mega/Due:64 - AGCM4:56 + #define LCD_PINS_RS AUX2_06 + #define LCD_PINS_EN AUX2_08 + #define LCD_PINS_D4 AUX2_10 + #define LCD_PINS_D5 AUX2_09 + #define LCD_PINS_D6 AUX2_07 + #define LCD_PINS_D7 AUX2_05 + + #elif ENABLED(TFTGLCD_PANEL_SPI) + + #define TFTGLCD_CS EXP2_05_PIN #else #if ENABLED(CR10_STOCKDISPLAY) - // TO TEST - //#define LCD_PINS_RS 27 - //#define LCD_PINS_ENABLE 29 - //#define LCD_PINS_D4 25 + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_EN EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN #if !IS_NEWPANEL - // TO TEST - //#define BEEPER_PIN 37 + #define BEEPER_PIN EXP1_01_PIN #endif #elif ENABLED(ZONESTAR_LCD) - // TO TEST - //#define LCD_PINS_RS 56 // Mega/Due:64 - AGCM4:56 - //#define LCD_PINS_ENABLE 44 - //#define LCD_PINS_D4 55 // Mega/Due:63 - AGCM4:55 - //#define LCD_PINS_D5 40 - //#define LCD_PINS_D6 42 - //#define LCD_PINS_D7 57 // Mega/Due:65 - AGCM4:57 + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! ZONESTAR_LCD on RAMPS requires wiring modifications. It plugs into AUX2 but GND and 5V need to be swapped. See 'pins_RAMPS.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif + + #define LCD_PINS_RS AUX2_05 + #define LCD_PINS_EN AUX2_07 + #define LCD_PINS_D4 AUX2_04 + #define LCD_PINS_D5 AUX2_06 + #define LCD_PINS_D6 AUX2_08 + #define LCD_PINS_D7 AUX2_10 + + #elif ENABLED(AZSMZ_12864) + + // TODO #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) - // TO TEST - //#define LCD_PINS_DC 25 // Set as output on init - //#define LCD_PINS_RS 27 // Pull low for 1s to init + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) + #define LCD_PINS_DC EXP1_06_PIN // Set as output on init + #define LCD_PINS_RS EXP1_07_PIN // Pull low for 1s to init // DOGM SPI LCD Support - //#define DOGLCD_CS 16 - //#define DOGLCD_MOSI 17 - //#define DOGLCD_SCK 23 - //#define DOGLCD_A0 LCD_PINS_DC + #define DOGLCD_A0 LCD_PINS_DC + #define DOGLCD_CS EXP1_04_PIN + #define DOGLCD_MOSI EXP1_03_PIN + #define DOGLCD_SCK EXP1_05_PIN #else - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN #endif - #define LCD_PINS_D7 29 + #define LCD_PINS_D7 EXP1_08_PIN #if !IS_NEWPANEL - #define BEEPER_PIN 33 + #define BEEPER_PIN EXP2_05_PIN #endif #endif @@ -343,13 +510,17 @@ // Buttons attached to a shift register // Not wired yet //#define SHIFT_CLK_PIN 38 - //#define SHIFT_LD_PIN 42 - //#define SHIFT_OUT_PIN 40 - //#define SHIFT_EN_PIN 17 + //#define SHIFT_LD_PIN AUX2_08 + //#define SHIFT_OUT_PIN AUX2_06 + //#define SHIFT_EN_PIN EXP1_03_PIN #endif #endif + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + // // LCD Display input pins // @@ -357,215 +528,270 @@ #if IS_RRD_SC - #define BEEPER_PIN 37 + #define BEEPER_PIN EXP1_01_PIN #if ENABLED(CR10_STOCKDISPLAY) - // TO TEST - //#define BTN_EN1 17 - //#define BTN_EN2 23 + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN #else - #define BTN_EN1 31 - #define BTN_EN2 33 - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder - #endif + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #endif - #define BTN_ENC 35 + #define BTN_ENC EXP1_02_PIN #ifndef SD_DETECT_PIN - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN EXP2_07_PIN + #endif + #ifndef KILL_PIN + #define KILL_PIN EXP2_08_PIN #endif - #define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) - //#define LCD_BACKLIGHT_PIN 39 // TO TEST + #define LCD_BACKLIGHT_PIN AUX4_08 // Probably a slightly different adapter from RRD SC #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - // TO TEST - //#define BTN_EN1 56 // Mega/Due:64 - AGCM4:56 - //#define BTN_EN2 72 // Mega/Due:59 - AGCM4:72 - //#define BTN_ENC 55 - //#define SD_DETECT_PIN 42 + #define BTN_EN1 AUX2_05 + #define BTN_EN2 AUX2_03 + #define BTN_ENC AUX2_04 + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN AUX2_08 + #endif #elif ENABLED(LCD_I2C_PANELOLU2) - // TO TEST - //#define BTN_EN1 47 - //#define BTN_EN2 43 - //#define BTN_ENC 32 - //#define LCD_SDSS SDSS - //#define KILL_PIN 41 + #define BTN_EN1 AUX4_04 + #define BTN_EN2 AUX4_06 + #define BTN_ENC AUX4_03 + #define LCD_SDSS SDSS + #define KILL_PIN AUX4_07 #elif ENABLED(LCD_I2C_VIKI) - // TO TEST - //#define BTN_EN1 40 // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - //#define BTN_EN2 42 - //#define BTN_ENC -1 + #define BTN_EN1 AUX2_06 // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains AUX2-06 and AUX2-08. + #define BTN_EN2 AUX2_08 + #define BTN_ENC -1 - //#define LCD_SDSS SDSS - //#define SD_DETECT_PIN 49 - - #elif EITHER(VIKI2, miniVIKI) + #define LCD_SDSS SDSS + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #endif - // TO TEST - //#define DOGLCD_CS 45 - //#define DOGLCD_A0 44 + #elif ANY(VIKI2, miniVIKI) - //#define BEEPER_PIN 33 - //#define STAT_LED_RED_PIN 32 - //#define STAT_LED_BLUE_PIN 35 + #define DOGLCD_CS AUX4_05 + #define DOGLCD_A0 AUX2_07 + #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 - //#define BTN_EN1 22 - //#define BTN_EN2 7 - //#define BTN_ENC 39 + #define BEEPER_PIN EXP2_05_PIN + #define STAT_LED_RED_PIN AUX4_03 + #define STAT_LED_BLUE_PIN EXP1_02_PIN - //#define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board - //#define KILL_PIN 31 + #define BTN_EN1 22 + #define BTN_EN2 7 + #define BTN_ENC AUX4_08 - //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board + #endif + #define KILL_PIN EXP2_03_PIN #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - // TO TEST - //#define DOGLCD_CS 29 - //#define DOGLCD_A0 27 + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN - //#define BEEPER_PIN 23 - //#define LCD_BACKLIGHT_PIN 33 + #define BEEPER_PIN EXP1_05_PIN + #define LCD_BACKLIGHT_PIN EXP2_05_PIN - //#define BTN_EN1 35 - //#define BTN_EN2 37 - //#define BTN_ENC 31 + #define BTN_EN1 EXP1_02_PIN + #define BTN_EN2 EXP1_01_PIN + #define BTN_ENC EXP2_03_PIN - //#define LCD_SDSS SDSS - //#define SD_DETECT_PIN 49 - //#define KILL_PIN 41 + #define LCD_SDSS SDSS + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #endif + #define KILL_PIN EXP2_08_PIN - #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) + #elif ANY(MKS_MINI_12864, FYSETC_MINI_12864) - // TO TEST - //#define BEEPER_PIN 37 - //#define BTN_ENC 35 - //#define SD_DETECT_PIN 49 + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #endif - //#ifndef KILL_PIN - // #define KILL_PIN 41 - //#endif + #ifndef KILL_PIN + #define KILL_PIN EXP2_08_PIN + #endif #if ENABLED(MKS_MINI_12864) - // TO TEST - //#define DOGLCD_A0 27 - //#define DOGLCD_CS 25 + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN // not connected to a pin - //#define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) - - //#define BTN_EN1 31 - //#define BTN_EN2 33 + #define LCD_BACKLIGHT_PIN -1 // 65 (MKS mini12864 can't adjust backlight by software!) - //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #elif ENABLED(FYSETC_MINI_12864) - // From https://wiki.fysetc.com/Mini12864_Panel/?fbclid=IwAR1FyjuNdVOOy9_xzky3qqo_WeM5h-4gpRnnWhQr_O1Ef3h0AFnFXmCehK8 + // From https://wiki.fysetc.com/Mini12864_Panel/ - // TO TEST - //#define DOGLCD_A0 16 - //#define DOGLCD_CS 17 + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_03_PIN - //#define BTN_EN1 33 - //#define BTN_EN2 31 + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN //#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 23 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - // TO TEST - //#define RGB_LED_R_PIN 25 + #define RGB_LED_R_PIN EXP1_06_PIN #endif #ifndef RGB_LED_G_PIN - // TO TEST - //#define RGB_LED_G_PIN 27 + #define RGB_LED_G_PIN EXP1_07_PIN #endif #ifndef RGB_LED_B_PIN - // TO TEST - //#define RGB_LED_B_PIN 29 + #define RGB_LED_B_PIN EXP1_08_PIN #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - // TO TEST - //#define NEOPIXEL_PIN 25 + #define NEOPIXEL_PIN EXP1_06_PIN #endif #endif #elif ENABLED(MINIPANEL) - // TO TEST - //#define BEEPER_PIN 42 - // not connected to a pin - //#define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) + #define BEEPER_PIN AUX2_08 + #define LCD_BACKLIGHT_PIN AUX2_10 - //#define DOGLCD_A0 44 - //#define DOGLCD_CS 58 // Mega/Due:66 - AGCM4:58 + #define DOGLCD_A0 AUX2_07 + #define DOGLCD_CS AUX2_09 - //#define BTN_EN1 40 - //#define BTN_EN2 55 // Mega/Due:63 - AGCM4:55 - //#define BTN_ENC 72 // Mega/Due:59 - AGCM4:72 + #define BTN_EN1 AUX2_06 + #define BTN_EN2 AUX2_04 + #define BTN_ENC AUX2_03 - //#define SD_DETECT_PIN 49 - //#define KILL_PIN 56 // Mega/Due:64 - AGCM4:56 - - //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN AUX3_02 + #endif + #define KILL_PIN AUX2_05 #elif ENABLED(ZONESTAR_LCD) - // TO TEST - //#define ADC_KEYPAD_PIN 12 + #define ADC_KEYPAD_PIN 12 #elif ENABLED(AZSMZ_12864) - // TO TEST + // TODO - #else + #elif ENABLED(G3D_PANEL) - // Beeper on AUX-4 - //#define BEEPER_PIN 33 - - // Buttons are directly attached to AUX-2 - #if IS_RRW_KEYPAD - // TO TEST - //#define SHIFT_OUT_PIN 40 - //#define SHIFT_CLK_PIN 44 - //#define SHIFT_LD_PIN 42 - //#define BTN_EN1 56 // Mega/Due:64 - AGCM4:56 - //#define BTN_EN2 72 // Mega/Due:59 - AGCM4:72 - //#define BTN_ENC 55 // Mega/Due:63 - AGCM4:55 - #elif ENABLED(PANEL_ONE) - // TO TEST - //#define BTN_EN1 72 // AUX2 PIN 3 (Mega/Due:59 - AGCM4:72) - //#define BTN_EN2 55 // AUX2 PIN 4 (Mega/Due:63 - AGCM4:55) - //#define BTN_ENC 49 // AUX3 PIN 7 - #else - // TO TEST - //#define BTN_EN1 37 - //#define BTN_EN2 35 - //#define BTN_ENC 31 + #define BEEPER_PIN EXP1_01_PIN + + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #endif + #define KILL_PIN EXP2_08_PIN + + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN + #define BTN_ENC EXP1_02_PIN + + #elif IS_TFTGLCD_PANEL + + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif - #if ENABLED(G3D_PANEL) - // TO TEST - //#define SD_DETECT_PIN 49 - //#define KILL_PIN 41 + #else + + #define BEEPER_PIN EXP2_05_PIN + + #if ENABLED(PANEL_ONE) // Buttons connect directly to AUX-2 + #define BTN_EN1 AUX2_03 + #define BTN_EN2 AUX2_04 + #define BTN_ENC AUX3_02 + #else + #define BTN_EN1 EXP1_01_PIN + #define BTN_EN2 EXP1_02_PIN + #define BTN_ENC EXP2_03_PIN #endif #endif #endif // IS_NEWPANEL -#endif // HAS_WIRED_LCD +#endif // HAS_WIRED_LCD && !LCD_PINS_DEFINED + +#if IS_RRW_KEYPAD && !HAS_ADC_BUTTONS + #define SHIFT_OUT_PIN AUX2_06 + #define SHIFT_CLK_PIN AUX2_07 + #define SHIFT_LD_PIN AUX2_08 + #ifndef BTN_EN1 + #define BTN_EN1 AUX2_05 + #endif + #ifndef BTN_EN2 + #define BTN_EN2 AUX2_03 + #endif + #ifndef BTN_ENC + #define BTN_ENC AUX2_04 + #endif +#endif + +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) + + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_RAMPS.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #endif + + /** + * FYSETC TFT-81050 display pinout + * + * Board Display + * ------ ------ + * (MISO) 50 | 1 2 | 52 (SCK) 5V |10 9 | GND + * (LCD_CS) 33 | 3 4 | 53 (SD_CS) RESET | 8 7 | (SD_DET) + * 31 5 6 | 51 (MOSI) (MOSI) 6 5 | (LCD_CS) + * (SD_DET) 49 | 7 8 | RESET (SD_CS) | 4 3 | (MOD_RESET) + * GND | 9 10 | -- (SCK) | 2 1 | (MISO) + * ------ ------ + * EXP2 EXP1 + * + * Needs custom cable: + * + * Board Adapter Display + * ---------------------------------- + * EXP2-1 <--diode--- EXP1-1 MISO + * EXP2-2 ----------- EXP1-2 SCK + * EXP2-4 ----------- EXP1-3 MOD_RST + * EXP2-4 ----------- EXP1-4 SD_CS + * EXP2-3 ----------- EXP1-5 LCD_CS + * EXP2-6 ----------- EXP1-6 MOSI + * EXP2-7 ----------- EXP1-7 SD DET + * EXP2-8 ----------- EXP1-8 RESET + * EXP2-1 ----------- EXP1-9 MISO->GND + * EXP1-10 ---------- EXP1-10 5V + * + * NOTE: The MISO pin should not get a 5V signal. + * To fix, insert a 1N4148 diode in the MISO line. + */ + + #define BEEPER_PIN EXP1_01_PIN + + #ifndef SD_DETECT_PIN + #define SD_DETECT_PIN EXP2_07_PIN + #endif + + #define CLCD_MOD_RESET EXP2_05_PIN + #define CLCD_SPI_CS EXP2_03_PIN + +#endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 diff --git a/Marlin/src/pins/sanguino/env_validate.h b/Marlin/src/pins/sanguino/env_validate.h index d229b6f102e4..bd7947f469a5 100644 --- a/Marlin/src/pins/sanguino/env_validate.h +++ b/Marlin/src/pins/sanguino/env_validate.h @@ -19,7 +19,8 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if ENABLED(ALLOW_MEGA644) #if NOT_TARGET(__AVR_ATmega644__, __AVR_ATmega644P__, __AVR_ATmega1284P__) @@ -40,3 +41,5 @@ #undef ALLOW_MEGA644 #undef ALLOW_MEGA644P #undef REQUIRE_MEGA644P + +#endif diff --git a/Marlin/src/pins/sanguino/pins_ANET_10.h b/Marlin/src/pins/sanguino/pins_ANET_10.h index f6816bfb953c..b0780d59288b 100644 --- a/Marlin/src/pins/sanguino/pins_ANET_10.h +++ b/Marlin/src/pins/sanguino/pins_ANET_10.h @@ -148,8 +148,8 @@ #define HEATER_0_PIN 13 // (extruder) #define HEATER_BED_PIN 12 // (bed) -#ifndef FAN_PIN - #define FAN_PIN 4 +#ifndef FAN0_PIN + #define FAN0_PIN 4 #endif // @@ -158,66 +158,124 @@ #define SDSS 31 #define LED_PIN -1 +/** + * Connector pinouts + * + * ------ ------ ---- + * (SDA) 17 | 1 2 | 30 (A1) 3V3 | 1 2 | 4 (SS) J3_RX |1 2| J3_TX + * (SCL) 16 | 3 4 | 29 (A2) GND | 3 4 | RESET (TXO) 9 |3 4| 8 (RX0) + * 11 | 5 6 28 (A3) (MOSI) 5 | 5 6 7 (SCK) USB_RX |5 6| USB_TX + * 10 | 7 8 | 27 (A4) 5V | 7 8 | 6 (MISO) ---- + * 5V | 9 10 | GND J3_RX | 9 10 | J3_TX USB_BLE + * ------ ------ + * LCD J3 + */ +#define EXP1_01_PIN 17 // BEEPER / ENC +#define EXP1_02_PIN 30 // LCD_D4 / SERVO +#define EXP1_03_PIN 16 // ENC / LCD_EN +#define EXP1_04_PIN 29 // SERVO / LCD_RS +#define EXP1_05_PIN 11 // EN1 / LCD_D4 +#define EXP1_06_PIN 28 // LCD_EN / EN1 +#define EXP1_07_PIN 10 // EN2 +#define EXP1_08_PIN 27 // LCD_RS / BEEPER + /** * LCD / Controller * * Only the following displays are supported: * ZONESTAR_LCD - * ANET_FULL_GRAPHICS_LCD(_ALT_WIRING)? + * ANET_FULL_GRAPHICS_LCD + * ANET_FULL_GRAPHICS_LCD_ALT_WIRING * REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER */ #if HAS_WIRED_LCD - #define LCD_SDSS 28 + #define LCD_SDSS EXP1_06_PIN #if HAS_ADC_BUTTONS - #define SERVO0_PIN 27 // free for BLTouch/3D-Touch - #define LCD_PINS_RS 28 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 10 - #define LCD_PINS_D5 11 - #define LCD_PINS_D6 16 - #define LCD_PINS_D7 17 + #define SERVO0_PIN EXP1_08_PIN // free for BLTouch/3D-Touch + #define LCD_PINS_RS EXP1_06_PIN + #define LCD_PINS_EN EXP1_04_PIN + #define LCD_PINS_D4 EXP1_07_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_03_PIN + #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN 1 #elif IS_RRD_FG_SC // Pin definitions for the Anet A6 Full Graphics display and the RepRapDiscount Full Graphics - // display using an adapter board // https://go.aisler.net/benlye/anet-lcd-adapter/pcb + // display using an adapter board. See https://go.aisler.net/benlye/anet-lcd-adapter/pcb // See below for alternative pin definitions for use with https://www.thingiverse.com/thing:2103748 #if ENABLED(ANET_FULL_GRAPHICS_LCD_ALT_WIRING) - #define SERVO0_PIN 30 - #define BEEPER_PIN 27 - #define LCD_PINS_RS 29 - #define LCD_PINS_ENABLE 16 - #define LCD_PINS_D4 11 - #define BTN_EN1 28 - #define BTN_EN2 10 - #define BTN_ENC 17 + + /** + * ANET_FULL_GRAPHICS_LCD_ALT_WIRING pinout + * + * ------ + * GND | 1 2 | 5V + * BEEPER | 3 4 | BTN_EN2 + * BTN_EN1 5 6 | LCD_D4 + * LCD_RS | 7 8 | LCD_EN + * SERVO0 | 9 10 | BTN_ENC + * ------ + * LCD + */ + #define SERVO0_PIN EXP1_02_PIN + + #define BEEPER_PIN EXP1_08_PIN + + #define BTN_ENC EXP1_01_PIN + #define BTN_EN1 EXP1_06_PIN + #define BTN_EN2 EXP1_07_PIN + + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define BOARD_ST7920_DELAY_1 250 #define BOARD_ST7920_DELAY_2 250 #define BOARD_ST7920_DELAY_3 250 + #else - #define SERVO0_PIN 29 // free for BLTouch/3D-Touch - #define BEEPER_PIN 17 - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 28 - #define LCD_PINS_D4 30 - #define BTN_EN1 11 - #define BTN_EN2 10 - #define BTN_ENC 16 + + /** + * ANET_FULL_GRAPHICS_LCD pinouts + * + * ------ ------ + * GND | 1 2 | 5V - | 1 2 | - + * LCD_RS | 3 4 | BTN_EN2 - | 3 4 | 5V + * LCD_EN 5 6 | BTN_EN1 - 5 6 | - + * SERVO0 | 7 8 | BTN_ENC RESET | 7 8 | GND + * LCD_D4 | 9 10 | BEEPER_PIN - | 9 10 | 3V3 + * ------ ------ + * LCD J3 + */ + #define SERVO0_PIN EXP1_04_PIN // Free for BLTouch/3D-Touch + + #define BEEPER_PIN EXP1_01_PIN + + #define BTN_ENC EXP1_03_PIN + #define BTN_EN1 EXP1_05_PIN + #define BTN_EN2 EXP1_07_PIN + + #define LCD_PINS_RS EXP1_08_PIN + #define LCD_PINS_EN EXP1_06_PIN + #define LCD_PINS_D4 EXP1_02_PIN + #define BOARD_ST7920_DELAY_1 125 #define BOARD_ST7920_DELAY_2 63 #define BOARD_ST7920_DELAY_3 125 + #endif #endif #else - #define SERVO0_PIN 27 + #define SERVO0_PIN EXP1_08_PIN #endif #ifndef FIL_RUNOUT_PIN @@ -233,11 +291,11 @@ * published by oderwat on Thingiverse at https://www.thingiverse.com/thing:2103748. * * Using that adapter requires changing the pin definition as follows: - * #define SERVO0_PIN 27 // free for BLTouch/3D-Touch - * #define BEEPER_PIN 28 - * #define LCD_PINS_RS 30 - * #define LCD_PINS_ENABLE 29 - * #define LCD_PINS_D4 17 + * #define SERVO0_PIN 27 // free for BLTouch/3D-Touch + * #define BEEPER_PIN 28 + * #define LCD_PINS_RS 30 + * #define LCD_PINS_EN 29 + * #define LCD_PINS_D4 17 * * The BLTouch pin becomes LCD:3 */ @@ -247,32 +305,32 @@ * ===================== LCD PINOUTS ================================== * ==================================================================== * - * Anet V1.0 controller | ZONESTAR_LCD | ANET_FULL_ | RepRapDiscount Full | Thingiverse RepRap wiring - * physical logical alt | | GRAPHICS_LCD | Graphics Display Wiring | https://www.thingiverse - * pin pin functions | | | | .com/thing:2103748 - *------------------------------------------------------------------------------------------------------------------------ - * ANET-J3.1 8 *** | N/A | J3_TX *** | | - * ANET-J3.2 9 *** | N/A | J3_RX *** | | - * ANET-J3.3 6 MISO | N/A | MISO *** | EXP2.1 MISO | EXP2.1 MISO - * ANET-J3.4 +5V | N/A | +5V | | - * ANET-J3.5 7 SCK | N/A | SCK *** | EXP2.2 SCK | EXP2.2 SCK - * ANET-J3.6 5 MOSI | N/A | MOSI *** | EXP2.6 MOSI | EXP2.6 MOSI - * ANET-J3.7 !RESET | N/A | button | EXP2.8 panel button | EXP2.8 panel button - * ANET-J3.8 GND | N/A | GND | EXP2.9 GND | EXP2.9 GND - * ANET-J3.9 4 Don't use | N/A | N/C | | - * ANET-J3.10 +3.3V | N/A | +3.3V *** | | - * | | | | - * | | | | - * ANET-LCD.1 GND | GND | GND | EXP1.9 GND | EXP1.9 GND - * ANET-LCD.2 +5V | +5V | +5V | EXP1.10 +5V | EXP1.10 +5V - * ANET-LCD.3 27 A4 | N/C * | LCD_PINS_RS | EXP1.4 LCD_PINS_RS | EXP2.4 SDSS or N/C * - * ANET-LCD.4 10 | LCD_PINS_D4 | BTN_EN2 | EXP2.3 BTN_EN2 | EXP2.3 BTN_EN2 - * ANET-LCD.5 28 A3 | LCD_PINS_RS | LCD_PINS_ENABLE | EXP1.3 LCD_PINS_ENABLE | EXP1.1 BEEPER_PIN - * ANET-LCD.6 11 | LCD_PINS_D5 | BTN_EN1 | EXP2.5 BTN_EN1 | EXP2.5 BTN_EN1 - * ANET-LCD.7 29 A2 | LCD_PINS_ENABLE | N/C * | EXP2.4 SDSS or N/C * | EXP1.3 LCD_PINS_ENABLE - * ANET-LCD.8 16 SCL | LCD_PINS_D6 | BTN_ENC | EXP1.2 BTN_ENC | EXP1.2 BTN_ENC - * ANET-LCD.9 30 A1 | ADC_KEYPAD_PIN ** | LCD_PINS_D4 | EXP1.5 LCD_PINS_D4 | EXP1.4 LCD_PINS_RS - * ANET-LCD.10 17 SDA | LCD_PINS_D7 | BEEPER_PIN | EXP1.1 BEEPER_PIN | EXP1.5 LCD_PINS_D4 + * Anet V1.0 controller | ZONESTAR_LCD | ANET_FULL_ | RepRapDiscount Full | Thingiverse RepRap wiring + * physical logical alt | | GRAPHICS_LCD | Graphics Display Wiring | https://www.thingiverse + * pin pin functions | | | | .com/thing:2103748 + *-------------------------------------------------------------------------------------------------------------------- + * ANET-J3.1 8 *** | N/A | J3_TX *** | | + * ANET-J3.2 9 *** | N/A | J3_RX *** | | + * ANET-J3.3 6 MISO | N/A | MISO *** | EXP2.1 MISO | EXP2.1 MISO + * ANET-J3.4 +5V | N/A | +5V | | + * ANET-J3.5 7 SCK | N/A | SCK *** | EXP2.2 SCK | EXP2.2 SCK + * ANET-J3.6 5 MOSI | N/A | MOSI *** | EXP2.6 MOSI | EXP2.6 MOSI + * ANET-J3.7 !RESET | N/A | button | EXP2.8 panel button | EXP2.8 panel button + * ANET-J3.8 GND | N/A | GND | EXP2.9 GND | EXP2.9 GND + * ANET-J3.9 4 Don't use | N/A | N/C | | + * ANET-J3.10 +3.3V | N/A | +3.3V *** | | + * | | | | + * | | | | + * ANET-LCD.1 GND | GND | GND | EXP1.9 GND | EXP1.9 GND + * ANET-LCD.2 +5V | +5V | +5V | EXP1.10 +5V | EXP1.10 +5V + * ANET-LCD.3 27 A4 | N/C * | LCD_PINS_RS | EXP1.4 LCD_PINS_RS | EXP2.4 SDSS or N/C * + * ANET-LCD.4 10 | LCD_PINS_D4 | BTN_EN2 | EXP2.3 BTN_EN2 | EXP2.3 BTN_EN2 + * ANET-LCD.5 28 A3 | LCD_PINS_RS | LCD_PINS_EN | EXP1.3 LCD_PINS_EN | EXP1.1 BEEPER_PIN + * ANET-LCD.6 11 | LCD_PINS_D5 | BTN_EN1 | EXP2.5 BTN_EN1 | EXP2.5 BTN_EN1 + * ANET-LCD.7 29 A2 | LCD_PINS_EN | N/C * | EXP2.4 SDSS or N/C * | EXP1.3 LCD_PINS_EN + * ANET-LCD.8 16 SCL | LCD_PINS_D6 | BTN_ENC | EXP1.2 BTN_ENC | EXP1.2 BTN_ENC + * ANET-LCD.9 30 A1 | ADC_KEYPAD_PIN ** | LCD_PINS_D4 | EXP1.5 LCD_PINS_D4 | EXP1.4 LCD_PINS_RS + * ANET-LCD.10 17 SDA | LCD_PINS_D7 | BEEPER_PIN | EXP1.1 BEEPER_PIN | EXP1.5 LCD_PINS_D4 * * N/C * - if not connected to the LCD can be used for BLTouch servo input * ** - analog pin -WITHOUT a pullup @@ -284,7 +342,7 @@ * physical pin function * EXP1.1 BEEPER * EXP1.2 BTN_ENC - * EXP1.3 LCD_PINS_ENABLE + * EXP1.3 LCD_PINS_EN * EXP1.4 LCD_PINS_RS * EXP1.5 LCD_PINS_D4 * EXP1.6 LCD_PINS_D5 (not used) diff --git a/Marlin/src/pins/sanguino/pins_AZTEEG_X1.h b/Marlin/src/pins/sanguino/pins_AZTEEG_X1.h index 76d53c6021db..1cbafab432c4 100644 --- a/Marlin/src/pins/sanguino/pins_AZTEEG_X1.h +++ b/Marlin/src/pins/sanguino/pins_AZTEEG_X1.h @@ -29,6 +29,6 @@ #define BOARD_INFO_NAME "Azteeg X1" -#define FAN_PIN 4 +#define FAN0_PIN 4 #include "pins_SANGUINOLOLU_12.h" // ... SANGUINOLOLU_11 diff --git a/Marlin/src/pins/sanguino/pins_GEN6.h b/Marlin/src/pins/sanguino/pins_GEN6.h index 75138845f402..4a6136e0810a 100644 --- a/Marlin/src/pins/sanguino/pins_GEN6.h +++ b/Marlin/src/pins/sanguino/pins_GEN6.h @@ -117,6 +117,8 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 5 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM -#define SPINDLE_DIR_PIN 6 +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 5 // Pullup or pulldown! + #define SPINDLE_DIR_PIN 6 +#endif diff --git a/Marlin/src/pins/sanguino/pins_GEN6_DELUXE.h b/Marlin/src/pins/sanguino/pins_GEN6_DELUXE.h index 9c635706202c..476375203c6b 100644 --- a/Marlin/src/pins/sanguino/pins_GEN6_DELUXE.h +++ b/Marlin/src/pins/sanguino/pins_GEN6_DELUXE.h @@ -48,7 +48,6 @@ * Once installed select the SANGUINO board and then select the CPU. */ - #define BOARD_INFO_NAME "Gen6 Deluxe" #include "pins_GEN6.h" diff --git a/Marlin/src/pins/sanguino/pins_GEN7_12.h b/Marlin/src/pins/sanguino/pins_GEN7_12.h index ade59fd80794..0bf65c37cd38 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_12.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_12.h @@ -117,8 +117,8 @@ #define HEATER_0_PIN 4 #define HEATER_BED_PIN 3 -#if !defined(FAN_PIN) && GEN7_VERSION < 13 // Gen7 v1.3 removed the fan pin - #define FAN_PIN 31 +#if !defined(FAN0_PIN) && GEN7_VERSION < 13 // Gen7 v1.3 removed the fan pin + #define FAN0_PIN 31 #endif // diff --git a/Marlin/src/pins/sanguino/pins_GEN7_14.h b/Marlin/src/pins/sanguino/pins_GEN7_14.h index 698bd066066a..db80c45eeefe 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_14.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_14.h @@ -118,6 +118,8 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 20 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM -#define SPINDLE_DIR_PIN 21 +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 20 // Pullup or pulldown! + #define SPINDLE_DIR_PIN 21 +#endif diff --git a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h index 6d7678e6e3d2..154e26725f20 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h @@ -116,7 +116,7 @@ // 4bit LCD Support #define LCD_PINS_RS 18 -#define LCD_PINS_ENABLE 17 +#define LCD_PINS_EN 17 #define LCD_PINS_D4 16 #define LCD_PINS_D5 15 #define LCD_PINS_D6 13 @@ -134,6 +134,8 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 5 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM -#define SPINDLE_DIR_PIN 6 +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 5 // Pullup or pulldown! + #define SPINDLE_DIR_PIN 6 +#endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI.h b/Marlin/src/pins/sanguino/pins_MELZI.h index be1b7934c81f..a0c7050a9111 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI.h +++ b/Marlin/src/pins/sanguino/pins_MELZI.h @@ -33,8 +33,8 @@ #define IS_MELZI 1 -#ifndef FAN_PIN - #define FAN_PIN 4 +#ifndef FAN0_PIN + #define FAN0_PIN 4 #endif // Alter timing for graphical display diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index a61692c9f1fa..1dd261fecab3 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -38,115 +38,116 @@ #define BOARD_INFO_NAME "Melzi (Creality)" -// Alter timing for graphical display -#if IS_U8GLIB_ST7920 - #define BOARD_ST7920_DELAY_1 125 - #define BOARD_ST7920_DELAY_2 125 - #define BOARD_ST7920_DELAY_3 125 -#endif +/** ------ + * 27 | 1 2 | 16 + * 11 | 3 4 | RESET + * 10 5 6 | 30 + * 28 | 7 8 | 17 + * GND | 9 10 | 5V + * ------ + * EXP1 + */ +#define EXP1_01_PIN 27 // BEEP +#define EXP1_02_PIN 16 // ENC +#define EXP1_03_PIN 11 // EN1 +#define EXP1_04_PIN -1 // RESET +#define EXP1_05_PIN 10 // EN2 +#define EXP1_06_PIN 30 // A0 / ST9720 CLK +#define EXP1_07_PIN 28 // CS / ST9720 CS +#define EXP1_08_PIN 17 // ST9720 DAT // // LCD / Controller // + #if ANY(MKS_MINI_12864, CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) - #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) - #define LCD_PINS_RS 28 // ST9720 CS - #define LCD_PINS_ENABLE 17 // ST9720 DAT - #define LCD_PINS_D4 30 // ST9720 CLK + #if ANY(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) + #define LCD_PINS_RS EXP1_07_PIN // ST9720 CS + #define LCD_PINS_EN EXP1_08_PIN // ST9720 DAT + #define LCD_PINS_D4 EXP1_06_PIN // ST9720 CLK #endif - #if EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) - #define DOGLCD_CS 28 - #define DOGLCD_A0 30 + #if ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #define DOGLCD_CS EXP1_07_PIN + #define DOGLCD_A0 EXP1_06_PIN #endif #define LCD_SDSS 31 // Controller's SD card - #define BTN_ENC 16 - #define BTN_EN1 11 - #define BTN_EN2 10 - #define BEEPER_PIN 27 + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + #define BEEPER_PIN EXP1_01_PIN #define LCD_PINS_DEFINED #endif +// Alter timing for graphical display +#if IS_U8GLIB_ST7920 + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 125 + #define BOARD_ST7920_DELAY_3 125 +#endif + #include "pins_MELZI.h" // ... SANGUINOLOLU_12 ... SANGUINOLOLU_11 #if ENABLED(BLTOUCH) #ifndef SERVO0_PIN - #define SERVO0_PIN 27 - #endif - #if SERVO0_PIN == BEEPER_PIN - #undef BEEPER_PIN + #define SERVO0_PIN EXP1_01_PIN #endif #elif HAS_FILAMENT_SENSOR #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 27 - #endif - #if FIL_RUNOUT_PIN == BEEPER_PIN - #undef BEEPER_PIN + #define FIL_RUNOUT_PIN EXP1_01_PIN #endif #endif - -#if ENABLED(MINIPANEL) - #undef DOGLCD_CS - #define DOGLCD_CS LCD_PINS_RS +#if PIN_EXISTS(BEEPER) && (SERVO0_PIN == BEEPER_PIN || FIL_RUNOUT_PIN == BEEPER_PIN) + #undef BEEPER_PIN + #define BEEPER_PIN -1 #endif /** - PIN: 0 Port: B0 E0_DIR_PIN protected - PIN: 1 Port: B1 E0_STEP_PIN protected - PIN: 2 Port: B2 Z_DIR_PIN protected - PIN: 3 Port: B3 Z_STEP_PIN protected - PIN: 4 Port: B4 AVR_SS_PIN protected - . FAN_PIN protected - . SD_SS_PIN protected - PIN: 5 Port: B5 AVR_MOSI_PIN Output = 1 - . SD_MOSI_PIN Output = 1 - PIN: 6 Port: B6 AVR_MISO_PIN Input = 0 TIMER3A PWM: 0 WGM: 1 COM3A: 0 CS: 3 TCCR3A: 1 TCCR3B: 3 TIMSK3: 0 - . SD_MISO_PIN Input = 0 - PIN: 7 Port: B7 AVR_SCK_PIN Output = 0 TIMER3B PWM: 0 WGM: 1 COM3B: 0 CS: 3 TCCR3A: 1 TCCR3B: 3 TIMSK3: 0 - . SD_SCK_PIN Output = 0 - PIN: 8 Port: D0 RXD Input = 1 - PIN: 9 Port: D1 TXD Input = 0 - PIN: 10 Port: D2 BTN_EN2 Input = 1 - PIN: 11 Port: D3 BTN_EN1 Input = 1 - PIN: 12 Port: D4 HEATER_BED_PIN protected - PIN: 13 Port: D5 HEATER_0_PIN protected - PIN: 14 Port: D6 E0_ENABLE_PIN protected - . X_ENABLE_PIN protected - . Y_ENABLE_PIN protected - PIN: 15 Port: D7 X_STEP_PIN protected - PIN: 16 Port: C0 BTN_ENC Input = 1 - . SCL Input = 1 - PIN: 17 Port: C1 LCD_PINS_ENABLE Output = 0 - . SDA Output = 0 - PIN: 18 Port: C2 X_MIN_PIN protected - . X_STOP_PIN protected - PIN: 19 Port: C3 Y_MIN_PIN protected - . Y_STOP_PIN protected - PIN: 20 Port: C4 Z_MIN_PIN protected - . Z_STOP_PIN protected - PIN: 21 Port: C5 X_DIR_PIN protected - PIN: 22 Port: C6 Y_STEP_PIN protected - PIN: 23 Port: C7 Y_DIR_PIN protected - PIN: 24 Port: A7 TEMP_0_PIN protected - PIN: 25 Port: A6 TEMP_BED_PIN protected - PIN: 26 Port: A5 Z_ENABLE_PIN protected - PIN: 27 Port: A4 BEEPER_PIN Output = 0 - PIN: 28 Port: A3 LCD_PINS_RS Output = 0 - PIN: 29 Port: A2 Input = 0 - PIN: 30 Port: A1 LCD_PINS_D4 Output = 1 - PIN: 31 Port: A0 SDSS Output = 1 + PIN: 0 Port: B0 E0_DIR_PIN protected + PIN: 1 Port: B1 E0_STEP_PIN protected + PIN: 2 Port: B2 Z_DIR_PIN protected + PIN: 3 Port: B3 Z_STEP_PIN protected + PIN: 4 Port: B4 AVR_SS_PIN protected + . FAN0_PIN protected + . SD_SS_PIN protected + PIN: 5 Port: B5 AVR_MOSI_PIN Output = 1 + . SD_MOSI_PIN Output = 1 + PIN: 6 Port: B6 AVR_MISO_PIN Input = 0 TIMER3A PWM: 0 WGM: 1 COM3A: 0 CS: 3 TCCR3A: 1 TCCR3B: 3 TIMSK3: 0 + . SD_MISO_PIN Input = 0 + PIN: 7 Port: B7 AVR_SCK_PIN Output = 0 TIMER3B PWM: 0 WGM: 1 COM3B: 0 CS: 3 TCCR3A: 1 TCCR3B: 3 TIMSK3: 0 + . SD_SCK_PIN Output = 0 + PIN: 8 Port: D0 RXD Input = 1 + PIN: 9 Port: D1 TXD Input = 0 + PIN: 10 Port: D2 BTN_EN2 Input = 1 + PIN: 11 Port: D3 BTN_EN1 Input = 1 + PIN: 12 Port: D4 HEATER_BED_PIN protected + PIN: 13 Port: D5 HEATER_0_PIN protected + PIN: 14 Port: D6 E0_ENABLE_PIN protected + . X_ENABLE_PIN protected + . Y_ENABLE_PIN protected + PIN: 15 Port: D7 X_STEP_PIN protected + PIN: 16 Port: C0 BTN_ENC Input = 1 + . SCL Input = 1 + PIN: 17 Port: C1 LCD_PINS_EN Output = 0 + . SDA Output = 0 + PIN: 18 Port: C2 X_MIN_PIN protected + . X_STOP_PIN protected + PIN: 19 Port: C3 Y_MIN_PIN protected + . Y_STOP_PIN protected + PIN: 20 Port: C4 Z_MIN_PIN protected + . Z_STOP_PIN protected + PIN: 21 Port: C5 X_DIR_PIN protected + PIN: 22 Port: C6 Y_STEP_PIN protected + PIN: 23 Port: C7 Y_DIR_PIN protected + PIN: 24 Port: A7 TEMP_0_PIN protected + PIN: 25 Port: A6 TEMP_BED_PIN protected + PIN: 26 Port: A5 Z_ENABLE_PIN protected + PIN: 27 Port: A4 BEEPER_PIN Output = 0 + PIN: 28 Port: A3 LCD_PINS_RS Output = 0 + PIN: 29 Port: A2 Input = 0 + PIN: 30 Port: A1 LCD_PINS_D4 Output = 1 + PIN: 31 Port: A0 SDSS Output = 1 */ - -/** - * EXP1 Connector EXP1 as CR10 STOCKDISPLAY - * ------ ------ - * PA4 | 1 2 | PC0 BEEPER_PIN | 1 2 | BTN_ENC - * PD3 | 3 4 | RESET BTN_EN1 | 3 4 | RESET - * PD2 5 6 | PA1 BTN_EN2 5 6 | LCD_PINS_D4 (ST9720 CLK) - * PA3 | 7 8 | PC1 (ST9720 CS) LCD_PINS_RS | 7 8 | LCD_PINS_ENABLE (ST9720 DAT) - * GND | 9 10 | 5V GND | 9 10 | 5V - * ------ ------ - */ diff --git a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h index 00c9db6f81a8..dc1ea950a72d 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h @@ -29,12 +29,13 @@ #define BOARD_INFO_NAME "Melzi (Malyan)" #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS 17 // ST9720 CS - #define LCD_PINS_ENABLE 16 // ST9720 DAT - #define LCD_PINS_D4 11 // ST9720 CLK + #define BTN_ENC 28 #define BTN_EN1 30 #define BTN_EN2 29 - #define BTN_ENC 28 + + #define LCD_PINS_RS 17 // ST9720 CS + #define LCD_PINS_EN 16 // ST9720 DAT + #define LCD_PINS_D4 11 // ST9720 CLK #define LCD_PINS_DEFINED #endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h index da010ab1a6e2..99cdfd0b4228 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h @@ -32,16 +32,18 @@ #define LCD_SDSS -1 -#if EITHER(CR10_STOCKDISPLAY, LCD_FOR_MELZI) +#if ANY(CR10_STOCKDISPLAY, LCD_FOR_MELZI) + #define BTN_ENC 26 + #define BTN_EN1 10 + #define BTN_EN2 11 + #define LCD_PINS_RS 30 - #define LCD_PINS_ENABLE 28 + #define LCD_PINS_EN 28 #define LCD_PINS_D4 16 + #define LCD_PINS_D5 17 #define LCD_PINS_D6 27 #define LCD_PINS_D7 29 - #define BTN_EN1 10 - #define BTN_EN2 11 - #define BTN_ENC 26 #define LCD_PINS_DEFINED #endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI_V2.h b/Marlin/src/pins/sanguino/pins_MELZI_V2.h index 2cd949e095de..b48e77a5c367 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_V2.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_V2.h @@ -25,6 +25,8 @@ * Melzi V2.0 as found at https://www.reprap.org/wiki/Melzi * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Melzi%20V2/Melzi-circuit.png * Origin: https://www.reprap.org/mediawiki/images/7/7d/Melzi-circuit.png + * + * ATmega644P */ #define BOARD_INFO_NAME "Melzi V2" diff --git a/Marlin/src/pins/sanguino/pins_OMCA.h b/Marlin/src/pins/sanguino/pins_OMCA.h index 7f18283d1c54..65f9006adbf5 100644 --- a/Marlin/src/pins/sanguino/pins_OMCA.h +++ b/Marlin/src/pins/sanguino/pins_OMCA.h @@ -128,8 +128,8 @@ #define HEATER_0_PIN 3 // DONE PWM on RIGHT connector #define HEATER_BED_PIN 4 -#ifndef FAN_PIN - #define FAN_PIN 14 // PWM on MIDDLE connector +#ifndef FAN0_PIN + #define FAN0_PIN 14 // PWM on MIDDLE connector #endif // diff --git a/Marlin/src/pins/sanguino/pins_OMCA_A.h b/Marlin/src/pins/sanguino/pins_OMCA_A.h index a3ceb76a0de9..aa7f79d602d7 100644 --- a/Marlin/src/pins/sanguino/pins_OMCA_A.h +++ b/Marlin/src/pins/sanguino/pins_OMCA_A.h @@ -123,8 +123,8 @@ // #define HEATER_0_PIN 4 -#ifndef FAN_PIN - #define FAN_PIN 3 +#ifndef FAN0_PIN + #define FAN0_PIN 3 #endif // diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index a9e40b2b17a6..bee2a30e44ab 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -100,8 +100,8 @@ // #define HEATER_0_PIN 13 // (extruder) -#ifndef FAN_PIN - #define FAN_PIN 4 // Works for Panelolu2 too +#ifndef FAN0_PIN + #define FAN0_PIN 4 // Works for Panelolu2 too #endif #if DISABLED(SANGUINOLOLU_V_1_2) @@ -112,6 +112,10 @@ #define Z_ENABLE_PIN 4 #endif #define E0_ENABLE_PIN 4 +#else + #if !HAS_CUTTER && !ALL(HAS_WIRED_LCD, IS_NEWPANEL) // Use IO Header + #define CASE_LIGHT_PIN 4 // Hardware PWM - see if IO Header is available + #endif #endif // @@ -125,16 +129,12 @@ * Sanguino libraries! See #368. */ //#define SDSS 24 -#define SDSS 31 +#define SDSS AUX1_09 #if IS_MELZI - #define LED_PIN 27 + #define LED_PIN AUX1_01 #elif MB(STB_11) - #define LCD_BACKLIGHT_PIN 17 // LCD backlight LED -#endif - -#if !HAS_CUTTER && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // try to use IO Header - #define CASE_LIGHT_PIN 4 // Hardware PWM - see if IO Header is available + #define LCD_BACKLIGHT_PIN AUX1_04 // LCD backlight LED #endif /** @@ -145,11 +145,26 @@ * GND GND D31 D30 D29 D28 D27 * A4 A3 A2 A1 A0 */ +#define AUX1_01 27 // A0 +#define AUX1_02 16 // SCL +#define AUX1_03 28 // A1 +#define AUX1_04 17 // SDA +#define AUX1_05 29 // A2 +#define AUX1_06 10 // RX1 +#define AUX1_07 30 // A3 +#define AUX1_08 11 // TX1 +#define AUX1_09 31 // A4 +#define AUX1_10 12 // PWM // // LCD / Controller // -#if HAS_WIRED_LCD && DISABLED(LCD_PINS_DEFINED) + +#ifdef LCD_PINS_DEFINED + + // LCD pins already defined by including header + +#elif HAS_WIRED_LCD #define SD_DETECT_PIN -1 @@ -157,49 +172,53 @@ #if ENABLED(LCD_FOR_MELZI) - #define LCD_PINS_RS 17 - #define LCD_PINS_ENABLE 16 - #define LCD_PINS_D4 11 - #define KILL_PIN 10 - #define BEEPER_PIN 27 + #define LCD_PINS_RS AUX1_04 + #define LCD_PINS_EN AUX1_02 + #define LCD_PINS_D4 AUX1_08 + #define KILL_PIN AUX1_06 + #define BEEPER_PIN AUX1_01 - #elif IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 + #elif IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 #if IS_MELZI - #define LCD_PINS_RS 30 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 29 // SID (MOSI) - #define LCD_PINS_D4 17 // SCK (CLK) clock + #define LCD_PINS_RS AUX1_07 // CS chip select /SS chip slave select + #define LCD_PINS_EN AUX1_05 // SID (MOSI) + #define LCD_PINS_D4 AUX1_04 // SCK (CLK) clock // Pin 27 is taken by LED_PIN, but Melzi LED does nothing with // Marlin so this can be used for BEEPER_PIN. You can use this pin // with M42 instead of BEEPER_PIN. - #define BEEPER_PIN 27 - #else // Sanguinololu >=1.3 + #define BEEPER_PIN AUX1_01 + #else // Sanguinololu >=1.3 #define LCD_PINS_RS 4 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 30 - #define LCD_PINS_D5 29 - #define LCD_PINS_D6 28 - #define LCD_PINS_D7 27 + #define LCD_PINS_EN AUX1_04 + #define LCD_PINS_D4 AUX1_07 + #define LCD_PINS_D5 AUX1_05 + #define LCD_PINS_D6 AUX1_03 + #define LCD_PINS_D7 AUX1_01 #endif #else - #define DOGLCD_A0 30 + #define DOGLCD_A0 AUX1_07 #if ENABLED(MAKRPANEL) - #define BEEPER_PIN 29 - #define DOGLCD_CS 17 - #define LCD_BACKLIGHT_PIN 28 // PA3 + #define BEEPER_PIN AUX1_05 + #define DOGLCD_CS AUX1_04 + #define LCD_BACKLIGHT_PIN AUX1_03 // PA3 #elif IS_MELZI - #define BEEPER_PIN 27 - #define DOGLCD_CS 28 + #define BEEPER_PIN AUX1_01 + #ifndef DOGLCD_CS + #define DOGLCD_CS AUX1_03 + #endif - #else // !MAKRPANEL + #else - #define DOGLCD_CS 29 + #ifndef DOGLCD_CS + #define DOGLCD_CS AUX1_05 + #endif #endif @@ -209,29 +228,29 @@ #elif ENABLED(ZONESTAR_LCD) // For the Tronxy Melzi boards - #define LCD_PINS_RS 28 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 10 - #define LCD_PINS_D5 11 - #define LCD_PINS_D6 16 - #define LCD_PINS_D7 17 + #define LCD_PINS_RS AUX1_03 + #define LCD_PINS_EN AUX1_05 + #define LCD_PINS_D4 AUX1_06 + #define LCD_PINS_D5 AUX1_08 + #define LCD_PINS_D6 AUX1_02 + #define LCD_PINS_D7 AUX1_04 #else #define LCD_PINS_RS 4 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 30 - #define LCD_PINS_D5 29 - #define LCD_PINS_D6 28 - #define LCD_PINS_D7 27 + #define LCD_PINS_EN AUX1_04 + #define LCD_PINS_D4 AUX1_07 + #define LCD_PINS_D5 AUX1_05 + #define LCD_PINS_D6 AUX1_03 + #define LCD_PINS_D7 AUX1_01 #endif #if ENABLED(LCD_FOR_MELZI) - #define BTN_ENC 28 - #define BTN_EN1 29 - #define BTN_EN2 30 + #define BTN_ENC AUX1_03 + #define BTN_EN1 AUX1_05 + #define BTN_EN2 AUX1_07 #elif ENABLED(ZONESTAR_LCD) // For the Tronxy Melzi boards @@ -242,26 +261,26 @@ #elif ENABLED(LCD_I2C_PANELOLU2) #if IS_MELZI - #define BTN_ENC 29 + #define BTN_ENC AUX1_05 #ifndef LCD_SDSS - #define LCD_SDSS 30 // Panelolu2 SD card reader rather than the Melzi + #define LCD_SDSS AUX1_07 // Panelolu2 SD card reader rather than the Melzi #endif #else - #define BTN_ENC 30 + #define BTN_ENC AUX1_07 #endif - #else // !LCD_FOR_MELZI && !ZONESTAR_LCD && !LCD_I2C_PANELOLU2 + #else // !LCD_FOR_MELZI && !ZONESTAR_LCD && !LCD_I2C_PANELOLU2 - #define BTN_ENC 16 + #define BTN_ENC AUX1_02 #ifndef LCD_SDSS - #define LCD_SDSS 28 // Smart Controller SD card reader rather than the Melzi + #define LCD_SDSS AUX1_03 // Smart Controller SD card reader rather than the Melzi #endif #endif #if IS_NEWPANEL && !defined(BTN_EN1) - #define BTN_EN1 11 - #define BTN_EN2 10 + #define BTN_EN1 AUX1_08 + #define BTN_EN2 AUX1_06 #endif #endif // HAS_WIRED_LCD @@ -270,11 +289,11 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER - #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // try to use IO Header + #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !ALL(HAS_WIRED_LCD, IS_NEWPANEL) // try to use IO Header - #define SPINDLE_LASER_ENA_PIN 10 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM - #define SPINDLE_DIR_PIN 11 + #define SPINDLE_LASER_ENA_PIN AUX1_06 // Pullup or pulldown! + #define SPINDLE_DIR_PIN AUX1_08 #elif !MB(MELZI) // use X stepper motor socket @@ -300,7 +319,7 @@ * /RESET O| |O 1A * /SLEEP O| |O 1B * SPINDLE_LASER_PWM_PIN STEP O| |O VDD - * SPINDLE_LASER_ENA_PIN DIR O| |O GND + * SPINDLE_LASER_ENA_PIN DIR O| |O GND * ------- * * Note: Socket names vary from vendor to vendor. diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h index 220956926143..37d1e7030b42 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h @@ -52,8 +52,8 @@ #endif #define E0_ENABLE_PIN 14 -#if !defined(FAN_PIN) && ENABLED(LCD_I2C_PANELOLU2) - #define FAN_PIN 4 // Uses Transistor1 (PWM) on Panelolu2's Sanguino Adapter Board to drive the fan +#if !defined(FAN0_PIN) && ENABLED(LCD_I2C_PANELOLU2) + #define FAN0_PIN 4 // Uses Transistor1 (PWM) on Panelolu2's Sanguino Adapter Board to drive the fan #endif #define SANGUINOLOLU_V_1_2 diff --git a/Marlin/src/pins/sanguino/pins_SETHI.h b/Marlin/src/pins/sanguino/pins_SETHI.h index a2240b385b2b..31d5585cc8cf 100644 --- a/Marlin/src/pins/sanguino/pins_SETHI.h +++ b/Marlin/src/pins/sanguino/pins_SETHI.h @@ -97,13 +97,8 @@ #define HEATER_0_PIN 4 #define HEATER_BED_PIN 3 -#ifndef FAN_PIN - #if GEN7_VERSION >= 13 - // Gen7 v1.3 removed the fan pin - #define FAN_PIN -1 - #else - #define FAN_PIN 31 - #endif +#if !defined(FAN0_PIN) && GEN7_VERSION < 13 // Gen7 v1.3 removed the fan pin + #define FAN0_PIN 31 #endif // diff --git a/Marlin/src/pins/sanguino/pins_STB_11.h b/Marlin/src/pins/sanguino/pins_STB_11.h index 1bda25b3d4f7..5c6c5d4f826c 100644 --- a/Marlin/src/pins/sanguino/pins_STB_11.h +++ b/Marlin/src/pins/sanguino/pins_STB_11.h @@ -28,8 +28,8 @@ #define BOARD_INFO_NAME "STB V1.1" -#ifndef FAN_PIN - #define FAN_PIN 4 // Works for Panelolu2 too +#ifndef FAN0_PIN + #define FAN0_PIN 4 // Works for Panelolu2 too #endif #include "pins_SANGUINOLOLU_12.h" // ... SANGUINOLOLU_11 diff --git a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h index bd9230c32a82..ade9c08aa045 100644 --- a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h +++ b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h @@ -79,7 +79,7 @@ * PIN: 25 Port: A6 FIL_RUNOUT_PIN * PIN: 26 Port: A5 E0_DIR_PIN * PIN: 27 Port: A4 E0_STEP_PIN - * PIN: 28 Port: A3 FAN_PIN + * PIN: 28 Port: A3 FAN0_PIN * PIN: 29 Port: A2 EXP1_3(BTN_ENC) * ADC_KEY_PIN * PIN: 30 Port: A1 TEMP_0_PIN @@ -92,7 +92,7 @@ #define X_MIN_PIN 21 #define Y_MIN_PIN 18 -#if EITHER(Z6S_ZFAULT, Z6BS_ZFAULT) +#if ANY(Z6S_ZFAULT, Z6BS_ZFAULT) #define Z_MIN_PIN 25 #else #define Z_MIN_PIN 13 @@ -109,7 +109,7 @@ #define Y_DIR_PIN 19 #define Y_ENABLE_PIN 24 -#if EITHER(Z6S_ZFAULT, Z6BS_ZFAULT) +#if ANY(Z6S_ZFAULT, Z6BS_ZFAULT) #define Z_STEP_PIN 27 #define Z_DIR_PIN 26 #else @@ -119,7 +119,7 @@ #define Z_ENABLE_PIN 24 -#if EITHER(Z6S_ZFAULT, Z6BS_ZFAULT) +#if ANY(Z6S_ZFAULT, Z6BS_ZFAULT) #define E0_STEP_PIN 15 #define E0_DIR_PIN 14 #else @@ -144,13 +144,13 @@ // #define HEATER_0_PIN 0 #define HEATER_BED_PIN 1 -#define FAN_PIN 28 +#define FAN0_PIN 28 #define FAN1_PIN -1 // // Filament Runout Sensor // -#if EITHER(Z6S_ZFAULT, Z6BS_ZFAULT) +#if ANY(Z6S_ZFAULT, Z6BS_ZFAULT) #define FIL_RUNOUT_PIN 13 #else #define FIL_RUNOUT_PIN 25 // Z-MIN @@ -159,7 +159,7 @@ // // SD card // -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #define SDSS 4 #endif #define SD_DETECT_PIN -1 @@ -170,7 +170,7 @@ * (CS) D11 | 3 4 | D10 (DC/D4) * (EN2) D12 5 6 | D4 or D3 (EN/RS) * (ENC) D29 | 7 8 | D2 (EN1) - * (GND) | 9 10 | (5V) + * GND | 9 10 | 5V * ------ */ #define EXP1_01_PIN 5 @@ -193,15 +193,15 @@ #define LCDSCREEN_NAME "ZONESTAR_12864LCD" #define FORCE_SOFT_SPI //#define LCD_SDSS EXP1_03_PIN - #define LCD_PINS_RS EXP1_03_PIN // ST7920_CS_PIN (LCD module pin 4) - #define LCD_PINS_ENABLE EXP1_06_PIN // ST7920_DAT_PIN (LCD module pin 5) - #define LCD_PINS_D4 EXP1_04_PIN // ST7920_CLK_PIN (LCD module pin 6) + #define LCD_PINS_RS EXP1_03_PIN // ST7920 CS (LCD-4) + #define LCD_PINS_EN EXP1_06_PIN // ST7920 DAT (LCD-5) + #define LCD_PINS_D4 EXP1_04_PIN // ST7920 CLK (LCD-6) #define BOARD_ST7920_DELAY_1 DELAY_2_NOP #define BOARD_ST7920_DELAY_2 DELAY_2_NOP #define BOARD_ST7920_DELAY_3 DELAY_2_NOP -#elif EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) +#elif ANY(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) // // OLED 128x64 // diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index 061e27faf4f7..803b38c42d42 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -24,44 +24,51 @@ // // Prepare a list of protected pins for M42/M43 // +#if HAS_X_AXIS + + #if PIN_EXISTS(X_MIN) + #define _X_MIN X_MIN_PIN, + #else + #define _X_MIN + #endif + #if PIN_EXISTS(X_MAX) + #define _X_MAX X_MAX_PIN, + #else + #define _X_MAX + #endif + #if PIN_EXISTS(X_CS) && AXIS_HAS_SPI(X) + #define _X_CS X_CS_PIN, + #else + #define _X_CS + #endif + #if PIN_EXISTS(X_MS1) + #define _X_MS1 X_MS1_PIN, + #else + #define _X_MS1 + #endif + #if PIN_EXISTS(X_MS2) + #define _X_MS2 X_MS2_PIN, + #else + #define _X_MS2 + #endif + #if PIN_EXISTS(X_MS3) + #define _X_MS3 X_MS3_PIN, + #else + #define _X_MS3 + #endif + #if PIN_EXISTS(X_ENABLE) + #define _X_ENABLE_PIN X_ENABLE_PIN, + #else + #define _X_ENABLE_PIN + #endif + + #define _X_PINS X_STEP_PIN, X_DIR_PIN, _X_ENABLE_PIN _X_MIN _X_MAX _X_MS1 _X_MS2 _X_MS3 _X_CS -#if PIN_EXISTS(X_MIN) - #define _X_MIN X_MIN_PIN, -#else - #define _X_MIN -#endif -#if PIN_EXISTS(X_MAX) - #define _X_MAX X_MAX_PIN, -#else - #define _X_MAX -#endif -#if PIN_EXISTS(X_CS) && AXIS_HAS_SPI(X) - #define _X_CS X_CS_PIN, -#else - #define _X_CS -#endif -#if PIN_EXISTS(X_MS1) - #define _X_MS1 X_MS1_PIN, -#else - #define _X_MS1 -#endif -#if PIN_EXISTS(X_MS2) - #define _X_MS2 X_MS2_PIN, -#else - #define _X_MS2 -#endif -#if PIN_EXISTS(X_MS3) - #define _X_MS3 X_MS3_PIN, -#else - #define _X_MS3 -#endif -#if PIN_EXISTS(X_ENABLE) - #define _X_ENABLE_PIN X_ENABLE_PIN, #else - #define _X_ENABLE_PIN -#endif -#define _X_PINS X_STEP_PIN, X_DIR_PIN, _X_ENABLE_PIN _X_MIN _X_MAX _X_MS1 _X_MS2 _X_MS3 _X_CS + #define _X_PINS + +#endif #if HAS_Y_AXIS @@ -643,7 +650,7 @@ #endif #endif -#elif EITHER(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) +#elif ANY(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) #undef _E1_PINS #define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN, _E1_CS _E1_MS1 _E1_MS2 _E1_MS3 @@ -899,8 +906,8 @@ #define _Z_PROBE #endif -#if PIN_EXISTS(FAN) - #define _FAN0 FAN_PIN, +#if PIN_EXISTS(FAN0) + #define _FAN0 FAN0_PIN, #else #define _FAN0 #endif diff --git a/Marlin/src/pins/stm32f1/env_validate.h b/Marlin/src/pins/stm32f1/env_validate.h index 2d325428ac8c..47399a062d6c 100644 --- a/Marlin/src/pins/stm32f1/env_validate.h +++ b/Marlin/src/pins/stm32f1/env_validate.h @@ -19,7 +19,8 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if NOT_TARGET(__STM32F1__, STM32F1) #if DISABLED(ALLOW_STM32F4) @@ -30,3 +31,5 @@ #endif #undef ALLOW_STM32F4 + +#endif diff --git a/Marlin/src/pins/stm32f1/pins_BEAST.h b/Marlin/src/pins/stm32f1/pins_BEAST.h index 4dafe2f27365..cf64ff1c6a29 100644 --- a/Marlin/src/pins/stm32f1/pins_BEAST.h +++ b/Marlin/src/pins/stm32f1/pins_BEAST.h @@ -24,7 +24,7 @@ #include "env_validate.h" /** - * 21017 Victor Perez Marlin for stm32f1 test + * 2017 Victor Perez Marlin for stm32f1 test */ #define BOARD_INFO_NAME "Beast STM32" @@ -89,8 +89,8 @@ #define HEATER_BED_PIN PB9 // BED -#ifndef FAN_PIN - #define FAN_PIN PB10 +#ifndef FAN0_PIN + #define FAN0_PIN PB10 #endif #define FAN_SOFT_PWM_REQUIRED @@ -112,7 +112,7 @@ #error "REPRAPWORLD_GRAPHICAL_LCD is not supported." #else #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_EN PD2 #define LCD_PINS_D4 PB12 #define LCD_PINS_D5 PB13 #define LCD_PINS_D6 PB14 @@ -131,7 +131,7 @@ #error "LCD_I2C_PANELOLU2 is not supported." #elif ENABLED(LCD_I2C_VIKI) #error "LCD_I2C_VIKI is not supported." - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #error "VIKI2 / miniVIKI is not supported." #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) #error "ELB_FULL_GRAPHIC_CONTROLLER is not supported." diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h index e3e91ff35ad4..fb11bbe55f72 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -112,7 +112,7 @@ #define HEATER_0_PIN PC8 // HEATER1 #define HEATER_BED_PIN PC9 // HOT BED -#define FAN_PIN PC6 // FAN +#define FAN0_PIN PC6 // FAN #define FAN_SOFT_PWM_REQUIRED #define CONTROLLER_FAN_PIN PC7 @@ -120,13 +120,14 @@ // // LCD / Controller // + #if ENABLED(CR10_STOCKDISPLAY) #define BTN_ENC PA15 #define BTN_EN1 PA9 #define BTN_EN2 PA10 #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PB15 + #define LCD_PINS_EN PB15 #define LCD_PINS_D4 PB9 #define BEEPER_PIN PB5 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 075258991ddd..f3b3f8fec72d 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -31,7 +31,7 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -94,18 +94,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB5 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB4 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB3 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB5 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB4 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB3 #endif #if HAS_TMC_UART @@ -133,8 +131,11 @@ #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -147,7 +148,7 @@ // #define HEATER_0_PIN PC8 // "HE" #define HEATER_BED_PIN PC9 // "HB" -#define FAN_PIN PA8 // "FAN0" +#define FAN0_PIN PA8 // "FAN0" // // USB connect control @@ -175,6 +176,19 @@ #define EXP1_07_PIN PB8 #define EXP1_08_PIN PB7 +/* ----- + * | 1 | RST + * | 2 | PA3 RX2 + * | 3 | PA2 TX2 + * | 4 | GND + * | 5 | 5V + * ----- + * TFT + */ + +#define TFT_02 PA3 +#define TFT_03 PA2 + #if HAS_WIRED_LCD #if ENABLED(CR10_STOCKDISPLAY) @@ -186,7 +200,7 @@ #define BTN_EN2 EXP1_05_PIN #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! @@ -196,14 +210,14 @@ #endif #define LCD_PINS_RS EXP1_06_PIN - #define LCD_PINS_ENABLE EXP1_02_PIN + #define LCD_PINS_EN EXP1_02_PIN #define LCD_PINS_D4 EXP1_07_PIN #define LCD_PINS_D5 EXP1_05_PIN #define LCD_PINS_D6 EXP1_03_PIN #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) /** Creality Ender-2 display pinout * ------ @@ -237,7 +251,7 @@ #endif /** - * FYSETC_MINI_12864_2_1 / MKS_MINI_12864_V3 / BTT_MINI_12864_V1 display pinout + * FYSETC_MINI_12864_2_1 / MKS_MINI_12864_V3 / BTT_MINI_12864 display pinout * * Board Display * ------ ------ @@ -250,13 +264,13 @@ * EXP1 EXP1 * * - * ----- ------ + * --- ------ * | 1 | RST -- |10 9 | -- * | 2 | PA3 RX2 RESET_BTN | 8 7 | SD_DETECT * | 3 | PA2 TX2 LCD_MOSI | 6 5 EN2 * | 4 | GND -- | 4 3 | EN1 * | 5 | 5V LCD_SCK | 2 1 | -- - * ----- ------ + * --- ------ * TFT EXP2 * @@ -295,7 +309,7 @@ #endif // HAS_WIRED_LCD -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_E3_DIP.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" @@ -339,9 +353,8 @@ #endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 // -// SD Support +// SD Card // - #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif @@ -351,7 +364,7 @@ #define SD_SCK_PIN PA5 #define SD_MISO_PIN PA6 #define SD_MOSI_PIN PA7 -#elif SD_CONNECTION_IS(LCD) && BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#elif SD_CONNECTION_IS(LCD) && ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #define SD_DETECT_PIN EXP1_01_PIN #define SD_SS_PIN EXP1_05_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h index 44d4f2343546..c345a27b76e9 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h @@ -46,5 +46,8 @@ #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h index c0428279f0fe..b16cedb5cdf5 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h @@ -37,7 +37,7 @@ #undef NO_EEPROM_SELECTED #endif -#define FAN_PIN PC6 +#define FAN0_PIN PC6 // // USB connect control @@ -55,7 +55,13 @@ * ------ * EXP1 */ +#define EXP1_01_PIN PB5 #define EXP1_02_PIN PA15 +#define EXP1_03_PIN PA9 +#define EXP1_04_PIN -1 // RESET +#define EXP1_05_PIN PA10 +#define EXP1_06_PIN PB9 +#define EXP1_07_PIN PB8 #define EXP1_08_PIN PB15 #include "pins_BTT_SKR_MINI_E3_common.h" 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 5770f4a5ba01..eb043cbe307a 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -31,7 +31,7 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -100,8 +100,8 @@ #define HEATER_0_PIN PC8 // "HE" #define HEATER_BED_PIN PC9 // "HB" -#ifndef FAN_PIN - #define FAN_PIN PA8 // "FAN0" +#ifndef FAN0_PIN + #define FAN0_PIN PA8 // "FAN0" #endif // @@ -114,26 +114,39 @@ #define USB_CONNECT_INVERTING false /** - * SKR Mini E3 V1.0, V1.2 - * ------ - * (BEEPER) PB5 | 1 2 | PB6 (BTN_ENC) - * (BTN_EN1) PA9 | 3 4 | RESET - * (BTN_EN2) PA10 5 6 | PB9 (LCD_D4) - * (LCD_RS) PB8 | 7 8 | PB7 (LCD_EN) - * GND | 9 10 | 5V - * ------ - * EXP1 + * SKR Mini E3 V1.0, V1.2 SKR Mini E3 V2.0 + * ------ ------ + * (BEEPER) PB5 | 1 2 | PB6 (BTN_ENC) (BEEPER) PB5 | 1 2 | PA15 (BTN_ENC) + * (BTN_EN1) PA9 | 3 4 | RESET (BTN_EN1) PA9 | 3 4 | RESET + * (BTN_EN2) PA10 5 6 | PB9 (LCD_D4) (BTN_EN2) PA10 5 6 | PB9 (LCD_D4) + * (LCD_RS) PB8 | 7 8 | PB7 (LCD_EN) (LCD_RS) PB8 | 7 8 | PB15 (LCD_EN) + * GND | 9 10 | 5V GND | 9 10 | 5V + * ------ ------ + * EXP1 EXP1 */ -#ifndef EXP1_02_PIN +#ifndef EXP1_08_PIN + #define EXP1_01_PIN PB5 #define EXP1_02_PIN PB6 + #define EXP1_03_PIN PA9 + #define EXP1_04_PIN -1 // RESET + #define EXP1_05_PIN PA10 + #define EXP1_06_PIN PB9 + #define EXP1_07_PIN PB8 #define EXP1_08_PIN PB7 #endif -#define EXP1_01_PIN PB5 -#define EXP1_03_PIN PA9 -#define EXP1_04_PIN -1 // RESET -#define EXP1_05_PIN PA10 -#define EXP1_06_PIN PB9 -#define EXP1_07_PIN PB8 + +/* ----- + * | 1 | RST + * | 2 | PA3 RX2 + * | 3 | PA2 TX2 + * | 4 | GND + * | 5 | 5V + * ----- + * TFT + */ + +#define TFT_02 PA3 +#define TFT_03 PA2 #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI /** @@ -169,7 +182,7 @@ #define BTN_EN2 EXP1_05_PIN #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(LCD_FOR_MELZI) @@ -200,7 +213,7 @@ #define BTN_EN2 EXP1_07_PIN #define LCD_PINS_RS EXP1_01_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! @@ -210,14 +223,14 @@ #endif #define LCD_PINS_RS EXP1_06_PIN - #define LCD_PINS_ENABLE EXP1_02_PIN + #define LCD_PINS_EN EXP1_02_PIN #define LCD_PINS_D4 EXP1_07_PIN #define LCD_PINS_D5 EXP1_05_PIN #define LCD_PINS_D6 EXP1_03_PIN #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP1_03_PIN @@ -242,15 +255,15 @@ /** * TFTGLCD_PANEL_SPI display pinout * - * Board Display - * ------ ------ - * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V |10 9 | GND - * (MOD_RESET) PA9 | 3 4 | RESET -- | 8 7 | (SD_DET) - * (SD_CS) PA10 5 6 | PB9 (MOSI) | 6 5 | -- - * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 4 3 | (LCD_CS) - * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) - * ------ ------ - * EXP1 EXP1 + * Board Display + * ------ ------ + * (SD_DET) PB5 | 1 2 | PB6 or PA15 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PA9 | 3 4 | RESET -- | 8 7 | (SD_DET) + * (SD_CS) PA10 5 6 | PB9 (MOSI) | 6 5 | -- + * (LCD_CS) PB8 | 7 8 | PB7 or PB15 (SD_CS) | 4 3 | (LCD_CS) + * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * @@ -275,28 +288,28 @@ #elif ENABLED(FYSETC_MINI_12864_2_1) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING - #error "CAUTION! FYSETC_MINI_12864_2_1 / MKS_MINI_12864_V3 / BTT_MINI_12864_V1 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" + #error "CAUTION! FYSETC_MINI_12864_2_1 / MKS_MINI_12864_V3 / BTT_MINI_12864 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" #endif /** - * FYSETC_MINI_12864_2_1 / MKS_MINI_12864_V3 / BTT_MINI_12864_V1 display pinout + * FYSETC_MINI_12864_2_1 / MKS_MINI_12864_V3 / BTT_MINI_12864 display pinout * - * Board Display - * ------ ------ - * PB5 | 1 2 | PA15 (BEEP) |10 9 | BTN_ENC - * PA9 | 3 4 | RESET LCD_CS | 8 7 | LCD A0 - * PA10 | 5 6 | PB9 LCD_RST | 6 5 | RED - * PB8 | 7 8 | PB15 (GREEN) | 4 3 | (BLUE) - * GND | 9 10 | 5V GND | 2 1 | 5V - * ------ ------ - * EXP1 EXP1 + * Board Display + * ------ ------ + * PB5 | 1 2 | PB6 or PA15 (BEEP) |10 9 | BTN_ENC + * PA9 | 3 4 | RESET LCD_CS | 8 7 | LCD A0 + * PA10 | 5 6 | PB9 LCD_RST | 6 5 | RED + * PB8 | 7 8 | PB7 or PB15 (GREEN) | 4 3 | (BLUE) + * GND | 9 10 | 5V GND | 2 1 | 5V + * ------ ------ + * EXP1 EXP1 * * --- ------ * RST | 1 | (MISO) |10 9 | SCK * (RX2) PA3 | 2 | BTN_EN1 | 8 7 | (SS) * (TX2) PA2 | 3 | BTN_EN2 | 6 5 | MOSI * GND | 4 | (CD) | 4 3 | (RST) - * 5V | 5 | (GND) | 2 1 | (KILL) + * 5V | 5 | GND | 2 1 | (KILL) * --- ------ * TFT EXP2 * @@ -330,19 +343,19 @@ #define DOGLCD_SCK PA2 #define DOGLCD_MOSI PA3 - #define BTN_ENC PA15 + #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP1_06_PIN - #define BTN_EN2 PB15 + #define BTN_EN2 EXP1_08_PIN #define FORCE_SOFT_SPI #else - #error "Only CR10_STOCKDISPLAY, LCD_FOR_MELZI, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, TFTGLCD_PANEL_(SPI|I2C), FYSETC_MINI_12864_2_1, MKS_MINI_12864_V3, and BTT_MINI_12864_V1 are currently supported on the BIGTREE_SKR_MINI_E3." + #error "Only CR10_STOCKDISPLAY, LCD_FOR_MELZI, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, TFTGLCD_PANEL_(SPI|I2C), FYSETC_MINI_12864_2_1, MKS_MINI_12864_V3, and BTT_MINI_12864 are currently supported on the BIGTREE_SKR_MINI_E3." #endif #endif // HAS_WIRED_LCD -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" @@ -351,15 +364,15 @@ /** * FYSETC TFT TFT81050 display pinout * - * Board Display - * ------ ------ - * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V |10 9 | GND - * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 8 7 | (SD_DET) - * (SD_CS) PA10 5 6 | PB9 (MOSI) | 6 5 | (LCD_CS) - * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 4 3 | (MOD_RESET) - * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) - * ------ ------ - * EXP1 EXP1 + * Board Display + * ------ ------ + * (SD_DET) PB5 | 1 2 | PB6 or PA15 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 8 7 | (SD_DET) + * (SD_CS) PA10 5 6 | PB9 (MOSI) | 6 5 | (LCD_CS) + * (LCD_CS) PB8 | 7 8 | PB7 or PB15 (SD_CS) | 4 3 | (MOD_RESET) + * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * @@ -396,7 +409,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC4 -#elif SD_CONNECTION_IS(LCD) && (BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) +#elif SD_CONNECTION_IS(LCD) && (ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) #define SD_DETECT_PIN EXP1_01_PIN #define SD_SS_PIN EXP1_05_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index c544e1353c1f..d0bd2944bc03 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -31,7 +31,7 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -68,40 +68,42 @@ #define E0_DIR_PIN PB0 #define E0_ENABLE_PIN PC4 -#if ENABLED(TMC_USE_SW_SPI) // Shared with EXP2 - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB3 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB4 - #endif - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB5 - #endif +// Shared with EXP2 +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB3 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB4 +#endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB5 #endif #if HAS_TMC_UART // Shared with EXP1 - #define X_SERIAL_TX_PIN PC10 - #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + #define X_SERIAL_TX_PIN PC10 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN PC11 - #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + #define Y_SERIAL_TX_PIN PC11 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN PC12 - #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + #define Z_SERIAL_TX_PIN PC12 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN PC14 - #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN + #define E0_SERIAL_TX_PIN PC14 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Heaters / Fans // #define HEATER_0_PIN PA8 -#define FAN_PIN PC8 +#define FAN0_PIN PC8 #define HEATER_BED_PIN PC9 // @@ -140,7 +142,8 @@ // // LCD / Controller // -#if EITHER(TFT_COLOR_UI, TFT_CLASSIC_UI) + +#if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI) #define BEEPER_PIN EXP1_01_PIN #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP2_03_PIN @@ -169,7 +172,7 @@ #define LCD_READ_ID 0xD3 #define LCD_USE_DMA_SPI - #define TFT_BUFFER_SIZE 9600 + #define TFT_BUFFER_WORDS 9600 #elif HAS_WIRED_LCD #define BEEPER_PIN EXP1_01_PIN @@ -181,7 +184,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif IS_TFTGLCD_PANEL @@ -202,7 +205,7 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #if ENABLED(FYSETC_MINI_12864) @@ -215,11 +218,11 @@ #define FORCE_SOFT_SPI // SPI MODE3 - #define LED_PIN EXP1_06_PIN // red pwm + #define LED_PIN EXP1_06_PIN // red pwm //#define LED_PIN EXP1_07_PIN // green //#define LED_PIN EXP1_08_PIN // blue - //#if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + //#if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) // #ifndef RGB_LED_R_PIN // #define RGB_LED_R_PIN EXP1_06_PIN // #endif @@ -233,7 +236,7 @@ // #define NEOPIXEL_PIN EXP1_06_PIN //#endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #define LCD_PINS_D4 EXP1_05_PIN #if IS_ULTIPANEL @@ -271,7 +274,7 @@ #endif #if SD_CONNECTION_IS(LCD) - #define SPI_DEVICE 3 + #define SPI_DEVICE 3 // Maple #define SD_DETECT_PIN EXP2_07_PIN #define SD_SCK_PIN EXP2_02_PIN #define SD_MISO_PIN EXP2_01_PIN @@ -287,4 +290,4 @@ #define ONBOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card -#define SDSS SD_SS_PIN +#define SDSS SD_SS_PIN diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index c73544bf436f..47b32176bee3 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -41,7 +41,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE 0x800U // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -100,7 +100,9 @@ #endif // Reduce baud rate to improve software serial reliability -#define TMC_BAUD_RATE 19200 +#ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 +#endif // // Temperature Sensors @@ -114,7 +116,7 @@ #define HEATER_0_PIN PC8 // HEATER0 #define HEATER_BED_PIN PC9 // HOT BED -#define FAN_PIN PA7 // FAN (fan2 on board) model cool fan +#define FAN0_PIN PA7 // FAN (fan2 on board) model cool fan #define FAN1_PIN PA8 // FAN (fan0 on board) e0 cool fan #define FAN2_PIN PB9 // FAN (fan1 on board) controller cool fan @@ -134,7 +136,7 @@ #define EXP1_01_PIN PB5 #define EXP1_02_PIN PB6 #define EXP1_03_PIN PA2 -#define EXP1_04_PIN -1 // RESET +#define EXP1_04_PIN -1 // RESET #define EXP1_05_PIN PA3 #define EXP1_06_PIN PB8 #define EXP1_07_PIN PB7 @@ -143,6 +145,7 @@ // // LCD / Controller // + #if ENABLED(CR10_STOCKDISPLAY) #define BEEPER_PIN EXP1_01_PIN #define BTN_EN1 EXP1_03_PIN @@ -151,7 +154,7 @@ #define LCD_PINS_RS EXP1_07_PIN // CS -- SOFT SPI for ENDER3 LCD #define LCD_PINS_D4 EXP1_06_PIN // SCLK - #define LCD_PINS_ENABLE EXP1_08_PIN // DATA MOSI + #define LCD_PINS_EN EXP1_08_PIN // DATA MOSI #endif // Alter timing for graphical display diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D.h b/Marlin/src/pins/stm32f1/pins_CHITU3D.h index 3b66096a270d..2074bbeccec1 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D.h @@ -83,8 +83,8 @@ #define HEATER_0_PIN PD12 // HOT-END #define HEATER_BED_PIN PG11 // HOT-BED -#ifndef FAN_PIN - #define FAN_PIN PG14 // MAIN BOARD FAN +#ifndef FAN0_PIN + #define FAN0_PIN PG14 // MAIN BOARD FAN #endif #define FAN_SOFT_PWM_REQUIRED @@ -102,18 +102,18 @@ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) #define LCD_PINS_RS PD1 // 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE PD3 // 51 // SID (MOSI) + #define LCD_PINS_EN PD3 // 51 // SID (MOSI) #define LCD_PINS_D4 PD4 // 52 // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_EN PD2 #define LCD_PINS_D4 PB12 #define LCD_PINS_D5 PB13 #define LCD_PINS_D6 PB14 #define LCD_PINS_D7 PB15 #else #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_EN PD2 #define LCD_PINS_D4 PB12 #define LCD_PINS_D5 PB13 #define LCD_PINS_D6 PB14 @@ -171,7 +171,7 @@ #define LCD_SDSS PD5 // 53 #define SD_DETECT_PIN PD1 // 49 - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #define BEEPER_PIN PC1 // 33 diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h index 02daab3e63ac..18c8e22dff9e 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h @@ -39,7 +39,7 @@ #include "pins_CHITU3D_common.h" -/* +/** * Circuit diagram https://github.com/MarlinFirmware/Marlin/files/3401484/x5sa-main_board-2.pdf * * Details on the 30 pin ribbon pins. From: https://3dtoday.ru/blogs/artem-sr/tronxy-x5sa-pro-ustanovka-bfp-touch-na-board-chitu3d-v6-cxy-v6-191017 diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h index f5dd4a42b0f6..e595801103ba 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h @@ -99,7 +99,7 @@ // Fans // #define CONTROLLER_FAN_PIN PD6 // BOARD FAN -#define FAN_PIN PG13 // FAN +#define FAN0_PIN PG13 // FAN #define FAN2_PIN PG14 // @@ -113,18 +113,18 @@ #define FIL_RUNOUT_PIN PA15 // MT_DET #endif -// SPI Flash +// +// SPI Flash (SPI 2) +// #define SPI_FLASH #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x200000 // 2MB + #define SPI_FLASH_CS_PIN PB12 + #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif -// SPI 2 -#define SPI_FLASH_CS_PIN PB12 -#define SPI_FLASH_MOSI_PIN PB15 -#define SPI_FLASH_MISO_PIN PB14 -#define SPI_FLASH_SCK_PIN PB13 - // // TFT with FSMC interface // @@ -157,12 +157,12 @@ #define HAS_LOGO_IN_FLASH 0 #elif ENABLED(TFT_COLOR_UI) // Color UI - #define TFT_BUFFER_SIZE 14400 + #define TFT_BUFFER_WORDS 14400 #endif // SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available // so SPI2 is required. -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple #define SD_SCK_PIN PB13 #define SD_MISO_PIN PB14 #define SD_MOSI_PIN PB15 @@ -171,7 +171,7 @@ // // SD Card // -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define SD_DETECT_PIN -1 // PF0, but it isn't connected #define SDIO_CLOCK 4500000 #define SDIO_READ_RETRIES 16 diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1.h index f7a73de28471..058dcdf94f23 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1.h @@ -25,6 +25,11 @@ * Creality v2.4.S1 (STM32F103RE / STM32F103RC) v101 as found in the Ender-7 */ +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 + #error "Creality 2.4.S1 V101 only supports 1 hotend / E stepper." + #define E_ERROR 1 +#endif + #define BOARD_INFO_NAME "Creality v2.4.S1 V101" #define DEFAULT_MACHINE_NAME "Creality3D" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h index b7ea20725b25..a99143bad976 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h @@ -30,9 +30,10 @@ #if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "Creality v24S1 only supports 1 hotend / E stepper." + #define E_ERROR 1 #endif -#if BOTH(BLTOUCH, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) +#if ALL(BLTOUCH, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) #error "Disable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN when using BLTOUCH with Creality V24S1-301." #endif @@ -84,11 +85,11 @@ #if HAS_CUTTER //#define HEATER_0_PIN -1 //#define HEATER_BED_PIN -1 - #define FAN_PIN -1 - #define SPINDLE_LASER_ENA_PIN PC0 // FET 1 + #define FAN0_PIN -1 #define SPINDLE_LASER_PWM_PIN PC0 // Bed FET + #define SPINDLE_LASER_ENA_PIN PC0 // FET 1 #define SPINDLE_DIR_PIN PC0 // FET 4 - #define LASER_SOFT_PWM_PIN PC0 + //#define LASER_SOFT_PWM_PIN PC0 #endif #include "pins_CREALITY_V4.h" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h index a0152a522166..93be4978d341 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h @@ -49,11 +49,11 @@ #endif #if ENABLED(IIC_BL24CXX_EEPROM) - #define IIC_EEPROM_SDA PA11 - #define IIC_EEPROM_SCL PA12 - #define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16) -#elif EITHER(SDCARD_EEPROM_EMULATION, FLASH_EEPROM_EMULATION) - #define MARLIN_EEPROM_SIZE 0x800 // 2K + #define IIC_EEPROM_SDA PA11 + #define IIC_EEPROM_SCL PA12 + #define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16) +#elif ANY(SDCARD_EEPROM_EMULATION, FLASH_EEPROM_EMULATION) + #define MARLIN_EEPROM_SIZE 0x800 // 2K #endif // @@ -61,19 +61,16 @@ // #define X_STOP_PIN PC4 #define Y_STOP_PIN PC5 +#define Z_STOP_PIN PC15 +// +// Probe +// #if ENABLED(BLTOUCH) - #define Z_STOP_PIN -1 #define SERVO0_PIN PC14 // BLTouch OUT PIN - #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PC15 // BLTouch IN PIN - #endif -#else - #define Z_STOP_PIN PC15 - #if ENABLED(PROBE_ACTIVATION_SWITCH) - #define PROBE_TARE_PIN PC14 - #define PROBE_ACTIVATION_SWITCH_PIN PB2 - #endif +#elif ENABLED(PROBE_ACTIVATION_SWITCH) + #define PROBE_TARE_PIN PC14 + #define PROBE_ACTIVATION_SWITCH_PIN PB2 #endif // @@ -114,7 +111,7 @@ #define HEATER_0_PIN PB14 // HEATER1 #define HEATER_BED_PIN PB13 // HOT BED -#define FAN_PIN PB15 // FAN +#define FAN0_PIN PB15 // FAN #ifndef E0_AUTO_FAN_PIN #define E0_AUTO_FAN_PIN PC13 // FAN #endif @@ -127,7 +124,7 @@ #define SDCARD_CONNECTION ONBOARD #define ON_BOARD_SPI_DEVICE 1 #define ONBOARD_SD_CS_PIN PC12 // SDSS -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define NO_SD_HOST_DRIVE // This board's SD is only seen by the printer // diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index c5125aaff4d8..96b3007ca650 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -27,7 +27,7 @@ #include "env_validate.h" -#if HAS_MULTI_HOTEND || E_STEPPERS > 1 +#if !E_ERROR && (HAS_MULTI_HOTEND || E_STEPPERS > 1) #error "Creality v4 only supports 1 hotend / E stepper." #endif @@ -149,8 +149,8 @@ #ifndef HEATER_BED_PIN #define HEATER_BED_PIN PA2 // HOT BED #endif -#ifndef FAN_PIN - #define FAN_PIN PA0 // FAN +#ifndef FAN0_PIN + #define FAN0_PIN PA0 // FAN #endif #define FAN_SOFT_PWM_REQUIRED @@ -159,7 +159,7 @@ // #define SD_DETECT_PIN PC7 #define SDCARD_CONNECTION ONBOARD -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define NO_SD_HOST_DRIVE // This board's SD is only seen by the printer #if ANY(RET6_12864_LCD, HAS_DWIN_E3V2, IS_DWIN_MARLINUI) @@ -183,7 +183,7 @@ #define EXP3_07_PIN PB12 #define EXP3_08_PIN PB15 -#elif EITHER(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD) +#elif ANY(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD) /** * VET6 12864 LCD @@ -204,14 +204,14 @@ #define EXP3_07_PIN PA4 #define EXP3_08_PIN PA7 -#elif EITHER(CR10_STOCKDISPLAY, FYSETC_MINI_12864_2_1) +#elif ANY(CR10_STOCKDISPLAY, FYSETC_MINI_12864_2_1) #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for the LCD with the Creality V4 controller." #endif #if ENABLED(CR10_STOCKDISPLAY) #define LCD_PINS_RS EXP3_07_PIN - #define LCD_PINS_ENABLE EXP3_08_PIN + #define LCD_PINS_EN EXP3_08_PIN #define LCD_PINS_D4 EXP3_06_PIN #define BTN_ENC EXP3_02_PIN @@ -299,11 +299,3 @@ #define UART4_RX_PIN PC11 // default uses sdcard SDIO_D3 #define UART5_TX_PIN PC12 // default uses sdcard SDIO_CK #define UART5_RX_PIN PD2 // default uses sdcard SDIO_CMD - -// SDIO pins -#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/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index f3b7e4f308b9..2e0de876410b 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -130,7 +130,7 @@ #define HEATER_0_PIN PA0 // HEATER1 #define HEATER_BED_PIN PA1 // HOT BED -#define FAN_PIN PA2 // FAN +#define FAN0_PIN PA2 // FAN #define FAN_SOFT_PWM_REQUIRED // @@ -140,7 +140,7 @@ #define SDCARD_CONNECTION ONBOARD #define ONBOARD_SPI_DEVICE 1 #define ONBOARD_SD_CS_PIN PA4 // SDSS -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define NO_SD_HOST_DRIVE // This board's SD is only seen by the printer #if ANY(RET6_12864_LCD, HAS_DWIN_E3V2, IS_DWIN_MARLINUI) @@ -164,7 +164,7 @@ #define EXP3_07_PIN PB12 #define EXP3_08_PIN PB15 -#elif EITHER(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD) +#elif ANY(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD) /** * VET6 12864 LCD @@ -193,7 +193,7 @@ #endif #define LCD_PINS_RS EXP3_07_PIN - #define LCD_PINS_ENABLE EXP3_08_PIN + #define LCD_PINS_EN EXP3_08_PIN #define LCD_PINS_D4 EXP3_06_PIN #define BTN_ENC EXP3_02_PIN diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V425.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V425.h index 1c62d19a99e4..a225fe11be5a 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V425.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V425.h @@ -27,10 +27,6 @@ #include "env_validate.h" -#if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "Creality v4.2.5 only supports 1 hotend / E stepper." -#endif - #define BOARD_INFO_NAME "Creality V4.2.5" #define DEFAULT_MACHINE_NAME "CR200B" @@ -72,6 +68,6 @@ // #define HEATER_0_PIN PA0 // HEATER1 #define HEATER_BED_PIN PA1 // HOT BED -#define FAN_PIN PA2 // FAN +#define FAN0_PIN PA2 // FAN #include "pins_CREALITY_V4.h" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h index 4f57f8a805df..2f89402607cd 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h @@ -33,7 +33,7 @@ #define HEATER_0_PIN PA1 // HEATER1 #define HEATER_BED_PIN PA2 // HOT BED -#define FAN_PIN PA0 // FAN +#define FAN0_PIN PA0 // FAN #if ENABLED(PROBE_ACTIVATION_SWITCH) #ifndef PROBE_ACTIVATION_SWITCH_PIN diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h index 6a0fa4f41802..25b5d6c0acc7 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h @@ -33,7 +33,7 @@ #define HEATER_0_PIN PB14 // HEATER1 #define HEATER_BED_PIN PB13 // HOT BED -#define FAN_PIN PB15 // FAN +#define FAN0_PIN PB15 // FAN #if ENABLED(PROBE_ACTIVATION_SWITCH) #ifndef PROBE_ACTIVATION_SWITCH_PIN diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h index a9ff02d1f4e2..d592b4808a38 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h @@ -105,7 +105,7 @@ #define SD_DETECT_PIN PC7 #define NO_SD_HOST_DRIVE // SD is only seen by the printer -#define SDIO_SUPPORT // Extra added by Creality +#define ONBOARD_SDIO // Extra added by Creality #define SDIO_CLOCK 6000000 // In original source code overridden by Creality in sdio.h // diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h index d3d3685531dc..2660b6e50518 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h @@ -133,9 +133,9 @@ #define HEATER_1_PIN PA0 // HEATER1 #define HEATER_BED_PIN PA2 // HOT BED -#define FAN_PIN PB14 // FAN +#define FAN0_PIN PB14 // FAN #define FAN1_PIN PB12 // FAN -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED // // SD Card @@ -144,7 +144,7 @@ #define SDCARD_CONNECTION ONBOARD #define ONBOARD_SPI_DEVICE 1 #define ONBOARD_SD_CS_PIN PC11 // SDSS -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define NO_SD_HOST_DRIVE // This board's SD is only seen by the printer #if ANY(RET6_12864_LCD, HAS_DWIN_E3V2, IS_DWIN_MARLINUI) @@ -168,7 +168,7 @@ #define EXP3_07_PIN PB12 #define EXP3_08_PIN PB15 -#elif EITHER(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD) +#elif ANY(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD) /** * VET6 12864 LCD @@ -197,7 +197,7 @@ #endif #define LCD_PINS_RS EXP3_07_PIN - #define LCD_PINS_ENABLE EXP3_08_PIN + #define LCD_PINS_EN EXP3_08_PIN #define LCD_PINS_D4 EXP3_06_PIN #define BTN_ENC EXP3_02_PIN @@ -219,8 +219,3 @@ #endif #endif - -// DGUS LCDs -#if HAS_DGUS_LCD - #define LCD_SERIAL_PORT 3 -#endif diff --git a/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h b/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h index 08c9500fc5e1..b18bd09de894 100644 --- a/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h @@ -39,7 +39,7 @@ #define DISABLE_JTAG //#define ENABLE_SPI3 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -98,22 +98,22 @@ #define FAN1_PIN PD12 #elif DISABLED(FET_ORDER_SF) // Not Spindle, Fan (i.e., "EFBF" or "EFBE") #define HEATER_BED_PIN PD12 - #if EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) + #if ANY(HAS_MULTI_HOTEND, HEATERS_PARALLEL) #define HEATER_1_PIN PB9 #else #define FAN1_PIN PB9 #endif #endif -#ifndef FAN_PIN - #if EITHER(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan - #define FAN_PIN PB5 - #elif EITHER(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan - #define FAN_PIN PD12 +#ifndef FAN0_PIN + #if ANY(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan + #define FAN0_PIN PB5 + #elif ANY(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan + #define FAN0_PIN PD12 #elif ENABLED(FET_ORDER_EEB) // Hotend, Hotend, Bed - #define FAN_PIN -1 // IO pin. Buffer needed + #define FAN0_PIN -1 // IO pin. Buffer needed #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") - #define FAN_PIN PB5 + #define FAN0_PIN PB5 #endif #endif @@ -148,25 +148,29 @@ #define E0_SLAVE_ADDRESS 0 #endif #endif + // // Temperature Sensors // -#define TEMP_BED_PIN PC2 //TB -#define TEMP_0_PIN PC1 //TH1 -//#define TEMP_1_PIN PC3 //TH2 -#define TEMP_BOARD_PIN PC3 -#ifndef TEMP_SENSOR_BOARD - #define TEMP_SENSOR_BOARD 13 -#endif +#define TEMP_BED_PIN PC2 // TB +#define TEMP_0_PIN PC1 // TH1 +//#define TEMP_1_PIN PC3 // TH2 #define FIL_RUNOUT_PIN PA10 // MT_DET +#ifndef TEMP_BOARD_PIN + #define TEMP_BOARD_PIN PC3 +#endif +#if TEMP_BOARD_PIN == PC3 && TEMP_SENSOR_BOARD != 13 + #warning "The built-in TEMP_SENSOR_BOARD is 13 for ERYONE Ery32 mini." +#endif + // // LCD Pins // #if HAS_WIRED_LCD #define BEEPER_PIN PE12 #define BTN_ENC PE11 - #define LCD_PINS_ENABLE PE10 + #define LCD_PINS_EN PE10 #define LCD_PINS_RS PE9 #define BTN_EN1 PE4 #define BTN_EN2 PE3 diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h index c6b65962a5d1..941f9dd183fa 100644 --- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -51,7 +51,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -60,22 +60,26 @@ // // SPI -// Note: FLSun Hispeed (clone MKS_Robin_miniV2) board is using SPI2 interface. +// +#define SPI_DEVICE 2 // Maple + +// +// SD Card SPI // #define SD_SCK_PIN PB13 // SPI2 #define SD_MISO_PIN PB14 // SPI2 #define SD_MOSI_PIN PB15 // SPI2 -#define SPI_DEVICE 2 +// // SPI Flash +// #define SPI_FLASH #if ENABLED(SPI_FLASH) - // SPI 2 + #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 // SPI2_NSS / Flash chip-select - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 - #define SPI_FLASH_SIZE 0x1000000 // 16MB + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif // @@ -128,7 +132,9 @@ #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN #define Z_SERIAL_TX_PIN PC7 // IO1 #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN - #define TMC_BAUD_RATE 19200 + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif #else // Motor current PWM pins #define MOTOR_CURRENT_PWM_XY_PIN PA6 // VREF2/3 CONTROL XY @@ -169,7 +175,6 @@ #if AXIS_DRIVER_TYPE_E0(TMC2208) || AXIS_DRIVER_TYPE_E0(TMC2209) #define E0_SERIAL_TX_PIN PA8 // IO0 #define E0_SERIAL_RX_PIN PA8 // IO0 - #define TMC_BAUD_RATE 19200 #else // Motor current PWM pins #define MOTOR_CURRENT_PWM_E_PIN PB0 // VREF1 CONTROL E @@ -191,7 +196,7 @@ #define HEATER_0_PIN PC3 // HEATER_E0 #define HEATER_BED_PIN PA0 // HEATER_BED-WKUP -#define FAN_PIN PB1 // E_FAN +#define FAN0_PIN PB1 // E_FAN // // Misc. Functions @@ -256,7 +261,7 @@ #define SD_SS_PIN -1 #define SD_DETECT_PIN PD12 // SD_CD (if -1 no detection) #else - #define SDIO_SUPPORT + #define ONBOARD_SDIO #define SDIO_CLOCK 4500000 // 4.5 MHz #define SDIO_READ_RETRIES 16 #define ONBOARD_SPI_DEVICE 1 // SPI1 @@ -267,6 +272,7 @@ // // LCD / Controller // + #ifndef BEEPER_PIN #define BEEPER_PIN PC5 #endif @@ -304,13 +310,13 @@ #define TFT_CS_PIN FSMC_CS_PIN #define TFT_RS_PIN FSMC_RS_PIN - #ifdef TFT_CLASSIC_UI + #if ENABLED(TFT_CLASSIC_UI) #define TFT_MARLINBG_COLOR 0x3186 // Grey #define TFT_MARLINUI_COLOR 0xC7B6 // Green #define TFT_BTARROWS_COLOR 0xDEE6 // Yellow #define TFT_BTOKMENU_COLOR 0x145F // Cyan #endif - #define TFT_BUFFER_SIZE 14400 + #define TFT_BUFFER_WORDS 14400 #elif HAS_GRAPHICAL_TFT diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index f39850f755f1..e31d11f40827 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -30,7 +30,7 @@ // // Flash EEPROM Emulation // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE 0x800 // 2K #define EEPROM_START_ADDRESS (0x8000000 + 256 * 1024 - 2 * EEPROM_PAGE_SIZE) // 256K firmware space @@ -83,16 +83,14 @@ #define E0_CS_PIN PC2 #endif -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI EXP2_06_PIN - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO EXP2_01_PIN - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK EXP2_02_PIN - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI EXP2_06_PIN +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO EXP2_01_PIN +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK EXP2_02_PIN #endif #if HAS_TMC_UART @@ -111,8 +109,8 @@ // #define HEATER_0_PIN PC6 #define HEATER_BED_PIN PC7 -#ifndef FAN_PIN - #define FAN_PIN PC8 +#ifndef FAN0_PIN + #define FAN0_PIN PC8 #endif #define FAN1_PIN PC9 @@ -131,30 +129,31 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_01_PIN PC14 -#define EXP1_02_PIN PC13 -#define EXP1_03_PIN PB9 -#define EXP1_04_PIN PB8 -#define EXP1_05_PIN PB7 -#define EXP1_06_PIN PB6 -#define EXP1_07_PIN PB5 -#define EXP1_08_PIN PB4 - -#define EXP2_01_PIN PB14 -#define EXP2_02_PIN PB13 -#define EXP2_03_PIN PB3 -#define EXP2_04_PIN PB12 -#define EXP2_05_PIN PD2 -#define EXP2_06_PIN PB15 -#define EXP2_07_PIN PB11 -#define EXP2_08_PIN -1 // RESET +#define EXP1_01_PIN PC14 +#define EXP1_02_PIN PC13 +#define EXP1_03_PIN PB9 +#define EXP1_04_PIN PB8 +#define EXP1_05_PIN PB7 +#define EXP1_06_PIN PB6 +#define EXP1_07_PIN PB5 +#define EXP1_08_PIN PB4 + +#define EXP2_01_PIN PB14 +#define EXP2_02_PIN PB13 +#define EXP2_03_PIN PB3 +#define EXP2_04_PIN PB12 +#define EXP2_05_PIN PD2 +#define EXP2_06_PIN PB15 +#define EXP2_07_PIN PB11 +#define EXP2_08_PIN -1 // RESET // // LCD / Controller // + #if HAS_WIRED_LCD - #define SPI_DEVICE 2 + #define SPI_DEVICE 2 // Maple #define SD_SS_PIN EXP2_04_PIN #define SD_SCK_PIN EXP2_02_PIN #define SD_MISO_PIN EXP2_01_PIN @@ -166,7 +165,7 @@ #define BEEPER_PIN EXP1_01_PIN #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #define LCD_PINS_D5 EXP1_06_PIN #define LCD_PINS_D6 EXP1_07_PIN diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h index 9250ee112762..93ef7b75d4e7 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h @@ -38,7 +38,7 @@ // // Flash EEPROM Emulation // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -118,8 +118,11 @@ #endif // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Stepper current PWM @@ -134,8 +137,8 @@ // #define HEATER_0_PIN PC7 #define HEATER_BED_PIN PC6 -#ifndef FAN_PIN - #define FAN_PIN PC8 +#ifndef FAN0_PIN + #define FAN0_PIN PC8 #endif // diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index e59e8aef595f..49b6f25a47e6 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -35,7 +35,7 @@ #define RESET_STEPPERS_ON_MEDIA_INSERT #define DISABLE_JTAG -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -104,8 +104,8 @@ // #define HEATER_0_PIN PC6 #define HEATER_BED_PIN PC7 -#ifndef FAN_PIN - #define FAN_PIN PC8 +#ifndef FAN0_PIN + #define FAN0_PIN PC8 #endif // @@ -164,7 +164,7 @@ #define DOGLCD_SCK EXP1_06_PIN #define DOGLCD_MOSI EXP1_08_PIN - #if EITHER(FYSETC_MINI_12864, U8GLIB_ST7920) + #if ANY(FYSETC_MINI_12864, U8GLIB_ST7920) #define FORCE_SOFT_SPI #endif //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 @@ -172,7 +172,7 @@ #define LCD_PINS_RS EXP1_07_PIN // CS -- SOFT SPI for ENDER3 LCD #define LCD_PINS_D4 EXP1_06_PIN // SCLK - #define LCD_PINS_ENABLE EXP1_08_PIN // DATA MOSI + #define LCD_PINS_EN EXP1_08_PIN // DATA MOSI //#define LCD_CONTRAST_INIT 190 diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h index 120d6d6f0a7b..96e90b701ca7 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h @@ -55,5 +55,8 @@ #define E0_SERIAL_RX_PIN PA3 // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h index 24981cda61f4..94c6dc2bfa6b 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h @@ -51,7 +51,7 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // Enable EEPROM Emulation for this board as it doesn't have EEPROM -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif @@ -110,7 +110,7 @@ // // These are FAN PWM pins on EXT0..EXT2 connectors. // -//#define FAN_PIN PB9 // EXT0 port +//#define FAN0_PIN PB9 // EXT0 port #define FAN1_PIN PB8 // EXT1 port #define FAN2_PIN PB7 // EXT2 port @@ -134,6 +134,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #if IS_RRD_SC @@ -143,7 +144,7 @@ // RepRapDiscount Smart Controller, but adds an FFC40 connector // #define LCD_PINS_RS PE6 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE PE14 // SID (MOSI) + #define LCD_PINS_EN PE14 // SID (MOSI) #define LCD_PINS_D4 PD8 // SCK (CLK) clock #define LCD_PINS_D5 PD9 #define LCD_PINS_D6 PD10 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h index cbe23356e38b..5f66f9bc3bb9 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h @@ -51,7 +51,7 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // Enable EEPROM Emulation for this board as it doesn't have EEPROM -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif @@ -110,7 +110,7 @@ // // These are FAN PWM pins on EXT0..EXT2 connectors. // -//#define FAN_PIN PB9 // EXT0 port +//#define FAN0_PIN PB9 // EXT0 port #define FAN1_PIN PB8 // EXT1 port #define FAN2_PIN PB7 // EXT2 port @@ -134,6 +134,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #if IS_RRD_SC @@ -144,7 +145,7 @@ // connected with a flat wire to J2 connector on the board. // #define LCD_PINS_RS PE6 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE PE14 // SID (MOSI) + #define LCD_PINS_EN PE14 // SID (MOSI) #define LCD_PINS_D4 PD8 // SCK (CLK) clock #define LCD_PINS_D5 PD9 #define LCD_PINS_D6 PD10 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h index 1418340d2dcf..9f7efa99c427 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h @@ -56,7 +56,7 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // Enable EEPROM Emulation for this board as it doesn't have EEPROM -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif @@ -115,7 +115,7 @@ // // These are FAN PWM pins on EXT0..EXT2 connectors. // -//#define FAN_PIN PB9 // EXT0 port +//#define FAN0_PIN PB9 // EXT0 port #define FAN1_PIN PB8 // EXT1 port #define FAN2_PIN PB7 // EXT2 port @@ -139,6 +139,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #if IS_RRD_SC @@ -148,7 +149,7 @@ // RepRapDiscount Smart Controller, but adds an FFC40 connector // #define LCD_PINS_RS PE6 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE PE14 // SID (MOSI) + #define LCD_PINS_EN PE14 // SID (MOSI) #define LCD_PINS_D4 PD8 // SCK (CLK) clock #define LCD_PINS_D5 PD9 #define LCD_PINS_D6 PD10 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index 22ff91aeac45..3f6ae1414bc8 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -51,7 +51,7 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // Enable EEPROM Emulation for this board as it doesn't have EEPROM -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif @@ -110,7 +110,7 @@ // // These are FAN PWM pins on EXT0..EXT2 connectors. // -//#define FAN_PIN PB9 // EXT0 port +//#define FAN0_PIN PB9 // EXT0 port #define FAN1_PIN PB8 // EXT1 port #define FAN2_PIN PB7 // EXT2 port @@ -134,6 +134,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #if IS_RRD_SC @@ -146,7 +147,7 @@ // #define LCD_PINS_RS PA12 // CS chip select /SS chip slave select // RW is hardwired to VSS - #define LCD_PINS_ENABLE PC7 // SID (MOSI) + #define LCD_PINS_EN PC7 // SID (MOSI) #define LCD_PINS_D4 PD1 // SCK (CLK) clock #define LCD_PINS_D5 PD4 #define LCD_PINS_D6 PD5 diff --git a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h index d3cf3e5cf52c..c4638cd9a975 100644 --- a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h +++ b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h @@ -104,7 +104,7 @@ #define HEATER_0_PIN PA2 #define HEATER_BED_PIN PA3 -#define FAN_PIN PA1 +#define FAN0_PIN PA1 #define FIL_RUNOUT_PIN PC7 diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index ad6b84b05769..b913532fbbdd 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -35,18 +35,18 @@ #define BOARD_NO_NATIVE_USB -//#define DISABLE_DEBUG // We still want to debug with STLINK... -#define DISABLE_JTAG // We free the jtag pins (PA15) but keep STLINK - // Release PB4 (STEP_X_PIN) from JTAG NRST role. +//#define DISABLE_DEBUG // Allow debug with STLINK... +#define DISABLE_JTAG // We free the JTAG pins (PA15) but keep STLINK + // Release PB4 (STEP_X_PIN) from JTAG NRST role. // // Limit Switches // -#define X_MIN_PIN PC1 // pin 16 -#define X_MAX_PIN PC0 // pin 15 (Filament sensor on Alfawise setup) -#define Y_MIN_PIN PC15 // pin 9 -#define Y_MAX_PIN PC14 // pin 8 (Unused in stock Alfawise setup) -#define Z_MIN_PIN PE6 // pin 5 Standard Endstop or Z_Probe endstop function -#define Z_MAX_PIN PE5 // pin 4 (Unused in stock Alfawise setup) +#define X_MIN_PIN PC1 +#define X_MAX_PIN PC0 // (Filament sensor on Alfawise setup) +#define Y_MIN_PIN PC15 +#define Y_MAX_PIN PC14 // (Unused in stock Alfawise setup) +#define Z_MIN_PIN PE6 // Standard Endstop or Z_Probe endstop function +#define Z_MAX_PIN PE5 // (Unused in stock Alfawise setup) // May be used for BLTouch Servo function on older variants (<= V08) #define ONBOARD_ENDSTOPPULLUPS @@ -60,35 +60,35 @@ // // Steppers // -#define X_ENABLE_PIN PB5 // pin 91 -#define X_STEP_PIN PB4 // pin 90 -#define X_DIR_PIN PB3 // pin 89 +#define X_ENABLE_PIN PB5 +#define X_STEP_PIN PB4 +#define X_DIR_PIN PB3 -#define Y_ENABLE_PIN PB8 // pin 95 -#define Y_STEP_PIN PB7 // pin 93 -#define Y_DIR_PIN PB6 // pin 92 +#define Y_ENABLE_PIN PB8 +#define Y_STEP_PIN PB7 +#define Y_DIR_PIN PB6 -#define Z_ENABLE_PIN PE1 // pin 98 -#define Z_STEP_PIN PE0 // pin 97 -#define Z_DIR_PIN PB9 // pin 96 +#define Z_ENABLE_PIN PE1 +#define Z_STEP_PIN PE0 +#define Z_DIR_PIN PB9 -#define E0_ENABLE_PIN PE4 // pin 3 -#define E0_STEP_PIN PE3 // pin 2 -#define E0_DIR_PIN PE2 // pin 1 +#define E0_ENABLE_PIN PE4 +#define E0_STEP_PIN PE3 +#define E0_DIR_PIN PE2 // // Temperature Sensors // -#define TEMP_0_PIN PA0 // pin 23 (Nozzle 100K/3950 thermistor) -#define TEMP_BED_PIN PA1 // pin 24 (Hot Bed 100K/3950 thermistor) +#define TEMP_0_PIN PA0 // (Nozzle 100K/3950 thermistor) +#define TEMP_BED_PIN PA1 // (Hot Bed 100K/3950 thermistor) // // Heaters / Fans // -#define HEATER_0_PIN PD3 // pin 84 (Nozzle Heat Mosfet) -#define HEATER_BED_PIN PA8 // pin 67 (Hot Bed Mosfet) +#define HEATER_0_PIN PD3 // (Nozzle Heat Mosfet) +#define HEATER_BED_PIN PA8 // (Hot Bed Mosfet) -#define FAN_PIN PA15 // pin 77 (4cm Fan) +#define FAN0_PIN PA15 // (4cm Fan) #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 @@ -104,10 +104,10 @@ #endif #endif -//#define BEEPER_PIN PD13 // pin 60 (Servo PWM output 5V/GND on Board V0G+) made for BL-Touch sensor +//#define BEEPER_PIN PD13 // (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 -#define LED_PIN PC2 // pin 17 +#define LED_PIN PC2 // Longer3D board mosfets are passing by default // Avoid nozzle heat and fan start before serial init @@ -116,7 +116,7 @@ #define BOARD_PREINIT() { \ OUT_WRITE_OD(HEATER_0_PIN, 0); \ OUT_WRITE_OD(HEATER_BED_PIN, 0); \ - OUT_WRITE_OD(FAN_PIN, 0); \ + OUT_WRITE_OD(FAN0_PIN, 0); \ } // @@ -136,23 +136,23 @@ // #if HAS_FSMC_TFT #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT - #define FSMC_CS_PIN PD7 // pin 88 = FSMC_NE1 - #define FSMC_RS_PIN PD11 // pin 58 A16 Register. Only one address needed #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 + #define FSMC_CS_PIN PD7 // FSMC_NE1 + #define FSMC_RS_PIN PD11 // A16 Register. Only one address needed #define TFT_CS_PIN FSMC_CS_PIN #define TFT_RS_PIN FSMC_RS_PIN - #define TFT_RESET_PIN PC4 // pin 33 - #define TFT_BACKLIGHT_PIN PD12 // pin 59 + #define TFT_RESET_PIN PC4 + #define TFT_BACKLIGHT_PIN PD12 #define TFT_BACKLIGHT_PWM 150 // Brightness with alt. TIM4 chan 1 (1-255) #define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h #define DOGLCD_SCK -1 // Buffer for Color UI - #define TFT_BUFFER_SIZE 3200 + #define TFT_BUFFER_WORDS 3200 #endif #if defined(TFT_BACKLIGHT_PWM) && !defined(MAPLE_STM32F1) @@ -160,7 +160,7 @@ #define LCD_BRIGHTNESS_DEFAULT TFT_BACKLIGHT_PWM #endif -#if ENABLED(SDIO_SUPPORT) +#if ENABLED(ONBOARD_SDIO) #define SD_SS_PIN -1 // else SDSS set to PA4 in M43 (spi_pins.h) #endif @@ -170,11 +170,11 @@ * declared below. */ #if NEED_TOUCH_PINS - #define TOUCH_CS_PIN PB12 // pin 51 SPI2_NSS - #define TOUCH_SCK_PIN PB13 // pin 52 - #define TOUCH_MOSI_PIN PB14 // pin 53 (Inverted MOSI/MISO = No HW SPI2) - #define TOUCH_MISO_PIN PB15 // pin 54 - #define TOUCH_INT_PIN PC6 // pin 63 (PenIRQ coming from ADS7843) + #define TOUCH_CS_PIN PB12 // SPI2_NSS + #define TOUCH_SCK_PIN PB13 + #define TOUCH_MISO_PIN PB15 // (Swapped MOSI/MISO = No HW SPI2) + #define TOUCH_MOSI_PIN PB14 + #define TOUCH_INT_PIN PC6 // (PenIRQ coming from ADS7843) #endif // @@ -183,25 +183,25 @@ // #if NO_EEPROM_SELECTED //#define SPI_EEPROM - //#define SPI_FLASH // need MARLIN_DEV_MODE for M993/M994 EEPROM backup tests + //#define SPI_FLASH // Use MARLIN_DEV_MODE for M993/M994 EEPROM backup tests #define FLASH_EEPROM_EMULATION #endif #if ENABLED(SPI_EEPROM) // SPI1 EEPROM Winbond W25Q64 (8MB/64Mbits) #define SPI_CHAN_EEPROM1 1 - #define SPI_EEPROM1_CS_PIN PC5 // pin 34 - #define EEPROM_SCK_PIN BOARD_SPI1_SCK_PIN // PA5 pin 30 - #define EEPROM_MISO_PIN BOARD_SPI1_MISO_PIN // PA6 pin 31 - #define EEPROM_MOSI_PIN BOARD_SPI1_MOSI_PIN // PA7 pin 32 + #define SPI_EEPROM1_CS_PIN PC5 + #define EEPROM_SCK_PIN BOARD_SPI1_SCK_PIN // PA5 + #define EEPROM_MISO_PIN BOARD_SPI1_MISO_PIN // PA6 + #define EEPROM_MOSI_PIN BOARD_SPI1_MOSI_PIN // PA7 #define EEPROM_PAGE_SIZE 0x1000U // 4K (from datasheet) - #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64K for now... + #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64K for now... #elif ENABLED(SPI_FLASH) - #define SPI_FLASH_SIZE 0x40000U // limit to 256K (M993 will reboot with 512) + #define SPI_FLASH_SIZE 0x40000U // Limit to 256K (M993 will reboot with 512) #define SPI_FLASH_CS_PIN PC5 - #define SPI_FLASH_MOSI_PIN PA7 - #define SPI_FLASH_MISO_PIN PA6 #define SPI_FLASH_SCK_PIN PA5 + #define SPI_FLASH_MISO_PIN PA6 + #define SPI_FLASH_MOSI_PIN PA7 #elif ENABLED(FLASH_EEPROM_EMULATION) // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) #define EEPROM_PAGE_SIZE (0x800U) // 2K 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 f157c8e45544..233d6f1d37b1 100644 --- a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h @@ -51,22 +51,22 @@ #define E2END 0xFFFF // EEPROM end address AT24C256 (32kB) */ -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE 0x800U // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple // // Limit Switches // #define X_MIN_PIN PD6 -#define X_MAX_PIN PG15 // To double check +#define X_MAX_PIN PG15 // To double check #define Y_MIN_PIN PG9 -#define Y_MAX_PIN PG14 // To double check +#define Y_MAX_PIN PG14 // To double check #define Z_MIN_PIN PG10 #define Z_MAX_PIN PG13 @@ -111,7 +111,7 @@ #define HEATER_0_PIN PB0 #define HEATER_BED_PIN PB1 -#define FAN_PIN PA0 // FAN +#define FAN0_PIN PA0 // FAN // // SD Card @@ -120,7 +120,7 @@ #define SDCARD_CONNECTION ONBOARD #endif -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define SDIO_CLOCK 4500000 // 4.5 MHz #define SDIO_READ_RETRIES 16 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index be5f6c740482..20df1b8c5c17 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -116,7 +116,7 @@ // // Fan // -#define FAN_PIN PA7 // FAN +#define FAN0_PIN PA7 // FAN // // Thermocouples @@ -184,7 +184,7 @@ #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 - #define TFT_BUFFER_SIZE 14400 + #define TFT_BUFFER_WORDS 14400 #endif #if NEED_TOUCH_PINS @@ -197,12 +197,12 @@ // SPI2 is shared by LCD touch driver and flash // SPI1(PA7) & SPI3(PB5) not available -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define SDIO_CLOCK 4500000 #define SDIO_READ_RETRIES 16 -#if ENABLED(SDIO_SUPPORT) +#if ENABLED(ONBOARD_SDIO) #define SD_SCK_PIN PB13 // SPI2 #define SD_MISO_PIN PB14 // SPI2 #define SD_MOSI_PIN PB15 // SPI2 @@ -276,7 +276,7 @@ #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x800000 // 8MB #define SPI_FLASH_CS_PIN PG9 - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h index 77c2b792157a..6d8889733215 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h @@ -50,18 +50,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB15 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB14 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB13 #endif #include "pins_MKS_ROBIN_E3_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h index 2ad68a01405c..89fda7ab6799 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h @@ -50,18 +50,17 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers +// Software and hardware actually, they are connected to SPI2 bus. // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB15 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB14 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB13 #endif #include "pins_MKS_ROBIN_E3_V1_1_common.h" // ... MKS_ROBIN_E3_common diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 89525d93ef48..b4cec047d189 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -52,15 +52,15 @@ //#define FLASH_EEPROM_EMULATION //#define SDCARD_EEPROM_EMULATION -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM // EEPROM on I2C-0 #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // -// Note: MKS Robin board is using SPI2 interface. +// SPI // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple // // Servos @@ -112,18 +112,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PD14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PD1 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PD0 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PD14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PD1 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PD0 #endif #if HAS_TMC_UART @@ -158,7 +156,10 @@ #define E0_SERIAL_RX_PIN PD9 // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + #endif // HAS_TMC_UART // @@ -173,7 +174,7 @@ #define HEATER_0_PIN PC3 // HEATER1 #define HEATER_BED_PIN PA0 // HOT BED -#define FAN_PIN PB1 // FAN +#define FAN0_PIN PB1 // FAN // // Misc. Functions @@ -241,7 +242,7 @@ #endif #if SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT + #define ONBOARD_SDIO #define SDIO_CLOCK 4500000 // 4.5 MHz #define SD_DETECT_PIN PD12 #define ONBOARD_SD_CS_PIN PC11 @@ -264,6 +265,17 @@ * to let the bootloader init the screen. */ +#if ENABLED(TFT_CLASSIC_UI) + // Emulated DOGM SPI + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN +#elif ENABLED(TFT_COLOR_UI) + #define TFT_BUFFER_WORDS 14400 +#endif + #if HAS_SPI_TFT // Shared SPI TFT @@ -294,27 +306,16 @@ #define LCD_USE_DMA_SPI -#endif +#elif HAS_WIRED_LCD + + #define BEEPER_PIN EXP1_01_PIN -#if ENABLED(TFT_CLASSIC_UI) - // Emulated DOGM SPI - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_RS EXP1_04_PIN #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN -#elif ENABLED(TFT_COLOR_UI) - #define TFT_BUFFER_SIZE 14400 -#endif -#if HAS_WIRED_LCD && !HAS_SPI_TFT - #define BEEPER_PIN EXP1_01_PIN - #define BTN_ENC EXP1_02_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN - #define LCD_BACKLIGHT_PIN -1 #if ENABLED(MKS_MINI_12864) @@ -355,7 +356,7 @@ #endif //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 - #else // !MKS_MINI_12864 + #else // !FYSETC_MINI_12864_2_1 #define LCD_PINS_D4 EXP1_05_PIN #if IS_ULTIPANEL @@ -373,21 +374,21 @@ #define BOARD_ST7920_DELAY_2 125 #define BOARD_ST7920_DELAY_3 125 - #endif // !MKS_MINI_12864 + #endif // !FYSETC_MINI_12864_2_1 #endif // HAS_WIRED_LCD && !HAS_SPI_TFT +#ifndef BEEPER_PIN + #define BEEPER_PIN EXP1_01_PIN +#endif + #define SPI_FLASH #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 -#endif - -#ifndef BEEPER_PIN - #define BEEPER_PIN EXP1_01_PIN + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif #if ENABLED(SPEAKER) && BEEPER_PIN == PC5 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h index 31e034e025e9..9fa5ec6b31d1 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h @@ -34,6 +34,6 @@ #define Z_STEP_PIN PC14 #define Z_DIR_PIN PC15 -#define BTN_ENC_EN -1 +#define BTN_ENC_EN -1 #include "pins_MKS_ROBIN_E3_common.h" 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 642c97bb1144..4cf83765f210 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -38,7 +38,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -112,14 +112,17 @@ #define E0_SERIAL_RX_PIN PC11 // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Heaters 0,1 / Fans / Bed // #define HEATER_0_PIN PC9 -#define FAN_PIN PA8 +#define FAN0_PIN PA8 #define HEATER_BED_PIN PC8 // @@ -165,13 +168,13 @@ #define EXP2_05_PIN PB0 #define EXP2_06_PIN PB15 #define EXP2_07_PIN PC10 -#define EXP2_08_PIN -1 // RESET +#define EXP2_08_PIN -1 // RESET // "Ender-3 EXP1" #define EXP3_01_PIN PC1 #define EXP3_02_PIN PC3 #define EXP3_03_PIN PB11 -#define EXP3_04_PIN -1 // RESET +#define EXP3_04_PIN -1 // RESET #define EXP3_05_PIN PB0 #define EXP3_06_PIN PA6 #define EXP3_07_PIN PA5 @@ -181,7 +184,7 @@ #define BEEPER_PIN EXP1_01_PIN #define BTN_ENC EXP1_02_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_RS EXP1_04_PIN #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN @@ -210,7 +213,7 @@ #define SOFTWARE_SPI //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 - #else + #else // !FYSETC_MINI_12864_2_1 #define LCD_PINS_D4 EXP1_05_PIN #if IS_ULTIPANEL @@ -224,7 +227,7 @@ #endif - #endif // !MKS_MINI_12864 + #endif // !FYSETC_MINI_12864_2_1 #endif // HAS_WIRED_LCD @@ -250,11 +253,11 @@ // SD Card // #define SDCARD_CONNECTION ONBOARD -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple #define ONBOARD_SPI_DEVICE 2 #define SDSS SD_SS_PIN #define ONBOARD_SD_CS_PIN SD_SS_PIN -#define SD_DETECT_PIN PC10 // EXP2_07_PIN +#define SD_DETECT_PIN EXP2_07_PIN #define NO_SD_HOST_DRIVE // TODO: This is the only way to set SPI for SD on STM32 (for now) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index 7ead6aa28820..50e241901837 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -68,7 +68,7 @@ // Heaters / Fans // #define HEATER_0_PIN PC9 -#define FAN_PIN PA8 +#define FAN0_PIN PA8 #define HEATER_BED_PIN PC8 // @@ -80,9 +80,9 @@ #define FIL_RUNOUT_PIN PB8 // MT_DET /** ------ - * (BEEPER) PD2 | 1 2 | PB3 (BTN_ENC) - * (BTN_EN1) PB5 | 3 4 | PA11 (RESET?) - * (BTN_EN2) PB4 5 6 | PC1 (LCD_D4) + * (BEEPER) PD2 | 1 2 | PB3 (ENC) + * (EN1) PB5 | 3 4 | PA11 (RESET?) + * (EN2) PB4 5 6 | PC1 (LCD_D4) * (LCD_RS) PC3 | 7 8 | PC2 (LCD_EN) * GND | 9 10 | 5V * ------ @@ -110,7 +110,7 @@ #define BTN_EN1 EXP3_03_PIN #define BTN_EN2 EXP3_05_PIN - #define LCD_PINS_ENABLE EXP3_08_PIN + #define LCD_PINS_EN EXP3_08_PIN #if ENABLED(MKS_MINI_12864) @@ -121,7 +121,7 @@ #define DOGLCD_SCK PB13 #define DOGLCD_MOSI PB15 - #else // !MKS_MINI_12864 + #else // !MKS_MINI_12864 #define LCD_PINS_D4 EXP3_06_PIN #if IS_ULTIPANEL @@ -156,7 +156,7 @@ // // SPI // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple #define SD_SCK_PIN PB13 #define SD_MISO_PIN PB14 #define SD_MOSI_PIN PB15 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h index b1aaa53c9487..03be44bba64a 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h @@ -82,7 +82,7 @@ // #define HEATER_0_PIN PC9 #define HEATER_1_PIN PC7 -#define FAN_PIN PA8 +#define FAN0_PIN PA8 #define HEATER_BED_PIN PC8 // @@ -101,7 +101,7 @@ #define BEEPER_PIN PC1 #define BTN_ENC PC3 - #define LCD_PINS_ENABLE PA4 + #define LCD_PINS_EN PA4 #define LCD_PINS_RS PA5 #define BTN_EN1 PB11 #define BTN_EN2 PB0 @@ -122,7 +122,7 @@ #define TFTGLCD_CS PB11 #endif - #else // !MKS_MINI_12864 + #else // !MKS_MINI_12864 #define LCD_PINS_D4 PA6 #if IS_ULTIPANEL @@ -152,7 +152,7 @@ // // SPI // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple #define SD_SCK_PIN PB13 #define SD_MISO_PIN PB14 #define SD_MOSI_PIN PB15 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h index 59441dc80609..b39a2660b21b 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h @@ -43,14 +43,14 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple // // Servos @@ -111,7 +111,7 @@ #define HEATER_0_PIN PC3 #define HEATER_BED_PIN PA0 -#define FAN_PIN PB1 // FAN +#define FAN0_PIN PB1 // FAN // // Misc. Functions @@ -133,7 +133,7 @@ #define SDCARD_CONNECTION ONBOARD #endif -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define SDIO_CLOCK 4500000 // 4.5 MHz #define SD_DETECT_PIN PD12 #define ONBOARD_SPI_DEVICE 1 // SPI1 @@ -149,31 +149,32 @@ * If the screen stays white, disable 'LCD_RESET_PIN' * to let the bootloader init the screen. */ -#if EITHER(HAS_FSMC_GRAPHICAL_TFT, TFT_320x240) - #define FSMC_CS_PIN PD7 // NE4 - #define FSMC_RS_PIN PD11 // A0 +#if HAS_FSMC_TFT - #define TFT_CS_PIN FSMC_CS_PIN - #define TFT_RS_PIN FSMC_RS_PIN + #define TFT_CS_PIN PD7 // NE4 + #define TFT_RS_PIN PD11 // A0 + #define LCD_RESET_PIN PC6 // FSMC_RST + #define LCD_BACKLIGHT_PIN PD13 + + #define FSMC_CS_PIN TFT_CS_PIN // NE4 + #define FSMC_RS_PIN TFT_RS_PIN // A0 #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 - #define LCD_RESET_PIN PC6 // FSMC_RST - #define LCD_BACKLIGHT_PIN PD13 -#endif + #if NEED_TOUCH_PINS + #define TOUCH_CS_PIN PC2 // SPI2_NSS + #define TOUCH_SCK_PIN PB13 // SPI2_SCK + #define TOUCH_MISO_PIN PB14 // SPI2_MISO + #define TOUCH_MOSI_PIN PB15 // SPI2_MOSI + #endif -#if BOTH(NEED_TOUCH_PINS, HAS_FSMC_GRAPHICAL_TFT) || ENABLED(TFT_320x240) - #define TOUCH_CS_PIN PC2 // SPI2_NSS - #define TOUCH_SCK_PIN PB13 // SPI2_SCK - #define TOUCH_MISO_PIN PB14 // SPI2_MISO - #define TOUCH_MOSI_PIN PB15 // SPI2_MOSI #endif #if ENABLED(TFT_320x240) // TFT32/28 #define TFT_DRIVER ILI9341 - #define TFT_BUFFER_SIZE 14400 + #define TFT_BUFFER_WORDS 14400 #define ILI9341_COLOR_RGB // YV for normal screen mounting #define ILI9341_ORIENTATION ILI9341_MADCTL_MY | ILI9341_MADCTL_MV @@ -200,7 +201,7 @@ #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 // Flash chip-select - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif 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 8dba94313651..b83a52a17380 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -54,15 +54,15 @@ //#define FLASH_EEPROM_EMULATION //#define SDCARD_EEPROM_EMULATION -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM // EEPROM on I2C-0 #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif // -// Note: MKS Robin board is using SPI2 interface. +// SPI // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple // // Servos @@ -122,18 +122,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PD14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PD1 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PD0 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PD14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PD1 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PD0 #endif #if HAS_TMC_UART @@ -165,7 +163,10 @@ #define E1_SERIAL_RX_PIN PD8 // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + #endif // HAS_TMC_UART // @@ -182,7 +183,7 @@ #define HEATER_1_PIN PB0 // HEATER2 #define HEATER_BED_PIN PA0 // HOT BED -#define FAN_PIN PB1 // FAN +#define FAN0_PIN PB1 // FAN // // Thermocouples @@ -241,19 +242,47 @@ #endif #if SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT + #define ONBOARD_SDIO #define SDIO_CLOCK 4500000 // 4.5 MHz #define SD_DETECT_PIN PD12 #define ONBOARD_SD_CS_PIN PC11 #elif SD_CONNECTION_IS(LCD) #define ENABLE_SPI1 - #define SDSS PE10 - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PE12 + #define SDSS EXP2_04_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN + #define SD_DETECT_PIN EXP2_07_PIN #endif +/** + * ------ ------ + * PC5 | 1 2 | PE13 PA6 | 1 2 | PA5 + * PD13 | 3 4 | PC6 PE8 | 3 4 | PE10 + * PE14 | 5 6 PE15 PE11 | 5 6 PA7 + * PD11 | 7 8 | PD10 PE12 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 3.3V + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_01_PIN PC5 +#define EXP1_02_PIN PE13 +#define EXP1_03_PIN PD13 +#define EXP1_04_PIN PC6 +#define EXP1_05_PIN PE14 +#define EXP1_06_PIN PE15 +#define EXP1_07_PIN PD11 +#define EXP1_08_PIN PD10 + +#define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PE8 +#define EXP2_04_PIN PE10 +#define EXP2_05_PIN PE11 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PE12 +#define EXP2_08_PIN -1 // RESET + // // LCD / Controller // @@ -264,29 +293,40 @@ * to let the bootloader init the screen. */ +#if ENABLED(TFT_CLASSIC_UI) + // Emulated DOGM SPI + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN +#elif ENABLED(TFT_COLOR_UI) + #define TFT_BUFFER_WORDS 14400 +#endif + #if HAS_SPI_TFT // Shared SPI TFT - #define LCD_BACKLIGHT_PIN PD13 + #define LCD_BACKLIGHT_PIN EXP1_03_PIN - #define TOUCH_CS_PIN PE14 // SPI1_NSS - #define TOUCH_SCK_PIN PA5 // SPI1_SCK - #define TOUCH_MISO_PIN PA6 // SPI1_MISO - #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI + #define TOUCH_CS_PIN EXP1_05_PIN // SPI1_NSS + #define TOUCH_SCK_PIN EXP2_02_PIN // SPI1_SCK + #define TOUCH_MISO_PIN EXP2_01_PIN // SPI1_MISO + #define TOUCH_MOSI_PIN EXP2_06_PIN // SPI1_MOSI - #define BTN_EN1 PE8 - #define BTN_EN2 PE11 - #define BTN_ENC PE13 + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN - #define TFT_CS_PIN PD11 - #define TFT_SCK_PIN PA5 - #define TFT_MISO_PIN PA6 - #define TFT_MOSI_PIN PA7 - #define TFT_DC_PIN PD10 + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + #define TFT_DC_PIN EXP1_08_PIN #define TFT_A0_PIN TFT_DC_PIN - #define TFT_RESET_PIN PC6 + #define TFT_RESET_PIN EXP1_04_PIN #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN #define TOUCH_BUTTONS_HW_SPI @@ -294,27 +334,16 @@ #define LCD_USE_DMA_SPI -#endif +#elif HAS_WIRED_LCD -#if ENABLED(TFT_CLASSIC_UI) - // Emulated DOGM SPI - #define LCD_PINS_ENABLE PD13 - #define LCD_PINS_RS PC6 - #define BTN_ENC PE13 - #define BTN_EN1 PE8 - #define BTN_EN2 PE11 -#elif ENABLED(TFT_COLOR_UI) - #define TFT_BUFFER_SIZE 14400 -#endif + #define BEEPER_PIN EXP1_01_PIN + + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN -#if HAS_WIRED_LCD && !HAS_SPI_TFT - #define BEEPER_PIN PC5 - #define BTN_ENC PE13 - #define LCD_PINS_ENABLE PD13 - #define LCD_PINS_RS PC6 - #define BTN_EN1 PE8 - #define BTN_EN2 PE11 - #define LCD_BACKLIGHT_PIN -1 + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN #if ENABLED(MKS_MINI_12864) @@ -323,18 +352,18 @@ #define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN -1 - #define DOGLCD_A0 PD11 - #define DOGLCD_CS PE15 - #define DOGLCD_SCK PA5 - #define DOGLCD_MOSI PA7 + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN #elif IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define PIN_SPI_SCK PA5 - #define PIN_TFT_MISO PA6 - #define PIN_TFT_MOSI PA7 - #define TFTGLCD_CS PE8 + #define PIN_SPI_SCK EXP2_02_PIN + #define PIN_TFT_MISO EXP2_01_PIN + #define PIN_TFT_MOSI EXP2_06_PIN + #define TFTGLCD_CS EXP2_03_PIN #endif #ifndef BEEPER_PIN @@ -342,26 +371,26 @@ #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define LCD_PINS_DC PC6 - #define DOGLCD_CS PD13 + #define LCD_PINS_DC EXP1_04_PIN + #define DOGLCD_CS EXP1_03_PIN #define DOGLCD_A0 DOGLCD_A0 #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN PE14 - #define NEOPIXEL_PIN PE15 - #define DOGLCD_MOSI PA7 - #define DOGLCD_SCK PA5 + #define LCD_RESET_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN + #define DOGLCD_MOSI EXP2_06_PIN + #define DOGLCD_SCK EXP2_02_PIN #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 - #else // !MKS_MINI_12864 + #else // !FYSETC_MINI_12864_2_1 - #define LCD_PINS_D4 PE14 + #define LCD_PINS_D4 EXP1_05_PIN #if IS_ULTIPANEL - #define LCD_PINS_D5 PE15 - #define LCD_PINS_D6 PD11 - #define LCD_PINS_D7 PD10 + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -375,7 +404,7 @@ #define BOARD_ST7920_DELAY_3 125 #endif - #endif // !MKS_MINI_12864 + #endif // !FYSETC_MINI_12864_2_1 #endif // HAS_WIRED_LCD && !HAS_SPI_TFT @@ -383,13 +412,13 @@ #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif #ifndef BEEPER_PIN - #define BEEPER_PIN PC5 + #define BEEPER_PIN EXP1_01_PIN #endif #if ENABLED(SPEAKER) && BEEPER_PIN == PC5 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 858dabb8b986..2b5014096e73 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h @@ -42,14 +42,14 @@ #if ENABLED(SRAM_EEPROM_EMULATION) #undef NO_EEPROM_SELECTED #endif -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple // // Servos @@ -105,8 +105,8 @@ #ifndef HEATER_0_PIN #define HEATER_0_PIN PC3 #endif -#ifndef FAN_PIN - #define FAN_PIN PB1 // FAN +#ifndef FAN0_PIN + #define FAN0_PIN PB1 // FAN #endif #ifndef HEATER_BED_PIN #define HEATER_BED_PIN PA0 @@ -163,7 +163,7 @@ #define SDCARD_CONNECTION ONBOARD #endif -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define SDIO_CLOCK 4500000 // 4.5 MHz #define SD_DETECT_PIN PD12 #define ONBOARD_SD_CS_PIN PC11 @@ -205,14 +205,14 @@ #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 - #define TFT_BUFFER_SIZE 14400 + #define TFT_BUFFER_WORDS 14400 #endif #define SPI_FLASH #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 048570102baf..ad4e45c70fc9 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -22,7 +22,8 @@ #pragma once /** - * MKS Robin pro (STM32F103ZET6) board pin assignments + * MKS Robin Pro (STM32F103ZET6) board pin assignments + * Schematic: https://github.com/makerbase-mks/MKS-Robin-Pro/blob/master/hardware/MKS%20Robin%20Pro%20V1.0_001/MKS%20Robin%20Pro%20V1.0_001%20SCH.pdf */ #include "env_validate.h" @@ -41,9 +42,9 @@ #define DISABLE_DEBUG // -// Note: MKS Robin board is using SPI2 interface. +// SPI // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple // // Servos @@ -104,19 +105,18 @@ #ifndef E2_CS_PIN #define E2_CS_PIN PG9 #endif + // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB15 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB14 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB13 #endif #if HAS_TMC_UART @@ -167,11 +167,11 @@ #define HEATER_1_PIN PB0 // +HE1- #define HEATER_2_PIN PF9 // +HE2- #define HEATER_BED_PIN PA0 // +HOT-BED- -#define FAN_PIN PB1 // +FAN- +#define FAN0_PIN PB1 // +FAN- -/** - * Note: MKS Robin Pro board is using SPI2 interface. Make sure your stm32duino library is configured accordingly - */ +// +// Note: Using SPI2 interface. Make sure stm32duino is configured accordingly +// //#define TEMP_0_CS_PIN PE5 // TC1 - CS1 //#define TEMP_0_CS_PIN PF11 // TC2 - CS2 @@ -206,19 +206,101 @@ #endif #if SD_CONNECTION_IS(LCD) - #define SD_DETECT_PIN PG3 - #define SD_SCK_PIN PB13 - #define SD_MISO_PIN PB14 - #define SD_MOSI_PIN PB15 - #define SD_SS_PIN PG6 + #define SD_DETECT_PIN EXP2_07_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN + #define SD_SS_PIN EXP2_04_PIN #elif SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT + #define ONBOARD_SDIO #define SD_DETECT_PIN PD12 #define ONBOARD_SD_CS_PIN PC11 #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif +/** ------ ------ + * (BEEPER) PC5 | 1 2 | PG2 (BTN_ENC) (MISO) PB14 | 1 2 | PB13 (SCK) + * (LCD_EN) PG0 | 3 4 | PG1 (LCD_RS) (BTN_EN1) PG5 | 3 4 | PG6 (SD_SS) + * (LCD_D4) PF14 5 6 | PF15 (LCD_D5) (BTN_EN2) PG4 5 6 | PB15 (MOSI) + * (LCD_D6) PF12 | 7 8 | PF13 (LCD_D7) (SD_DETECT) PG3 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_01_PIN PC5 +#define EXP1_02_PIN PG2 +#define EXP1_03_PIN PG0 +#define EXP1_04_PIN PG1 +#define EXP1_05_PIN PF14 +#define EXP1_06_PIN PF15 +#define EXP1_07_PIN PF12 +#define EXP1_08_PIN PF13 + +#define EXP2_01_PIN PB14 +#define EXP2_02_PIN PB13 +#define EXP2_03_PIN PG5 +#define EXP2_04_PIN PG6 +#define EXP2_05_PIN PG4 +#define EXP2_06_PIN PB15 +#define EXP2_07_PIN PG3 +#define EXP2_08_PIN -1 // RESET + +/** ------- + * | 0 | DGND-| + * 3V3 | 1 2 | DGND-| + * (D0) PD14 | 3 4 | PD15 (D1) + * (D2) PD0 | 5 6 | PD1 (D3) + * (D4) PE7 | 7 8 | PE8 (D5) + * (D6) PE9 | 9 10 | PE10 (D7) + * (D8) PE11 | 11 12 | PE12 (D9) + * (D10) PE13 | 13 14 | PE14 (D11) + * (D12) PE15 | 15 16 | PD8 (D13) + * (D14) PD9 | 17 18 | PD10 (D15) + * (NE4) PD7 | 19 20 | PD11 (A0) + * (NWE) PD5 | 21 22 | PD4 (NOE) + * (RST) PC6? | 23 24 | PD13?(LIGHT) + * (MISO2) PB14 | 25 26 | --- (INT) + * (MOSI2) PB15 | 27 28 | PC5 (BEEPER) + * (SCK2) PB13 | 29 30 | VCC + * (NSS2) PA7 | 31 32 | DGND + * ------- + * FSMC + */ +//#define FSMC_00_PIN -1 // GND +//#define FSMC_01_PIN -1 // 3.3V +//#define FSMC_02_PIN -1 // GND +#define FSMC_03_PIN PD14 // D0 +#define FSMC_04_PIN PD15 // D1 +#define FSMC_05_PIN PD0 // D2 +#define FSMC_06_PIN PD1 // D3 +#define FSMC_07_PIN PE7 // D4 +#define FSMC_08_PIN PE8 // D5 +#define FSMC_09_PIN PE9 // D6 +#define FSMC_10_PIN PE10 // D7 +#define FSMC_11_PIN PE11 // D8 +#define FSMC_12_PIN PE12 // D9 +#define FSMC_13_PIN PE13 // D10 +#define FSMC_14_PIN PE14 // D11 +#define FSMC_15_PIN PE15 // D12 +#define FSMC_16_PIN PD8 // D13 +#define FSMC_17_PIN PD9 // D14 +#define FSMC_18_PIN PD10 // D15 +#define FSMC_19_PIN PD7 // NE4 +#define FSMC_20_PIN PD11 // A0 +#define FSMC_21_PIN PD5 // NWE +#define FSMC_22_PIN PD4 // NOE +#define FSMC_23_PIN PC6 // RST +#define FSMC_24_PIN PD13 // LIGHT +#define FSMC_25_PIN PB14 // MISO2 +#define FSMC_26_PIN -1 // INT +#define FSMC_27_PIN PB15 // MOSI2 +#define FSMC_28_PIN PC5 // BEEPER +#define FSMC_29_PIN PB13 // SCK2 +//#define FSMC_30_PIN -1 // VCC +#define FSMC_31_PIN PA7 // NSS2 +//#define FSMC_32_PIN -1 // GND + // // TFT with FSMC interface // @@ -231,31 +313,31 @@ #define TFT_RESET_PIN LCD_RESET_PIN #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN - #define FSMC_CS_PIN PD7 // NE4 - #define FSMC_RS_PIN PD11 // A0 #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 + #define FSMC_CS_PIN FSMC_19_PIN // NE4 + #define FSMC_RS_PIN FSMC_20_PIN // A0 #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT #define TFT_CS_PIN FSMC_CS_PIN #define TFT_RS_PIN FSMC_RS_PIN - #define LCD_RESET_PIN PC6 - #define LCD_BACKLIGHT_PIN PD13 + #define LCD_RESET_PIN FSMC_23_PIN + #define LCD_BACKLIGHT_PIN FSMC_24_PIN - #define TFT_BUFFER_SIZE 14400 + #define TFT_BUFFER_WORDS 14400 #if NEED_TOUCH_PINS #define TOUCH_BUTTONS_HW_SPI #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 - #define TOUCH_CS_PIN PA7 // SPI2_NSS - #define TOUCH_SCK_PIN PB13 // SPI2_SCK - #define TOUCH_MISO_PIN PB14 // SPI2_MISO - #define TOUCH_MOSI_PIN PB15 // SPI2_MOSI + #define TOUCH_CS_PIN FSMC_31_PIN // SPI2_NSS + #define TOUCH_SCK_PIN FSMC_29_PIN // SPI2_SCK + #define TOUCH_MISO_PIN FSMC_25_PIN // SPI2_MISO + #define TOUCH_MOSI_PIN FSMC_27_PIN // SPI2_MOSI #else - #define BEEPER_PIN PC5 - #define BTN_ENC PG2 - #define BTN_EN1 PG5 - #define BTN_EN2 PG4 + #define BEEPER_PIN FSMC_28_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #endif #elif IS_TFTGLCD_PANEL @@ -266,30 +348,30 @@ #elif HAS_WIRED_LCD - #define BEEPER_PIN PC5 - #define BTN_ENC PG2 - #define LCD_PINS_ENABLE PG0 - #define LCD_PINS_RS PG1 - #define BTN_EN1 PG5 - #define BTN_EN2 PG4 + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN // MKS MINI12864 and MKS LCD12864B. If using MKS LCD12864A (Need to remove RPK2 resistor) - #if ENABLED(MKS_MINI_12864) + #if ANY(ENDER2_STOCKDISPLAY, MKS_MINI_12864) #define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN -1 - #define DOGLCD_A0 PF12 - #define DOGLCD_CS PF15 - #define DOGLCD_SCK PB13 - #define DOGLCD_MOSI PB15 + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN - #else // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY + #else // !ENDER2_STOCKDISPLAY && !MKS_MINI_12864 #define LCD_PINS_D4 PF14 #if IS_ULTIPANEL - #define LCD_PINS_D5 PF15 - #define LCD_PINS_D6 PF12 - #define LCD_PINS_D7 PF13 + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -297,9 +379,9 @@ #endif - #endif // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY + #endif -#endif +#endif // HAS_WIRED_LCD // Alter timing for graphical display #if IS_U8GLIB_ST7920 @@ -312,7 +394,7 @@ #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 // Flash chip-select - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MORPHEUS.h b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h index 87919c12f488..08e5455b3098 100644 --- a/Marlin/src/pins/stm32f1/pins_MORPHEUS.h +++ b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h @@ -82,7 +82,7 @@ #define HEATER_0_PIN PA2 // HOTEND MOSFET #define HEATER_BED_PIN PA0 // BED MOSFET -#define FAN_PIN PA1 // FAN1 header on board - PRINT FAN +#define FAN0_PIN PA1 // FAN1 header on board - PRINT FAN // // Misc. diff --git a/Marlin/src/pins/stm32f1/pins_ORCA_3D_SPRINGER.h b/Marlin/src/pins/stm32f1/pins_ORCA_3D_SPRINGER.h new file mode 100644 index 000000000000..a376feb93a74 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_ORCA_3D_SPRINGER.h @@ -0,0 +1,342 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 + +/** + * ORCA 3D Modular Controller (STM32F103VCT6) board pin assignments + */ + +#if NOT_TARGET(__STM32F1__, STM32F1) + #error "Oops! Select an STM32F1 board in 'Tools > Board.'" +#endif + +#define BOARD_INFO_NAME "ORCA 3D Modular Controller" + +// Avoid conflict with TIMER_SERVO when using the STM32 HAL +#define TEMP_TIMER 5 + +// +// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role +// +#define DISABLE_DEBUG + +// +// Servos +// +#define SERVO0_PIN PA8 // Enable BLTOUCH + +// +// Limit Switches +// +#define X_STOP_PIN PA15 +#define Y_STOP_PIN PA14 +#define Z_STOP_PIN PA12 + +// +// Steppers +// +#define X_ENABLE_PIN PC15 +#define X_STEP_PIN PE5 +#define X_DIR_PIN PE6 +#ifndef X_CS_PIN + #define X_CS_PIN PE3 +#endif + +#define Y_ENABLE_PIN PC15 +#define Y_STEP_PIN PC14 +#define Y_DIR_PIN PC13 +#ifndef Y_CS_PIN + #define Y_CS_PIN PE4 +#endif + +#define Z_ENABLE_PIN PB4 +#define Z_STEP_PIN PB5 +#define Z_DIR_PIN PB6 +#ifndef Z_CS_PIN + #define Z_CS_PIN PB3 +#endif + +#define E0_ENABLE_PIN PE2 +#define E0_STEP_PIN PE1 +#define E0_DIR_PIN PE0 +#ifndef E0_CS_PIN + #define E0_CS_PIN PB7 +#endif + +#define E1_ENABLE_PIN PB11 +#define E1_STEP_PIN PC7 +#define E1_DIR_PIN PC6 +#ifndef E1_CS_PIN + #define E1_CS_PIN PD15 +#endif + +#define E2_ENABLE_PIN PD7 +#define E2_STEP_PIN PD6 +#define E2_DIR_PIN PD5 +#ifndef E2_CS_PIN + #define E2_CS_PIN PD4 +#endif + +#define E3_ENABLE_PIN PD14 +#define E3_STEP_PIN PD13 +#define E3_DIR_PIN PC5 +#ifndef E3_CS_PIN + #define E3_CS_PIN PD11 +#endif + +#define E4_ENABLE_PIN PD3 +#define E4_STEP_PIN PE14 +#define E4_DIR_PIN PD9 +#ifndef E4_CS_PIN + #define E4_CS_PIN PD8 +#endif + +// +// SPI pins for TMC2130 stepper drivers +// +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB15 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB14 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB13 +#endif + +#if HAS_TMC_UART + /** + * TMC2208/TMC2209 stepper drivers + * + * Hardware serial communication ports. + * If undefined software serial is used according to the pins below + */ + //#define X_HARDWARE_SERIAL MSerial1 + //#define Y_HARDWARE_SERIAL MSerial1 + //#define Z_HARDWARE_SERIAL MSerial1 + //#define E0_HARDWARE_SERIAL MSerial1 + //#define E1_HARDWARE_SERIAL MSerial1 + + #define X_SERIAL_TX_PIN PE3 + #define X_SERIAL_RX_PIN PE3 + + #define Y_SERIAL_TX_PIN PE4 + #define Y_SERIAL_RX_PIN PE4 + + #define Z_SERIAL_TX_PIN PB3 + #define Z_SERIAL_RX_PIN PB3 + + #define E0_SERIAL_TX_PIN PB7 + #define E0_SERIAL_RX_PIN PB7 + + #define E1_SERIAL_TX_PIN PD15 + #define E1_SERIAL_RX_PIN PD15 + + #define E2_SERIAL_TX_PIN PD11 + #define E2_SERIAL_RX_PIN PD11 + + #define E3_SERIAL_TX_PIN PD8 + #define E3_SERIAL_RX_PIN PD8 + + // Reduce baud rate to improve software serial reliability + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC1 // TH1 +#define TEMP_1_PIN PC2 // TH2 +#define TEMP_2_PIN PC3 // TH2 +#define TEMP_3_PIN PC4 // TH2 +#define TEMP_BED_PIN PC0 // TB1 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PB1 // HEATER1 +#define HEATER_1_PIN PB2 // HEATER2 +#define HEATER_2_PIN PB10 // HEATER2 +#define HEATER_3_PIN PB12 // HEATER2 +#define HEATER_BED_PIN PB0 // HOT BED + +#define FAN0_PIN PA0 // FAN +#define FAN1_PIN PA1 // FAN +#define FAN2_PIN PA2 // FAN +#define FAN3_PIN PA3 // FAN + +// +// LCD / Controller +// + +/** + * Note: ORCA 3D Modular Controller uses various TFT controllers. + * - For TFT displays use UART0 + * - For 12864 displays use the expansion headers + */ + +/** ------ ------ + * -- | 1 2 | PE10 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) + * (LCD_EN) PE11 | 3 4 | PD10 (LCD_RS) (BTN_EN1) PE8 | 3 4 | PA4 (SD_SS) + * (LCD_D4) PE12 | 5 6 | PE13 (LCD_D5) (BTN_EN2) PE9 | 5 6 | PA7 (MOSI) + * (LCD_D6) PE15 | 7 8 | PE7 (LCD_D7) (SD_DETECT) PD12 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_01_PIN -1 // No BEEPER +#define EXP1_02_PIN PE10 // ENC +#define EXP1_03_PIN PE11 // LCD_EN +#define EXP1_04_PIN PD10 // LCD_RS +#define EXP1_05_PIN PE12 // LCD_D4 +#define EXP1_06_PIN PE13 // LCD_D5 +#define EXP1_07_PIN PE15 // LCD_D6 +#define EXP1_08_PIN PE7 // LCD_D7 + +#define EXP2_01_PIN PA6 // MISO +#define EXP2_02_PIN PA5 // SCK +#define EXP2_03_PIN PE8 // EN1 +#define EXP2_04_PIN PA4 // SD_SS +#define EXP2_05_PIN PE9 // EN2 +#define EXP2_06_PIN PA7 // MOSI +#define EXP2_07_PIN PD12 // SD_DET +#define EXP2_08_PIN -1 // RESET + +// +// SD Card +// +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#if SD_CONNECTION_IS(LCD) + #define SPI_DEVICE 1 + #define SD_DETECT_PIN EXP2_07_PIN + #define SD_SCK_PIN EXP2_02_PIN + #define SD_MISO_PIN EXP2_01_PIN + #define SD_MOSI_PIN EXP2_06_PIN + #define SD_SS_PIN EXP2_04_PIN +#elif SD_CONNECTION_IS(ONBOARD) + #define SD_DETECT_PIN PA3 + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_SS_PIN PA4 +#endif +#define ONBOARD_SPI_DEVICE 1 // SPI1 +#define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card + +// +// LCD / Controller +// + +#if HAS_WIRED_LCD + #define BEEPER_PIN EXP1_01_PIN // NC + #define BTN_ENC EXP1_02_PIN + + #if ENABLED(CR10_STOCKDISPLAY) + #define LCD_PINS_RS EXP1_07_PIN + + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + + #define LCD_PINS_EN EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + + #elif IS_TFTGLCD_PANEL + + #undef BEEPER_PIN + #undef BTN_ENC + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS EXP2_03_PIN + #endif + + #define SD_DETECT_PIN EXP2_07_PIN + + #else + + #define LCD_PINS_RS EXP1_04_PIN + + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + + #define LCD_PINS_EN EXP1_03_PIN + + #if ENABLED(FYSETC_MINI_12864) + + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN EXP1_05_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN + + #define FORCE_SOFT_SPI // SPI MODE3 + + #define LED_PIN EXP1_06_PIN // red pwm + //#define LED_PIN EXP1_07_PIN // green + //#define LED_PIN EXP1_08_PIN // blue + + //#if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + // #ifndef RGB_LED_R_PIN + // #define RGB_LED_R_PIN EXP1_06_PIN + // #endif + // #ifndef RGB_LED_G_PIN + // #define RGB_LED_G_PIN EXP1_07_PIN + // #endif + // #ifndef RGB_LED_B_PIN + // #define RGB_LED_B_PIN EXP1_08_PIN + // #endif + //#elif ENABLED(FYSETC_MINI_12864_2_1) + // #define NEOPIXEL_PIN EXP1_06_PIN + //#endif + + #else // !FYSETC_MINI_12864 + + #define LCD_PINS_D4 EXP1_05_PIN + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + + #endif + + #endif // !FYSETC_MINI_12864 + + #endif + +#endif // HAS_WIRED_LCD + +// Alter timing for graphical display +#if IS_U8GLIB_ST7920 + #define BOARD_ST7920_DELAY_1 125 + #define BOARD_ST7920_DELAY_2 125 + #define BOARD_ST7920_DELAY_3 125 +#endif diff --git a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h index ed602d8d011e..33440e30dd1d 100644 --- a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h +++ b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h @@ -31,7 +31,7 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -88,18 +88,16 @@ #define E0_DIR_PIN PB14 // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB5 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB4 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB3 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB5 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB4 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB3 #endif #if HAS_TMC_UART @@ -127,8 +125,11 @@ #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -142,7 +143,7 @@ // #define HEATER_0_PIN PB12 // "HE" #define HEATER_BED_PIN PB13 // "HB" -#define FAN_PIN PA8 // "FAN0" +#define FAN0_PIN PA8 // "FAN0" #define HEATER_1_PIN PA12 // @@ -167,17 +168,18 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #define BTN_ENC PA0 #define BTN_EN1 PC4 #define BTN_EN2 PC5 #define LCD_PINS_RS PC0 - #define LCD_PINS_ENABLE PC2 + #define LCD_PINS_EN PC2 #define LCD_PINS_D4 PC1 #endif -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_PANDA_PI_V29.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" @@ -218,7 +220,7 @@ #define CLCD_MOD_RESET PA9 #define CLCD_SPI_CS PB8 - #if SD_CONNECTION_IS(LCD) && BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) + #if SD_CONNECTION_IS(LCD) && ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #define SD_DETECT_PIN PA15 #define SD_SS_PIN PA10 #endif diff --git a/Marlin/src/pins/stm32f1/pins_SOVOL_V131.h b/Marlin/src/pins/stm32f1/pins_SOVOL_V131.h deleted file mode 100644 index 67b2944f4560..000000000000 --- a/Marlin/src/pins/stm32f1/pins_SOVOL_V131.h +++ /dev/null @@ -1,236 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2023 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 - -/** - * Sovol 1.3.1 (GD32F103RET6) board pin assignments - */ - -#include "env_validate.h" - -#if HOTENDS > 1 || E_STEPPERS > 1 - #error "SOVOL V131 only supports 1 hotend / E-stepper." -#endif - -#ifndef BOARD_INFO_NAME - #define BOARD_INFO_NAME "Sovol V131" -#endif -#ifndef DEFAULT_MACHINE_NAME - #define DEFAULT_MACHINE_NAME "Sovol SV06" -#endif - -//#define BOARD_NO_NATIVE_USB - -// -// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role -// -#ifndef DISABLE_DEBUG - #define DISABLE_DEBUG -#endif - -// -// EEPROM -// -#if NO_EEPROM_SELECTED - #define IIC_BL24CXX_EEPROM // EEPROM on I2C-0 - //#define SDCARD_EEPROM_EMULATION - #undef NO_EEPROM_SELECTED -#endif - -#if ENABLED(IIC_BL24CXX_EEPROM) - #define IIC_EEPROM_SDA PA11 - #define IIC_EEPROM_SCL PA12 - #define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16) -#elif ENABLED(SDCARD_EEPROM_EMULATION) - #define MARLIN_EEPROM_SIZE 0x800 // 2K -#endif - -// -// Servos -// -#ifndef SERVO0_PIN - #ifndef HAS_PIN_27_BOARD - #define SERVO0_PIN PB0 // BLTouch OUT - #else - #define SERVO0_PIN PC6 - #endif -#endif - -// -// Limit Switches -// -#ifndef X_STOP_PIN - #define X_STOP_PIN PA5 -#endif -#ifndef Y_STOP_PIN - #define Y_STOP_PIN PA6 -#endif -#ifndef Z_STOP_PIN - #define Z_STOP_PIN PA7 -#endif - -#ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PB1 // BLTouch IN -#endif - -// -// Filament Runout Sensor -// -#ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PA4 // "Pulled-high" -#endif - -// -// Steppers -// -#ifndef X_STEP_PIN - #define X_STEP_PIN PC2 -#endif -#ifndef X_DIR_PIN - #define X_DIR_PIN PB9 -#endif -#define X_ENABLE_PIN PC3 // Shared - -#ifndef Y_STEP_PIN - #define Y_STEP_PIN PB8 -#endif -#ifndef Y_DIR_PIN - #define Y_DIR_PIN PB7 -#endif -#define Y_ENABLE_PIN X_ENABLE_PIN - -#ifndef Z_STEP_PIN - #define Z_STEP_PIN PB6 -#endif -#ifndef Z_DIR_PIN - #define Z_DIR_PIN PB5 -#endif -#define Z_ENABLE_PIN X_ENABLE_PIN - -#ifndef E0_STEP_PIN - #define E0_STEP_PIN PB4 -#endif -#ifndef E0_DIR_PIN - #define E0_DIR_PIN PB3 -#endif -#define E0_ENABLE_PIN X_ENABLE_PIN - -#if HAS_TMC_UART - - /** - * TMC2208/TMC2209 stepper drivers - * - * Hardware serial communication ports. - * If undefined software serial is used according to the pins below - */ - - #define X_SERIAL_TX_PIN PC1 - #define X_SERIAL_RX_PIN PC1 - - #define Y_SERIAL_TX_PIN PC0 - #define Y_SERIAL_RX_PIN PC0 - - #define Z_SERIAL_TX_PIN PA15 - #define Z_SERIAL_RX_PIN PA15 - - #define E0_SERIAL_TX_PIN PC14 - #define E0_SERIAL_RX_PIN PC14 - - // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 - -#endif // HAS_TMC_UART - -// -// Temperature Sensors -// -#define TEMP_0_PIN PC5 // TH1 -#define TEMP_BED_PIN PC4 // TB1 - -// -// Heaters / Fans -// -#ifndef HEATER_0_PIN - #define HEATER_0_PIN PA1 // HEATER1 -#endif -#ifndef HEATER_BED_PIN - #define HEATER_BED_PIN PA2 // HOT BED -#endif -#ifndef FAN_PIN - #define FAN_PIN PA0 // FAN -#endif -#define FAN_SOFT_PWM_REQUIRED - -// -// SD Card -// -#define SD_DETECT_PIN PC7 -#define SDCARD_CONNECTION ONBOARD -#define ONBOARD_SPI_DEVICE 1 -#define ONBOARD_SD_CS_PIN PA4 // SDSS -#define SDIO_SUPPORT -#define NO_SD_HOST_DRIVE // This board's SD is only seen by the printer - -#if ANY(RET6_12864_LCD, HAS_DWIN_E3V2, IS_DWIN_MARLINUI) - /** - * RET6 12864 LCD - * ------ - * PC6 | 1 2 | PB2 - * PB10 | 3 4 | PB11 - * PB14 5 6 | PB13 - * PB12 | 7 8 | PB15 - * GND | 9 10 | 5V - * ------ - */ - #define EXP3_01_PIN PC6 - #define EXP3_02_PIN PB2 - #define EXP3_03_PIN PB10 - #define EXP3_04_PIN PB11 - #define EXP3_05_PIN PB14 - #define EXP3_06_PIN PB13 - #define EXP3_07_PIN PB12 - #define EXP3_08_PIN PB15 -#endif - -#if ENABLED(CR10_STOCKDISPLAY) - - #if ENABLED(RET6_12864_LCD) - - #define LCD_PINS_RS EXP3_07_PIN - #define LCD_PINS_ENABLE EXP3_08_PIN - #define LCD_PINS_D4 EXP3_06_PIN - - #define BTN_ENC EXP3_02_PIN - #define BTN_EN1 EXP3_03_PIN - #define BTN_EN2 EXP3_05_PIN - - #ifndef HAS_PIN_27_BOARD - #define BEEPER_PIN EXP3_01_PIN - #endif - - #else - - #error "Only the RET6_12864_LCD variant of CR10_STOCKDISPLAY is supported." - - #endif - -#endif diff --git a/Marlin/src/pins/stm32f1/pins_STM32F1R.h b/Marlin/src/pins/stm32f1/pins_STM32F1R.h index 634cadc1aa8e..9cbc69149cd5 100644 --- a/Marlin/src/pins/stm32f1/pins_STM32F1R.h +++ b/Marlin/src/pins/stm32f1/pins_STM32F1R.h @@ -24,7 +24,7 @@ #include "env_validate.h" /** - * 21017 Victor Perez Marlin for stm32f1 test + * 2017 Victor Perez Marlin for stm32f1 test */ #define BOARD_INFO_NAME "Misc. STM32F1R" @@ -101,7 +101,7 @@ #error "REPRAPWORLD_GRAPHICAL_LCD is not supported." #else #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_EN PD2 #define LCD_PINS_D4 PB12 #define LCD_PINS_D5 PB13 #define LCD_PINS_D6 PB14 @@ -120,7 +120,7 @@ #error "LCD_I2C_PANELOLU2 is not supported." #elif ENABLED(LCD_I2C_VIKI) #error "LCD_I2C_VIKI is not supported." - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #error "VIKI2 / miniVIKI is not supported." #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) #error "ELB_FULL_GRAPHIC_CONTROLLER is not supported." diff --git a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h index eee7dbf31669..e5b16460f010 100644 --- a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h @@ -24,7 +24,7 @@ #include "env_validate.h" /** - * 10 Dec 2017 Victor Perez Marlin for stm32f1 test + * 2017 Victor Perez Marlin for stm32f1 test */ #define BOARD_INFO_NAME "STM3R Mini" @@ -86,8 +86,8 @@ //#define HEATER_BED2_PIN -1 // BED2 //#define HEATER_BED3_PIN -1 // BED3 -#ifndef FAN_PIN - #define FAN_PIN PD14 +#ifndef FAN0_PIN + #define FAN0_PIN PD14 #endif #define FAN1_PIN PD13 @@ -116,7 +116,7 @@ #error "REPRAPWORLD_GRAPHICAL_LCD is not supported." #else #define LCD_PINS_RS PB8 - #define LCD_PINS_ENABLE PD2 + #define LCD_PINS_EN PD2 #define LCD_PINS_D4 PB12 #define LCD_PINS_D5 PB13 #define LCD_PINS_D6 PB14 @@ -144,7 +144,7 @@ #error "LCD_I2C_PANELOLU2 is not supported." #elif ENABLED(LCD_I2C_VIKI) #error "LCD_I2C_VIKI is not supported." - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #error "VIKI2 / miniVIKI is not supported." #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) #error "ELB_FULL_GRAPHIC_CONTROLLER is not supported." diff --git a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h index 73f61c1aca70..a62bc535db47 100644 --- a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h @@ -117,7 +117,7 @@ // Fans // #define CONTROLLER_FAN_PIN PD6 // FAN -#define FAN_PIN PG13 // FAN +#define FAN0_PIN PG13 // FAN #define FAN1_PIN PG14 // FAN // @@ -186,9 +186,9 @@ #endif // SPI1(PA7) & SPI3(PB5) not available -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple -#if ENABLED(SDIO_SUPPORT) +#if ENABLED(ONBOARD_SDIO) #define SD_SCK_PIN PB13 // SPI2 ok #define SD_MISO_PIN PB14 // SPI2 ok #define SD_MOSI_PIN PB15 // SPI2 ok diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h index 1347a1467882..8ce0f48839de 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h @@ -39,7 +39,7 @@ // Zonestar ZM3E2 V1.0 (STM32F103RCT6) board pin assignments //============================================================================= // PA0 PWR_HOLD | PB0 BEEP | PC0 HEATER_0 -// PA1 FAN_PIN | PB1 KILL | PC1 HEATER_BED +// PA1 FAN0_PIN | PB1 KILL | PC1 HEATER_BED // PA2 TX2 | PB2 LCD_SDA | PC2 TEMP_BED // PA3 RX2 | PB3 E1_EN | PC3 TEMP_E0 // PA4 SD_CS | PB4 Z_STOP | PC4 SD_DETECT @@ -149,7 +149,7 @@ #define HEATER_BED_PIN PC1 // BED #define FAN1_PIN PC6 -#define FAN_PIN PA1 +#define FAN0_PIN PA1 // // Temperature Sensors @@ -186,7 +186,7 @@ // 8 TX1 PA9 LCD_PINS_RS // 7 RX1 PA10 LCD_PINS_D4 // 6 ENA PC5 BTN_EN2 - // 5 DAT PB2 LCD_PINS_ENABLE + // 5 DAT PB2 LCD_PINS_EN // 4 TX3 PB10 BTN_ENC // 3 RX3 PB11 BTN_EN1 // 2 +5V @@ -194,7 +194,7 @@ #define LCDSCREEN_NAME "ZONESTAR LCD12864" #define LCD_PINS_RS EXP1_03_PIN - #define LCD_PINS_ENABLE EXP1_06_PIN + #define LCD_PINS_EN EXP1_06_PIN #define LCD_PINS_D4 EXP1_04_PIN //#define KILL_PIN EXP1_01_PIN #define BEEPER_PIN EXP1_02_PIN @@ -205,7 +205,7 @@ #define BOARD_ST7920_DELAY_2 200 #define BOARD_ST7920_DELAY_3 125 -#elif EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) +#elif ANY(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) //================================================================================ // OLED 128x64 diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h index 9618b3ad1abb..c1e5a46f70db 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V1_0.h @@ -190,6 +190,7 @@ #define Z2_DIR_PIN PD0 #endif +// TODO: Use different pin names for auto-remapping #ifdef OPTION_Z2_ENDSTOP #define Z2_MIN_PIN PD1 #define Z2_MAX_PIN PB12 @@ -249,7 +250,7 @@ #define HEATER_1_PIN PB0 // HEATER1 #endif -#define FAN_PIN PB1 // FAN1 +#define FAN0_PIN PB1 // FAN1 #define FAN1_PIN PB8 // FAN2 // @@ -277,10 +278,11 @@ // // LCD / Controller // + #if ENABLED(ZONESTAR_12864LCD) #define LCDSCREEN_NAME "ZONESTAR LCD12864" #define LCD_PINS_RS EXP1_03_PIN // 7 CS make sure for zonestar zm3e4! - #define LCD_PINS_ENABLE EXP1_06_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_EN EXP1_06_PIN // 6 DATA make sure for zonestar zm3e4! #define LCD_PINS_D4 EXP1_04_PIN // 8 SCK make sure for zonestar zm3e4! #define BEEPER_PIN EXP1_02_PIN #define KILL_PIN -1 // EXP1_01_PIN @@ -290,7 +292,7 @@ #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define LCDSCREEN_NAME "REPRAPDISCOUNT LCD12864" #define LCD_PINS_RS EXP1_03_PIN // 7 CS make sure for zonestar zm3e4! - #define LCD_PINS_ENABLE EXP1_04_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_EN EXP1_04_PIN // 6 DATA make sure for zonestar zm3e4! #define LCD_PINS_D4 EXP1_06_PIN // 8 SCK make sure for zonestar zm3e4! #define BEEPER_PIN EXP1_02_PIN #define KILL_PIN EXP2_07_PIN @@ -310,7 +312,7 @@ #if ENABLED(ZONESTAR_LCD2004_KNOB) #define LCDSCREEN_NAME "LCD2004 KNOB" #define LCD_PINS_RS EXP1_03_PIN - #define LCD_PINS_ENABLE EXP1_04_PIN + #define LCD_PINS_EN EXP1_04_PIN #define LCD_PINS_D4 EXP1_06_PIN #define LCD_PINS_D5 EXP1_05_PIN #define LCD_PINS_D6 EXP1_08_PIN @@ -323,7 +325,7 @@ #elif ENABLED(ZONESTAR_LCD2004_ADCKEY) #define LCDSCREEN_NAME "LCD2004 5KEY" #define LCD_PINS_RS EXP1_03_PIN - #define LCD_PINS_ENABLE EXP1_04_PIN + #define LCD_PINS_EN EXP1_04_PIN #define LCD_PINS_D4 EXP1_06_PIN #define LCD_PINS_D5 EXP1_05_PIN #define LCD_PINS_D6 EXP1_08_PIN diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h index d1d8a4c68fcf..24c7404360f0 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E4_V2_0.h @@ -156,6 +156,7 @@ #define Y_MAX_PIN PB14 #define Z_MAX_PIN PB13 +// TODO: Use different pin names for auto-remapping #ifdef OPTION_Z2_ENDSTOP #define Z2_MIN_PIN PD1 #define Z2_MAX_PIN PB12 @@ -249,7 +250,7 @@ // // Fans // -#define FAN_PIN PB1 // FAN1 +#define FAN0_PIN PB1 // FAN1 #define FAN1_PIN PB8 // FAN2 // @@ -277,7 +278,7 @@ #if ENABLED(ZONESTAR_12864LCD) #define LCDSCREEN_NAME "ZONESTAR LCD12864" #define LCD_PINS_RS EXP1_03_PIN // 7 CS make sure for zonestar zm3e4! - #define LCD_PINS_ENABLE EXP1_06_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_EN EXP1_06_PIN // 6 DATA make sure for zonestar zm3e4! #define LCD_PINS_D4 EXP1_04_PIN // 8 SCK make sure for zonestar zm3e4! #define BEEPER_PIN EXP1_02_PIN #define KILL_PIN -1 // EXP1_01_PIN @@ -287,7 +288,7 @@ #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define LCDSCREEN_NAME "REPRAPDISCOUNT LCD12864" #define LCD_PINS_RS EXP2_03_PIN // 7 CS make sure for zonestar zm3e4! - #define LCD_PINS_ENABLE EXP2_06_PIN // 6 DATA make sure for zonestar zm3e4! + #define LCD_PINS_EN EXP2_06_PIN // 6 DATA make sure for zonestar zm3e4! #define LCD_PINS_D4 EXP2_04_PIN // 8 SCK make sure for zonestar zm3e4! #define BEEPER_PIN EXP2_01_PIN #define KILL_PIN EXP2_02_PIN diff --git a/Marlin/src/pins/stm32f4/env_validate.h b/Marlin/src/pins/stm32f4/env_validate.h index c01401f06c9a..91adbfc86929 100644 --- a/Marlin/src/pins/stm32f4/env_validate.h +++ b/Marlin/src/pins/stm32f4/env_validate.h @@ -19,10 +19,13 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if NOT_TARGET(STM32F4) && (DISABLED(ALLOW_STM32DUINO) || NOT_TARGET(STM32F4xx)) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #endif #undef ALLOW_STM32DUINO + +#endif diff --git a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h index 7c6eaca812d9..c2b2512f4ab8 100644 --- a/Marlin/src/pins/stm32f4/pins_ANET_ET4.h +++ b/Marlin/src/pins/stm32f4/pins_ANET_ET4.h @@ -123,7 +123,7 @@ // // Fans // -#define FAN_PIN PE3 // Layer fan +#define FAN0_PIN PE3 // Layer fan #define FAN1_PIN PE1 // Hotend fan #ifndef E0_AUTO_FAN_PIN @@ -133,6 +133,7 @@ // // LCD / Controller // + #if HAS_SPI_TFT || HAS_FSMC_TFT #define TFT_RESET_PIN PE6 #define TFT_CS_PIN PD7 @@ -195,15 +196,15 @@ // // SD Card // -//#define SDIO_SUPPORT +//#define ONBOARD_SDIO #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION CUSTOM_CABLE #endif -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA - #if DISABLED(SDIO_SUPPORT) + #if DISABLED(ONBOARD_SDIO) #define SOFTWARE_SPI #define SDSS PC11 #define SD_SS_PIN SDSS diff --git a/Marlin/src/pins/stm32f4/pins_ARMED.h b/Marlin/src/pins/stm32f4/pins_ARMED.h index 2abcc21da5a4..b4661226380f 100644 --- a/Marlin/src/pins/stm32f4/pins_ARMED.h +++ b/Marlin/src/pins/stm32f4/pins_ARMED.h @@ -128,7 +128,7 @@ #define HEATER_1_PIN PA2 // Hardware PWM #define HEATER_BED_PIN PA0 // Hardware PWM -#define FAN_PIN PC6 // Hardware PWM, Part cooling fan +#define FAN0_PIN PC6 // Hardware PWM, Part cooling fan #define FAN1_PIN PC7 // Hardware PWM, Extruder fan #define FAN2_PIN PC8 // Hardware PWM, Controller fan @@ -158,7 +158,7 @@ #define LCD_RESET_PIN PB12 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN PB13 #endif @@ -173,7 +173,7 @@ #endif #else #define LCD_PINS_RS PE9 - #define LCD_PINS_ENABLE PE8 + #define LCD_PINS_EN PE8 #define LCD_PINS_D4 PB12 #define LCD_PINS_D5 PB13 #define LCD_PINS_D6 PB14 @@ -223,5 +223,8 @@ #define Z2_SERIAL_RX_PIN EXT4_PIN #define Z2_SERIAL_TX_PIN EXT4_PIN - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h index 7413b9b0645a..502ec19bed03 100644 --- a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h +++ b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h @@ -23,7 +23,7 @@ #include "env_validate.h" -#if HOTENDS > 1 || E_STEPPERS > 1 +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "Artillery Ruby only supports 1 hotend / E stepper." #endif @@ -100,8 +100,8 @@ #ifndef HEATER_BED_PIN #define HEATER_BED_PIN PA8 // Hotbed #endif -#ifndef FAN_PIN - #define FAN_PIN PC8 // Fan0 +#ifndef FAN0_PIN + #define FAN0_PIN PC8 // Fan0 #endif #ifndef FAN1_PIN #define FAN1_PIN PC7 // Fan1 @@ -125,8 +125,9 @@ // // LCD / Controller // + #if HAS_WIRED_LCD - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) #define LCD_PINS_DC PB8 // Set as output on init #define LCD_PINS_RS PB9 // Pull low for 1s to init // DOGM SPI LCD Support @@ -143,7 +144,7 @@ #define LCD_RESET_PIN PB5 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN PB9 #endif @@ -160,7 +161,7 @@ #define LCD_CONTRAST_INIT 255 #else #define LCD_PINS_RS PC15 - #define LCD_PINS_ENABLE PB6 + #define LCD_PINS_EN PB6 #define LCD_PINS_D4 PB5 #define LCD_PINS_D5 PB9 #define LCD_PINS_D6 PB8 @@ -173,7 +174,7 @@ // #define BEEPER_PIN PC13 - #if ENABLED(SDSUPPORT) + #if HAS_MEDIA #define SDSS PA15 #define SD_DETECT_PIN PD2 #endif diff --git a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h index c49abca9ef85..025a1fc9f1a8 100644 --- a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h +++ b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h @@ -101,7 +101,7 @@ #define HEATER_1_PIN PA3 // Heater1 #define HEATER_BED_PIN PA1 // Hotbed -#define FAN_PIN PE9 // Fan0 +#define FAN0_PIN PE9 // Fan0 #define FAN1_PIN PE11 // Fan1 #define FAN2_PIN PE13 // Fan2 #define FAN3_PIN PE14 // Fan3 @@ -121,7 +121,7 @@ #define BEEPER_PIN PD10 #define LCD_PINS_RS PE15 -#define LCD_PINS_ENABLE PD8 +#define LCD_PINS_EN PD8 #define LCD_PINS_D4 PE10 #define LCD_PINS_D5 PE12 #define LCD_PINS_D6 PD1 @@ -145,8 +145,8 @@ #endif #if SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT // Use SDIO for onboard SD - #if DISABLED(SDIO_SUPPORT) + #define ONBOARD_SDIO // Use SDIO for onboard SD + #if DISABLED(ONBOARD_SDIO) #define SOFTWARE_SPI // Use soft SPI for onboard SD #define SDSS PC11 #define SD_SCK_PIN PC12 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 2147dd9b4fa7..2abbf3452bed 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -108,18 +108,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB15 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB14 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB13 #endif #if HAS_TMC_UART @@ -154,29 +152,35 @@ #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors // #define TEMP_0_PIN PA2 // T0 <-> E0 #define TEMP_1_PIN PA0 // T1 <-> E1 -#define TEMP_BOARD_PIN PC2 // Onboard thermistor, NTC100K #define TEMP_BED_PIN PA1 // T2 <-> Bed #define TEMP_PROBE_PIN PC3 // Shares J4 connector with PD1 +#ifndef TEMP_BOARD_PIN + #define TEMP_BOARD_PIN PC2 // Onboard thermistor, NTC100K +#endif + // // Heaters / Fans // #define HEATER_0_PIN PE6 // Heater0 #define HEATER_BED_PIN PE5 // Hotbed -#ifndef FAN_PIN +#ifndef FAN0_PIN #ifdef MK3_FAN_PINS - #define FAN_PIN PB8 // Fan1 + #define FAN0_PIN PB8 // Fan1 #else - #define FAN_PIN PB9 // Fan0 + #define FAN0_PIN PB9 // Fan0 #endif #endif @@ -197,16 +201,14 @@ #endif /** - * ---------------------------------BTT002 V1.0--------------------------------- - * ------ ------ | - * (BEEPER) PE7 | 1 2 | PB1 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) | - * (LCD_EN) PE9 | 3 4 | PE8 (LCD_RS) (BTN_EN1) PC5 | 3 4 | PA4 (SD_SS) | - * (LCD_D4) PE10 5 6 | PE11 (LCD_D5) (BTN_EN2) PB0 5 6 | PA7 (MOSI) | - * (LCD_D6) PE12 | 7 8 | PE13 (LCD_D7) (SD_DET) PC4 | 7 8 | RESET | - * GND | 9 10 | 5V GND | 9 10 | PA3 | - * ------ ------ | - * EXP1 EXP2 | - * ------------------------------------------------------------------------------ + * ------ ------ + * (BEEPER) PE7 | 1 2 | PB1 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) + * (LCD_EN) PE9 | 3 4 | PE8 (LCD_RS) (BTN_EN1) PC5 | 3 4 | PA4 (SD_SS) + * (LCD_D4) PE10 5 6 | PE11 (LCD_D5) (BTN_EN2) PB0 5 6 | PA7 (MOSI) + * (LCD_D6) PE12 | 7 8 | PE13 (LCD_D7) (SD_DET) PC4 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | PA3 + * ------ ------ + * EXP1 EXP2 */ #define EXP1_01_PIN PE7 #define EXP1_02_PIN PB1 @@ -236,8 +238,9 @@ #define SDSS EXP2_04_PIN // -// LCDs and Controllers +// LCD / Controller // + #if HAS_WIRED_LCD #define BEEPER_PIN EXP1_01_PIN #define BTN_ENC EXP1_02_PIN @@ -250,7 +253,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) @@ -267,7 +270,7 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -283,7 +286,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index 60e33d9dc4ad..271b7d9cfe38 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -135,8 +135,11 @@ #endif // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -159,7 +162,7 @@ #define HEATER_1_PIN FPC16_PIN // "HE1" #endif -#define FAN_PIN PB5 // "FAN0" +#define FAN0_PIN PB5 // "FAN0" #ifndef CONTROLLER_FAN_PIN #define CONTROLLER_FAN_PIN PB6 // "FAN1" @@ -183,9 +186,7 @@ #define PS_ON_PIN PE1 // Power Supply Control #endif -/** - * BTT E3 RRF - * ------ +/** ------ * (BEEPER) PE8 | 1 2 | PE9 (BTN_ENC) * (BTN_EN1) PE7 | 3 4 | RESET * (BTN_EN2) PB2 5 6 | PE10 (LCD_D4) @@ -194,20 +195,28 @@ * ------ * EXP1 */ +#define EXP1_01_PIN PE8 +#define EXP1_02_PIN PE9 +#define EXP1_03_PIN PE7 +#define EXP1_04_PIN -1 // RESET +#define EXP1_05_PIN PB2 +#define EXP1_06_PIN PE10 +#define EXP1_07_PIN PB1 +#define EXP1_08_PIN PE11 #if HAS_WIRED_LCD - #if EITHER(CR10_STOCKDISPLAY, LCD_FOR_MELZI) + #if ANY(CR10_STOCKDISPLAY, LCD_FOR_MELZI) - #define BEEPER_PIN PE8 + #define BEEPER_PIN EXP1_01_PIN - #define BTN_ENC PE9 - #define BTN_EN1 PE7 - #define BTN_EN2 PB2 + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_RS PB1 - #define LCD_PINS_ENABLE PE11 - #define LCD_PINS_D4 PE10 + #define LCD_PINS_D4 EXP1_06_PIN + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_EN EXP1_08_PIN #if ENABLED(LCD_FOR_MELZI) @@ -251,24 +260,24 @@ #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" #endif - #define LCD_PINS_RS PE10 - #define LCD_PINS_ENABLE PE9 - #define LCD_PINS_D4 PB1 - #define LCD_PINS_D5 PB2 - #define LCD_PINS_D6 PE7 - #define LCD_PINS_D7 PE8 + #define LCD_PINS_RS EXP1_06_PIN + #define LCD_PINS_EN EXP1_02_PIN + #define LCD_PINS_D4 EXP1_07_PIN + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_03_PIN + #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN PB0 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) - #define BTN_ENC PE9 - #define BTN_EN1 PE7 - #define BTN_EN2 PB2 + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN - #define DOGLCD_CS PB1 - #define DOGLCD_A0 PE10 - #define DOGLCD_SCK PE8 - #define DOGLCD_MOSI PE11 + #define DOGLCD_CS EXP1_07_PIN + #define DOGLCD_A0 EXP1_06_PIN + #define DOGLCD_SCK EXP1_01_PIN + #define DOGLCD_MOSI EXP1_08_PIN #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 @@ -310,7 +319,7 @@ * EXP1-1 ----------- EXP1-7 SD_DET */ - #define TFTGLCD_CS PE7 + #define TFTGLCD_CS EXP1_03_PIN #endif @@ -331,7 +340,7 @@ #endif // HAS_WIRED_LCD -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" @@ -367,10 +376,10 @@ #define CLCD_SPI_BUS 1 // SPI1 connector - #define BEEPER_PIN PE9 + #define BEEPER_PIN EXP1_02_PIN - #define CLCD_MOD_RESET PE7 - #define CLCD_SPI_CS PB1 + #define CLCD_MOD_RESET EXP1_03_PIN + #define CLCD_SPI_CS EXP1_07_PIN #endif // TOUCH_UI_FTDI_EVE && LCD_FYSETC_TFT81050 @@ -383,7 +392,7 @@ #endif #if SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT // Use SDIO for onboard SD + #define ONBOARD_SDIO // Use SDIO for onboard SD //#define SDIO_CLOCK 48000000 #define SD_DETECT_PIN PC4 #elif SD_CONNECTION_IS(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 fe03ec8983ff..7e021c534ec5 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -106,11 +106,21 @@ // Pins on the extender // #if ENABLED(M5_EXTENDER) - #define X2_STOP_PIN PI4 // M5 M1_STOP - #define Y2_STOP_PIN PF12 // M5 M5_STOP - #define Z2_STOP_PIN PF4 // M5 M2_STOP - #define Z3_STOP_PIN PI7 // M5 M4_STOP - #define Z4_STOP_PIN PF6 // M5 M3_STOP + #ifndef X2_STOP_PIN + #define X2_STOP_PIN PI4 // M5 M1_STOP + #endif + #ifndef Y2_STOP_PIN + #define Y2_STOP_PIN PF12 // M5 M5_STOP + #endif + #ifndef Z2_STOP_PIN + #define Z2_STOP_PIN PF4 // M5 M2_STOP + #endif + #ifndef Z3_STOP_PIN + #define Z3_STOP_PIN PI7 // M5 M4_STOP + #endif + #ifndef Z4_STOP_PIN + #define Z4_STOP_PIN PF6 // M5 M3_STOP + #endif #endif #ifndef Z_MIN_PROBE_PIN @@ -202,18 +212,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PG15 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB3 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PG15 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB6 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB3 #endif #if HAS_TMC_UART @@ -274,8 +282,11 @@ #endif // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -304,9 +315,9 @@ //#define TEMP_0_MOSI_PIN ... // For MAX31865 #define TEMP_1_CS_PIN PH2 // M5 K-TEMP -#define TEMP_1_SCK_PIN TEMP_0_SCK_PIN -#define TEMP_1_MISO_PIN TEMP_0_MISO_PIN -//#define TEMP_1_MOSI_PIN TEMP_0_MOSI_PIN +#define TEMP_1_SCK_PIN TEMP_0_SCK_PIN +#define TEMP_1_MISO_PIN TEMP_0_MISO_PIN +//#define TEMP_1_MOSI_PIN TEMP_0_MOSI_PIN // // Heaters / Fans @@ -325,7 +336,7 @@ #define HEATER_BED_PIN PA2 // Hotbed -#define FAN_PIN PE5 // Fan0 +#define FAN0_PIN PE5 // Fan0 #define FAN1_PIN PE6 // Fan1 #define FAN2_PIN PC8 // Fan2 @@ -392,8 +403,9 @@ #define EXP2_07_PIN PB10 // -// LCDs and Controllers +// LCD / Controller // + #if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) #define TFT_CS_PIN EXP2_04_PIN @@ -421,7 +433,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) @@ -440,7 +452,7 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -453,7 +465,7 @@ //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index 8b061a431c13..2eae84f1ab9a 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -27,7 +27,7 @@ #define USES_DIAG_JUMPERS // Onboard I2C EEPROM -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #undef NO_EEPROM_SELECTED #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x1000 // 4K (AT24C32) @@ -61,13 +61,6 @@ #define E2_DIAG_PIN PG14 // E2DET #define E3_DIAG_PIN PG15 // E3DET -// -// Z Probe (when not Z_MIN_PIN) -// -#ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PB7 -#endif - // // Check for additional used endstop pins // @@ -95,7 +88,7 @@ #else #define X_MIN_PIN E0_DIAG_PIN // E0DET #endif -#elif EITHER(DUAL_X_CARRIAGE, NEEDS_X_MINMAX) +#elif ANY(DUAL_X_CARRIAGE, NEEDS_X_MINMAX) #ifndef X_MIN_PIN #define X_MIN_PIN X_DIAG_PIN // X-STOP #endif @@ -142,6 +135,13 @@ #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP #endif +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PB7 +#endif + // // Filament Runout Sensor // @@ -164,6 +164,11 @@ #define POWER_LOSS_PIN PC0 // PWRDET #endif +// +// Misc. Functions +// +#define LED_PIN PA13 + // // Steppers // @@ -241,7 +246,7 @@ #define HEATER_2_PIN PB10 // Heater2 #define HEATER_3_PIN PB11 // Heater3 -#define FAN_PIN PA8 // Fan0 +#define FAN0_PIN PA8 // Fan0 #define FAN1_PIN PE5 // Fan1 #define FAN2_PIN PD12 // Fan2 #define FAN3_PIN PD13 // Fan3 @@ -260,18 +265,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PA7 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PA6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PA5 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PA7 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PA6 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PA5 #endif #if HAS_TMC_UART @@ -318,8 +321,11 @@ #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART /** ------ ------ * (BEEPER) PE8 | 1 2 | PE7 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) @@ -353,7 +359,7 @@ // Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 // #if SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT // Use SDIO for onboard SD + #define ONBOARD_SDIO // Use SDIO for onboard SD #ifndef SD_DETECT_STATE #define SD_DETECT_STATE HIGH #elif SD_DETECT_STATE == LOW @@ -421,8 +427,9 @@ #endif // BTT_MOTOR_EXPANSION // -// LCDs and Controllers +// LCD / Controller // + #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) @@ -465,7 +472,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #else @@ -475,7 +482,7 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -483,7 +490,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif @@ -510,7 +517,8 @@ #endif #endif -#endif // HAS_WIRED_LCD + +#endif // HAS_WIRED_LCD // Alter timing for graphical display #if IS_U8GLIB_ST7920 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h index 31551f6ff6f4..64ab2dd6c9e8 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h @@ -25,7 +25,7 @@ #include "env_validate.h" -#if HOTENDS > 1 || E_STEPPERS > 1 +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "BTT SKR Mini E3 V3.0.1 supports up to 1 hotend / E stepper." #endif @@ -43,7 +43,7 @@ #endif // Onboard I2C EEPROM -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #undef NO_EEPROM_SELECTED #define I2C_EEPROM #define SOFT_I2C_EEPROM // Force the use of Software I2C @@ -146,7 +146,7 @@ // #define HEATER_0_PIN PA15 // "HE" #define HEATER_BED_PIN PB3 // "HB" -#define FAN_PIN PC9 // "FAN0" +#define FAN0_PIN PC9 // "FAN0" #define FAN1_PIN PA8 // "FAN1" #define FAN2_PIN PC8 // "FAN2" @@ -202,7 +202,7 @@ #define BTN_EN2 EXP1_05_PIN #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! @@ -212,14 +212,14 @@ #endif #define LCD_PINS_RS EXP1_06_PIN - #define LCD_PINS_ENABLE EXP1_02_PIN + #define LCD_PINS_EN EXP1_02_PIN #define LCD_PINS_D4 EXP1_07_PIN #define LCD_PINS_D5 EXP1_05_PIN #define LCD_PINS_D6 EXP1_03_PIN #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP1_03_PIN @@ -280,7 +280,7 @@ #endif // HAS_WIRED_LCD -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" @@ -332,7 +332,7 @@ #define SDCARD_CONNECTION ONBOARD #endif -#if SD_CONNECTION_IS(LCD) && (BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) +#if SD_CONNECTION_IS(LCD) && (ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) #define SD_DETECT_PIN EXP1_01_PIN #define SD_SS_PIN EXP1_05_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index f848a181131b..3e3f4fda33b5 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -23,14 +23,14 @@ #include "env_validate.h" -#define USES_DIAG_JUMPERS +#define USES_DIAG_PINS // 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 -#if BOTH(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) - #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) +#if ALL(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) + #if ANY(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) #define EXP_MOT_USE_EXP2_ONLY 1 #else #error "You can't use both an LCD and a Motor Expansion Module on EXP1/EXP2 at the same time." @@ -172,18 +172,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PC12 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PC11 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PC10 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PC12 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PC11 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PC10 #endif #if HAS_TMC_UART @@ -224,8 +222,11 @@ #define E2_SERIAL_RX_PIN E2_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -291,7 +292,7 @@ // // Fans // -#define FAN_PIN PC8 // Fan0 +#define FAN0_PIN PC8 // Fan0 #define FAN1_PIN PE5 // Fan1 #ifndef E0_AUTO_FAN_PIN @@ -424,8 +425,9 @@ #endif // BTT_MOTOR_EXPANSION // -// LCDs and Controllers +// LCD / Controller // + #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) @@ -444,7 +446,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) @@ -487,7 +489,7 @@ #define DOGLCD_A0 EXP1_06_PIN #define DOGLCD_SCK EXP1_04_PIN #define DOGLCD_MOSI EXP1_02_PIN - #define LCD_BACKLIGHT_PIN -1 + #define LCD_BACKLIGHT_PIN -1 #else @@ -496,7 +498,7 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -504,7 +506,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 10105a6ce830..e22056ad6eb8 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -29,8 +29,8 @@ // https://github.com/bigtreetech/BTT-Expansion-module/tree/master/BTT%20EXP-MOT //#define BTT_MOTOR_EXPANSION -#if BOTH(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) - #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) +#if ALL(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) + #if ANY(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) #define EXP_MOT_USE_EXP2_ONLY 1 #else #error "You can't use both an LCD and a Motor Expansion Module on EXP1/EXP2 at the same time." @@ -137,10 +137,8 @@ // // Probe enable // -#if ENABLED(PROBE_ENABLE_DISABLE) - #ifndef PROBE_ENABLE_PIN - #define PROBE_ENABLE_PIN SERVO0_PIN - #endif +#if ENABLED(PROBE_ENABLE_DISABLE) && !defined(PROBE_ENABLE_PIN) + #define PROBE_ENABLE_PIN SERVO0_PIN #endif // @@ -251,8 +249,8 @@ #ifndef HEATER_BED_PIN #define HEATER_BED_PIN PD7 // Hotbed #endif -#ifndef FAN_PIN - #define FAN_PIN PB7 // Fan0 +#ifndef FAN0_PIN + #define FAN0_PIN PB7 // Fan0 #endif #if HAS_CUTTER @@ -272,18 +270,16 @@ #endif // SPINDLE_FEATURE || LASER_FEATURE // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PE14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PA14 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PE15 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PE14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PA14 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PE15 #endif #if HAS_TMC_UART @@ -324,8 +320,11 @@ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // SD Connection @@ -374,7 +373,7 @@ #define SD_MOSI_PIN EXP2_06_PIN #define SD_DETECT_PIN EXP2_07_PIN #elif SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT // Use SDIO for onboard SD + #define ONBOARD_SDIO // Use SDIO for onboard SD #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." #endif @@ -438,8 +437,9 @@ #endif // BTT_MOTOR_EXPANSION // -// LCDs and Controllers +// LCD / Controller // + #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) @@ -458,7 +458,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) @@ -475,7 +475,7 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -483,7 +483,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif @@ -513,6 +513,118 @@ #endif // HAS_WIRED_LCD +#if HAS_SPI_TFT + + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #if ENABLED(BTT_TFT35_SPI_V1_0) + + /** + * ------ ------ + * BEEPER | 1 2 | LCD-BTN MISO | 1 2 | CLK + * T_MOSI | 3 4 | T_CS LCD-ENCA | 3 4 | TFTCS + * T_CLK | 5 6 T_MISO LCD-ENCB | 5 6 MOSI + * PENIRQ | 7 8 | F_CS RS | 7 8 | RESET + * GND | 9 10 | VCC GND | 9 10 | NC + * ------ ------ + * EXP1 EXP2 + * + * 480x320, 3.5", SPI Display with Rotary Encoder. + * Stock Display for the BIQU B1 SE Series. + * Schematic: https://github.com/bigtreetech/TFT35-SPI/blob/master/v1/Hardware/BTT%20TFT35-SPI%20V1-SCH.pdf + */ + #define TFT_CS_PIN EXP2_04_PIN + #define TFT_DC_PIN EXP2_07_PIN + #define TFT_A0_PIN TFT_DC_PIN + + #define TOUCH_CS_PIN EXP1_04_PIN + #define TOUCH_SCK_PIN EXP1_05_PIN + #define TOUCH_MISO_PIN EXP1_06_PIN + #define TOUCH_MOSI_PIN EXP1_03_PIN + #define TOUCH_INT_PIN EXP1_07_PIN + + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X 17540 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y -11388 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X -21 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y 337 + #endif + #ifndef TOUCH_ORIENTATION + #define TOUCH_ORIENTATION TOUCH_LANDSCAPE + #endif + + #elif ENABLED(MKS_TS35_V2_0) + + /** ------ ------ + * BEEPER | 1 2 | BTN_ENC SPI1_MISO | 1 2 | SPI1_SCK + * TFT_BKL / LCD_EN | 3 4 | TFT_RESET / LCD_RS BTN_EN1 | 3 4 | SPI1_CS + * TOUCH_CS / LCD_D4 | 5 6 TOUCH_INT / LCD_D5 BTN_EN2 | 5 6 SPI1_MOSI + * SPI1_CS / LCD_D6 | 7 8 | SPI1_RS / LCD_D7 SPI1_RS | 7 8 | RESET + * GND | 9 10 | VCC GND | 9 10 | VCC + * ------ ------ + * EXP1 EXP2 + */ + #define TFT_CS_PIN EXP1_07_PIN // SPI1_CS + #define TFT_DC_PIN EXP1_08_PIN // SPI1_RS + #define TFT_A0_PIN TFT_DC_PIN + + #define TFT_RESET_PIN EXP1_04_PIN + + #define LCD_BACKLIGHT_PIN EXP1_03_PIN + #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #define TOUCH_CS_PIN EXP1_05_PIN // SPI1_NSS + #define TOUCH_SCK_PIN EXP2_02_PIN // SPI1_SCK + #define TOUCH_MISO_PIN EXP2_01_PIN // SPI1_MISO + #define TOUCH_MOSI_PIN EXP2_06_PIN // SPI1_MOSI + + #define LCD_READ_ID 0xD3 + #define LCD_USE_DMA_SPI + + #define TFT_BUFFER_WORDS 14400 + + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X -17253 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 11579 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 514 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -24 + #endif + #ifndef TOUCH_ORIENTATION + #define TOUCH_ORIENTATION TOUCH_LANDSCAPE + #endif + + #endif + +#endif // HAS_SPI_TFT + // Alter timing for graphical display #if IS_U8GLIB_ST7920 #ifndef BOARD_ST7920_DELAY_1 @@ -526,29 +638,6 @@ #endif #endif -#if HAS_SPI_TFT - - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN - #define BTN_ENC EXP1_02_PIN - - // - // e.g., BTT_TFT35_SPI_V1_0 (480x320, 3.5", SPI Stock Display with Rotary Encoder in BIQU B1 SE) - // - #define TFT_CS_PIN EXP2_04_PIN - #define TFT_A0_PIN EXP2_07_PIN - #define TFT_SCK_PIN EXP2_02_PIN - #define TFT_MISO_PIN EXP2_01_PIN - #define TFT_MOSI_PIN EXP2_06_PIN - - #define TOUCH_INT_PIN EXP1_07_PIN - #define TOUCH_MISO_PIN EXP1_06_PIN - #define TOUCH_MOSI_PIN EXP1_03_PIN - #define TOUCH_SCK_PIN EXP1_05_PIN - #define TOUCH_CS_PIN EXP1_04_PIN - -#endif - // // NeoPixel LED // diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 8d5e094122f4..d41a6eac754a 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -166,8 +166,8 @@ #define HEATER_5_PIN PE3 #define HEATER_BED_PIN PE2 -#ifndef FAN_PIN - #define FAN_PIN PF8 +#ifndef FAN0_PIN + #define FAN0_PIN PF8 #endif #define FAN1_PIN PF9 #define FAN2_PIN PA2 @@ -214,9 +214,9 @@ #if SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT // Use SDIO for onboard SD + #define ONBOARD_SDIO // Use SDIO for onboard SD - #if DISABLED(SDIO_SUPPORT) + #if DISABLED(ONBOARD_SDIO) #define SOFTWARE_SPI // Use soft SPI for onboard SD #define SDSS PC11 #define SD_SCK_PIN PC12 @@ -235,18 +235,16 @@ #endif // -// Trinamic Software SPI +// Trinamic SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_SCK - #define TMC_SW_SCK EXP2_02_PIN - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO EXP2_01_PIN - #endif - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI EXP2_06_PIN - #endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK EXP2_02_PIN +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO EXP2_01_PIN +#endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI EXP2_06_PIN #endif // @@ -285,10 +283,11 @@ // // LCD / Controller // + #if IS_RRD_SC #define BEEPER_PIN EXP1_01_PIN #define LCD_PINS_RS EXP1_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #define LCD_PINS_D5 EXP1_06_PIN #define LCD_PINS_D6 EXP1_07_PIN diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h index 031caa1ce174..16973b344fb3 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h @@ -34,7 +34,7 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define FLASH_EEPROM_LEVELING @@ -43,14 +43,14 @@ #define FLASH_ADDRESS_START 0x8004000 #endif -#define SERVO0_PIN PB1 // BL-TOUCH/PWM +#define SERVO0_PIN PB1 // BL-TOUCH/PWM // // Limit Switches // -#define X_STOP_PIN PB4 // X-MIN -#define Y_STOP_PIN PC8 // Y-MIN -#define Z_STOP_PIN PA0 // Z-MIN +#define X_STOP_PIN PB4 // X-MIN +#define Y_STOP_PIN PC8 // Y-MIN +#define Z_STOP_PIN PA0 // Z-MIN // // Z Probe @@ -59,7 +59,7 @@ #error "You need to set jumper to 5V for BLTouch, then comment out this line to proceed." #endif #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PB1 // BL-TOUCH/PWM repurposed + #define Z_MIN_PROBE_PIN PB1 // BL-TOUCH/PWM repurposed #endif // @@ -112,8 +112,8 @@ // #define HEATER_0_PIN PC6 #define HEATER_BED_PIN PC7 -#ifndef FAN_PIN - #define FAN_PIN PA14 +#ifndef FAN0_PIN + #define FAN0_PIN PA14 #endif #define FAN1_PIN PA13 #define FAN2_PIN PA1 @@ -149,17 +149,15 @@ * GND | 9 10 | 5V GND | 9 10 | 5V * ------ ------ * EXP2 EXP1 - */ - -/** - * ------ - * 5V | 1 2 | GND - * (LCD_EN/MOSI) PB15 | 3 4 | PB12 (LCD_RS) - * (LCD_D4/SCK) PB13 5 6 | PC11 (BTN_EN2) - * (LCD_D5/MISO) PB14 | 7 8 | PC10 (BTN_EN1) - * (BTN_ENC) PC12 | 9 10 | PC9 (BEEPER) - * ------ - * EXP3 + * + * ------ + * (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 */ #define EXP1_01_PIN PC9 @@ -180,22 +178,31 @@ #define EXP2_07_PIN PC3 #define EXP2_08_PIN -1 -#if HAS_WIRED_LCD +#define EXP3_01_PIN PC9 +#define EXP3_02_PIN PC12 +#define EXP3_03_PIN PC10 +#define EXP3_04_PIN PB14 +#define EXP3_05_PIN PC11 +#define EXP3_06_PIN PB13 +#define EXP3_07_PIN PB12 +#define EXP3_08_PIN PB15 - #define BEEPER_PIN EXP1_01_PIN - #define BTN_ENC EXP1_02_PIN +#if ENABLED(CR10_STOCKDISPLAY) - #if ENABLED(CR10_STOCKDISPLAY) + #define BEEPER_PIN EXP3_01_PIN + #define BTN_ENC EXP3_02_PIN + #define BTN_EN1 EXP3_03_PIN + #define BTN_EN2 EXP3_05_PIN + #define LCD_PINS_D4 EXP3_06_PIN + #define LCD_PINS_RS EXP3_07_PIN + #define LCD_PINS_EN EXP3_08_PIN - #define LCD_PINS_RS EXP1_04_PIN +#elif HAS_WIRED_LCD - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN - - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN + #define BEEPER_PIN EXP1_01_PIN + #define BTN_ENC EXP1_02_PIN - #elif ENABLED(MKS_MINI_12864) + #if ENABLED(MKS_MINI_12864) #define DOGLCD_A0 EXP1_07_PIN #define DOGLCD_CS EXP1_06_PIN @@ -209,7 +216,7 @@ #define BTN_EN1 EXP2_05_PIN #define BTN_EN2 EXP2_03_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -217,7 +224,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index fca181c1f46a..26e8cc0eb119 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -182,8 +182,8 @@ #define HEATER_BED_PIN PC8 #endif -#ifndef FAN_PIN - #define FAN_PIN PB0 +#ifndef FAN0_PIN + #define FAN0_PIN PB0 #endif #ifndef FAN1_PIN #define FAN1_PIN PB1 @@ -238,6 +238,7 @@ // // LCD / Controller // + #if ENABLED(FYSETC_242_OLED_12864) #define BTN_EN1 EXP1_01_PIN @@ -268,7 +269,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #else @@ -280,7 +281,7 @@ #define LCD_SDSS EXP2_04_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -291,7 +292,7 @@ #define LCD_BACKLIGHT_PIN EXP1_07_PIN #endif #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h index a9ce1383d8ca..a6035c2c6f01 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h @@ -53,19 +53,17 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // #define TMC_USE_SW_SPI -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PE14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PE13 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PE12 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PE14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PE13 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PE12 #endif #include "pins_FYSETC_S6.h" diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h index 009bfb248dfe..368f464f86ca 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h @@ -101,19 +101,17 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // #define TMC_USE_SW_SPI -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PE14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PE13 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PE12 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PE14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PE13 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PE12 #endif #if HOTENDS > 3 || E_STEPPERS > 3 diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_V2_2.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_V2_2.h index 50a19fa3d3c3..6ef86117e7f7 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_V2_2.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_V2_2.h @@ -28,7 +28,7 @@ #define TEMP_4_PIN PB1 #define TEMP_BED_PIN PB0 -#define FAN_PIN PA13 +#define FAN0_PIN PA13 #define FAN1_PIN PA14 #include "pins_FYSETC_SPIDER.h" diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index 6c6f8d25ea39..da11ce05ef18 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -154,13 +154,16 @@ #ifndef EX_SERIAL_RX_PIN #define EX_SERIAL_RX_PIN EX_SERIAL_TX_PIN #endif - //#define Z2_SERIAL_RX_PIN EX_SERIAL_RX_PIN - //#define Z2_SERIAL_TX_PIN EX_SERIAL_TX_PIN - //#define E2_SERIAL_RX_PIN EX_SERIAL_RX_PIN - //#define E2_SERIAL_TX_PIN EX_SERIAL_TX_PIN + //#define Z2_SERIAL_RX_PIN EX_SERIAL_RX_PIN + //#define Z2_SERIAL_TX_PIN EX_SERIAL_TX_PIN + //#define E2_SERIAL_RX_PIN EX_SERIAL_RX_PIN + //#define E2_SERIAL_TX_PIN EX_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -182,8 +185,8 @@ #define HEATER_1_PIN PA0 #define HEATER_BED_PIN PA2 -#ifndef FAN_PIN - #define FAN_PIN PF7 +#ifndef FAN0_PIN + #define FAN0_PIN PF7 #endif #define FAN1_PIN PF6 @@ -217,10 +220,10 @@ // // SD support // -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define SDIO_CLOCK 4800000 #define SD_DETECT_PIN PA8 -#if DISABLED(SDIO_SUPPORT) +#if DISABLED(ONBOARD_SDIO) #define SOFTWARE_SPI #define SD_SCK_PIN PC12 #define SD_MISO_PIN PC8 diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h index 376c2f3f2734..c7c9e3db3b13 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h @@ -122,7 +122,7 @@ #define HEATER_1_PIN PA1 #define HEATER_BED_PIN PA3 -#define FAN_PIN PA15 // heater 0 fan 1 +#define FAN0_PIN PA15 // heater 0 fan 1 #define FAN1_PIN PB10 // heater 1 fan 2 #define FAN2_PIN PF5 // heater 0 fan 2 and heater 1 fan 1 (two sockets, switched together) @@ -160,10 +160,10 @@ // // SD support // -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define SDIO_CLOCK 4800000 #define SD_DETECT_PIN PG15 -#if DISABLED(SDIO_SUPPORT) +#if DISABLED(ONBOARD_SDIO) #define SOFTWARE_SPI #define SD_SCK_PIN PC12 #define SD_MISO_PIN PC8 diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h index 6325697655ee..22e7f6e2e2b4 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h @@ -98,8 +98,8 @@ #define HEATER_1_PIN -1 #define HEATER_BED_PIN PA2 -//#ifndef FAN_PIN -// #define FAN_PIN PC15 +//#ifndef FAN0_PIN +// #define FAN0_PIN PC15 //#endif #define FAN1_PIN PC15 #define FAN2_PIN PA0 @@ -118,10 +118,10 @@ // // SD support (On board) // -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define SD_DETECT_PIN PA8 #define SDIO_CLOCK 4800000 -#if DISABLED(SDIO_SUPPORT) +#if DISABLED(ONBOARD_SDIO) #define SOFTWARE_SPI #define SD_SCK_PIN PC12 #define SD_MISO_PIN PC8 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V1.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V1.h index 50fe790dc34d..7d6ea8e03947 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V1.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V1.h @@ -39,7 +39,7 @@ // // Misc. Functions // -#define PW_DET PC5 // Y+ +#define PW_DET PC5 // Y+ #define PW_OFF PB12 // Z+ #define MT_DET_1_PIN PW_DET #define MT_DET_2_PIN PW_OFF diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V2.h index d70e935f0a29..772a93605ae6 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V2.h @@ -58,6 +58,9 @@ #define WIFI_RESET_PIN PD14 // MKS ESP WIFI RESET PIN #endif -#define NEOPIXEL_PIN PC5 +// The FYSETC_MINI_12864_2_1 uses one of the EXP pins +#if DISABLED(FYSETC_MINI_12864_2_1) && !defined(NEOPIXEL_PIN) + #define NEOPIXEL_PIN PC5 +#endif #include "pins_MKS_MONSTER8_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h index 1896cd5441b3..5b5c4fea8789 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h @@ -126,22 +126,23 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // This board only supports SW SPI for stepper drivers // #if HAS_TMC_SPI #define TMC_USE_SW_SPI #endif -#if ENABLED(TMC_USE_SW_SPI) - #if !defined(TMC_SW_MOSI) || TMC_SW_MOSI == -1 - #define TMC_SW_MOSI PE14 - #endif - #if !defined(TMC_SW_MISO) || TMC_SW_MISO == -1 - #define TMC_SW_MISO PE13 - #endif - #if !defined(TMC_SW_SCK) || TMC_SW_SCK == -1 - #define TMC_SW_SCK PE12 - #endif +#if !defined(TMC_SPI_MOSI) || TMC_SPI_MOSI == -1 + #undef TMC_SPI_MOSI + #define TMC_SPI_MOSI PE14 +#endif +#if !defined(TMC_SPI_MISO) || TMC_SPI_MISO == -1 + #undef TMC_SPI_MISO + #define TMC_SPI_MISO PE13 +#endif +#if !defined(TMC_SPI_SCK) || TMC_SPI_SCK == -1 + #undef TMC_SPI_SCK + #define TMC_SPI_SCK PE12 #endif #if HAS_TMC_UART @@ -174,8 +175,11 @@ #define E4_SERIAL_RX_PIN E4_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -193,7 +197,7 @@ #define HEATER_2_PIN PA3 // HE2 #define HEATER_BED_PIN PB10 // H-BED -#define FAN_PIN PA2 // FAN0 +#define FAN0_PIN PA2 // FAN0 #define FAN1_PIN PA1 // FAN1 #define FAN2_PIN PA0 // FAN2 @@ -237,7 +241,7 @@ #define EXP2_07_PIN PB11 #define EXP2_08_PIN -1 // RESET -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif @@ -259,7 +263,7 @@ #endif #endif -#if EITHER(TFT_COLOR_UI, TFT_CLASSIC_UI) +#if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI) #define TFT_CS_PIN EXP1_07_PIN #define TFT_SCK_PIN EXP2_02_PIN #define TFT_MISO_PIN EXP2_01_PIN @@ -290,7 +294,7 @@ #define LCD_READ_ID 0xD3 #define LCD_USE_DMA_SPI - #define TFT_BUFFER_SIZE 14400 + #define TFT_BUFFER_WORDS 14400 #ifndef TOUCH_CALIBRATION_X #define TOUCH_CALIBRATION_X -17253 @@ -310,7 +314,7 @@ #elif HAS_WIRED_LCD - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_RS EXP1_04_PIN #define LCD_BACKLIGHT_PIN -1 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h index 322739725e10..b85b2357d3af 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h @@ -90,7 +90,7 @@ #define HEATER_0_PIN PF3 // Heater0 #define HEATER_1_PIN PF2 // Heater1 #define HEATER_BED_PIN PF4 // Hotbed -#define FAN_PIN PA7 // Fan0 +#define FAN0_PIN PA7 // Fan0 // // Misc. Functions @@ -121,7 +121,7 @@ #define TFT_CS_PIN FSMC_CS_PIN #define TFT_RS_PIN FSMC_RS_PIN - #define TFT_BUFFER_SIZE 14400 + #define TFT_BUFFER_WORDS 14400 #define BEEPER_PIN PG2 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 32d8a47488b9..96e19c987f78 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -51,22 +51,23 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // This board only supports SW SPI for stepper drivers // #if HAS_TMC_SPI #define TMC_USE_SW_SPI #endif -#if ENABLED(TMC_USE_SW_SPI) - #if !defined(TMC_SW_MOSI) || TMC_SW_MOSI == -1 - #define TMC_SW_MOSI PD14 - #endif - #if !defined(TMC_SW_MISO) || TMC_SW_MISO == -1 - #define TMC_SW_MISO PD1 - #endif - #if !defined(TMC_SW_SCK) || TMC_SW_SCK == -1 - #define TMC_SW_SCK PD0 - #endif +#if !defined(TMC_SPI_MOSI) || TMC_SPI_MOSI == -1 + #undef TMC_SPI_MOSI + #define TMC_SPI_MOSI PD14 +#endif +#if !defined(TMC_SPI_MISO) || TMC_SPI_MISO == -1 + #undef TMC_SPI_MISO + #define TMC_SPI_MISO PD1 +#endif +#if !defined(TMC_SPI_SCK) || TMC_SPI_SCK == -1 + #undef TMC_SPI_SCK + #define TMC_SPI_SCK PD0 #endif #include "pins_MKS_ROBIN_NANO_V3_common.h" 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 42b252d320e7..7cc24d62557e 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h @@ -33,7 +33,7 @@ // Use one of these or SDCard-based Emulation will be used //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation //#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x1000 // 4K #define I2C_SCL_PIN PB6 @@ -108,8 +108,11 @@ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -133,7 +136,7 @@ #define HEATER_1_PIN PB0 // HEATER2 #define HEATER_BED_PIN PA0 // HOT BED -#define FAN_PIN PC14 // FAN +#define FAN0_PIN PC14 // FAN #define FAN1_PIN PB1 // FAN1 // @@ -210,8 +213,8 @@ // // Onboard SD card +// Detect pin doesn't work when ONBOARD and NO_SD_HOST_DRIVE disabled // -// detect pin doesn't work when ONBOARD and NO_SD_HOST_DRIVE disabled #if SD_CONNECTION_IS(ONBOARD) #define ENABLE_SPI3 #define SD_SS_PIN -1 @@ -224,13 +227,12 @@ #define SPI_FLASH #if ENABLED(SPI_FLASH) - #define SPI_FLASH - #define SPI_DEVICE 2 - #define SPI_FLASH_SIZE 0x1000000 + #define SPI_DEVICE 2 // Maple + #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 - #define SPI_FLASH_MOSI_PIN PC3 - #define SPI_FLASH_MISO_PIN PC2 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PC2 + #define SPI_FLASH_MOSI_PIN PC3 #endif /** @@ -276,6 +278,7 @@ // // LCD / Controller // + #if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) #define TFT_CS_PIN EXP1_07_PIN #define TFT_SCK_PIN EXP2_02_PIN @@ -307,7 +310,7 @@ #define LCD_READ_ID 0xD3 #define LCD_USE_DMA_SPI - #define TFT_BUFFER_SIZE 14400 + #define TFT_BUFFER_WORDS 14400 #ifndef TOUCH_CALIBRATION_X #define TOUCH_CALIBRATION_X -17253 @@ -327,7 +330,7 @@ #elif HAS_WIRED_LCD - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_RS EXP1_04_PIN #define LCD_BACKLIGHT_PIN -1 @@ -342,7 +345,6 @@ // Required for MKS_MINI_12864 with this board //#define MKS_LCD12864B - //#undef SHOW_BOOTSCREEN #elif ENABLED(FYSETC_MINI_12864_2_1) #define LCD_PINS_DC EXP1_04_PIN @@ -358,7 +360,7 @@ #endif //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 - #else // !MKS_MINI_12864 + #else // !MKS_MINI_12864 #define LCD_PINS_D4 EXP1_05_PIN #if IS_ULTIPANEL 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 14b3d6616830..342b585fe95e 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -113,18 +113,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PD14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PD1 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PD0 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PD14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PD1 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PD0 #endif #if HAS_TMC_UART @@ -162,7 +160,10 @@ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + #endif // HAS_TMC_UART // @@ -179,7 +180,7 @@ #define HEATER_1_PIN PB0 // HEATER2 #define HEATER_BED_PIN PA0 // HOT BED -#define FAN_PIN PB1 // FAN +#define FAN0_PIN PB1 // FAN // // Thermocouples @@ -238,23 +239,23 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_01_PIN PC5 -#define EXP1_02_PIN PE13 -#define EXP1_03_PIN PD13 -#define EXP1_04_PIN PC6 -#define EXP1_05_PIN PE14 -#define EXP1_06_PIN PE15 -#define EXP1_07_PIN PD11 -#define EXP1_08_PIN PD10 - -#define EXP2_01_PIN PA6 -#define EXP2_02_PIN PA5 -#define EXP2_03_PIN PE8 -#define EXP2_04_PIN PE10 -#define EXP2_05_PIN PE11 -#define EXP2_06_PIN PA7 -#define EXP2_07_PIN PE12 -#define EXP2_08_PIN -1 // RESET +#define EXP1_01_PIN PC5 +#define EXP1_02_PIN PE13 +#define EXP1_03_PIN PD13 +#define EXP1_04_PIN PC6 +#define EXP1_05_PIN PE14 +#define EXP1_06_PIN PE15 +#define EXP1_07_PIN PD11 +#define EXP1_08_PIN PD10 + +#define EXP2_01_PIN PA6 +#define EXP2_02_PIN PA5 +#define EXP2_03_PIN PE8 +#define EXP2_04_PIN PE10 +#define EXP2_05_PIN PE11 +#define EXP2_06_PIN PA7 +#define EXP2_07_PIN PE12 +#define EXP2_08_PIN -1 // RESET // // LCD SD @@ -270,19 +271,20 @@ #endif */ -// -// LCD / Controller #define SPI_FLASH -#define SPI_FLASH -#define SPI_DEVICE 2 -#define SPI_FLASH_SIZE 0x1000000 #if ENABLED(SPI_FLASH) + #define SPI_DEVICE 2 // Maple + #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif +// +// LCD / Controller +// + #if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) #ifndef TOUCH_CALIBRATION_X #define TOUCH_CALIBRATION_X -17253 @@ -335,13 +337,13 @@ #define LCD_USE_DMA_SPI //#define TFT_DRIVER ST7796 - #define TFT_BUFFER_SIZE 14400 + #define TFT_BUFFER_WORDS 14400 #elif HAS_WIRED_LCD #define BEEPER_PIN EXP1_01_PIN #define BTN_ENC EXP1_02_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_RS EXP1_04_PIN #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN @@ -358,9 +360,8 @@ // Required for MKS_MINI_12864 with this board //#define MKS_LCD12864B - //#undef SHOW_BOOTSCREEN - #else // !MKS_MINI_12864 + #else // !MKS_MINI_12864 #define LCD_PINS_D4 EXP1_05_PIN #if IS_ULTIPANEL diff --git a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h index 3f0d4e5ee924..3f55c7b291a2 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h @@ -75,7 +75,7 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN // X- -#elif EITHER(DUAL_X_CARRIAGE, NEEDS_X_MINMAX) +#elif ANY(DUAL_X_CARRIAGE, NEEDS_X_MINMAX) #ifndef X_MIN_PIN #define X_MIN_PIN X_DIAG_PIN // X- #endif @@ -113,7 +113,7 @@ #endif #if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) || ENABLED(USE_PROBE_FOR_Z_HOMING) - #ifndef Z_MIN_PROBE + #ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN E2_DIAG_PIN // defaults to 'Z+' connector #endif #endif @@ -186,19 +186,19 @@ #define HEATER_1_PIN PB0 // Heater1 #define HEATER_2_PIN PA3 // Heater2 -#define FAN_PIN PA2 // Fan0 +#define FAN0_PIN PA2 // Fan0 #define FAN1_PIN PA1 // Fan1 #define FAN2_PIN PA0 // Fan2 // -// Software SPI pins for TMC2130 stepper drivers -// This board doesn't support hardware SPI there +// Default pins for TMC software SPI +// This board only supports SW SPI for stepper drivers // #if HAS_TMC_SPI #define TMC_USE_SW_SPI - #define TMC_SW_MOSI PE14 - #define TMC_SW_MISO PE13 - #define TMC_SW_SCK PE12 + #define TMC_SPI_MOSI PE14 + #define TMC_SPI_MISO PE13 + #define TMC_SPI_SCK PE12 #endif // @@ -228,8 +228,11 @@ #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART /** ------ ------ * (BEEPER) PB2 | 1 2 | PE10 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) @@ -262,7 +265,7 @@ // SD Support // Onboard SD card use hardware SPI3 (defined in variant), LCD SD card use hardware SPI1 // -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION LCD #endif @@ -287,8 +290,9 @@ #endif // -// LCDs and Controllers +// LCD / Controller // + #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) @@ -307,7 +311,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #else @@ -317,7 +321,7 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -325,7 +329,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif @@ -350,7 +354,7 @@ #endif #endif -#endif // HAS_WIRED_LCD +#endif // HAS_WIRED_LCD // Alter timing for graphical display #if IS_U8GLIB_ST7920 diff --git a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h index 06bf09402c06..447c6227d6c1 100644 --- a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h +++ b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h @@ -144,14 +144,16 @@ #define K_SERIAL_RX_PIN K_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif -#endif +#endif // HAS_TMC_UART // // Heaters / Fans // -#define FAN_PIN PE2 +#define FAN0_PIN PE2 #define FAN1_PIN PE3 #define FAN2_PIN PE4 #define FAN3_PIN PE5 @@ -159,7 +161,7 @@ #define FAN_SOFT_PWM_REQUIRED // -// Neopixel +// NeoPixel // #define NEOPIXEL_PIN PC7 #define NEOPIXEL2_PIN PC8 @@ -171,9 +173,9 @@ #define MOSI_PIN PB5 #define SCK_PIN PB3 -#define TMC_SW_MISO MISO_PIN -#define TMC_SW_MOSI MOSI_PIN -#define TMC_SW_SCK SCK_PIN +#define TMC_SPI_MISO MISO_PIN +#define TMC_SPI_MOSI MOSI_PIN +#define TMC_SPI_SCK SCK_PIN // // I2C diff --git a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h index d16d7b200bd6..2f55fce4c388 100644 --- a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h +++ b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h @@ -141,14 +141,16 @@ #define K_SERIAL_RX_PIN K_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif -#endif +#endif // HAS_TMC_UART // // Heaters / Fans // -#define FAN_PIN PE2 +#define FAN0_PIN PE2 #define FAN1_PIN PE3 #define FAN2_PIN PE4 #define FAN3_PIN PE5 @@ -156,7 +158,7 @@ #define FAN_SOFT_PWM_REQUIRED // -// Neopixel +// NeoPixel // #define NEOPIXEL_PIN PC7 #define NEOPIXEL2_PIN PC8 @@ -168,9 +170,9 @@ #define MOSI_PIN PB5 #define SCK_PIN PB3 -#define TMC_SW_MISO MISO_PIN -#define TMC_SW_MOSI MOSI_PIN -#define TMC_SW_SCK SCK_PIN +#define TMC_SPI_MISO MISO_PIN +#define TMC_SPI_MOSI MOSI_PIN +#define TMC_SPI_SCK SCK_PIN // // I2C diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index 12871becbb40..4574df53ac11 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -91,16 +91,14 @@ #define E2_ENABLE_PIN PD0 #define E2_CS_PIN PD1 -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PA7 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PA6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PA5 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PA7 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PA6 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PA5 #endif // @@ -120,7 +118,7 @@ #define HEATER_2_PIN PC8 #define HEATER_BED_PIN PA1 -#define FAN_PIN PC9 +#define FAN0_PIN PC9 #define FAN1_PIN PA8 // @@ -141,28 +139,57 @@ #define SD_DETECT_PIN PB0 #define BEEPER_PIN PE8 +/** + * ------ ------ + * (BEEPER) ???? | 1 2 | PE7 (BTN_ENC) (MISO) ???? | 1 2 | ???? (SCK) + * (LCD_EN) PE9 | 3 4 | PE10 (LCD_RS) (BTN_EN1) PB2 | 3 4 | ???? (SD_SS) + * (LCD_D4) PE12 | 5 6 PE13 (LCD_D5) (BTN_EN2) PB1 | 5 6 ???? (MOSI) + * (LCD_D6) PE14 | 7 8 | PE15 (LCD_D7) (SD_DETECT) ???? | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | -- + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_01_PIN -1 +#define EXP1_02_PIN PE7 // ENC +#define EXP1_03_PIN PE9 +#define EXP1_04_PIN PE10 +#define EXP1_05_PIN PE12 +#define EXP1_06_PIN PE13 // CS +#define EXP1_07_PIN PE14 // A0 +#define EXP1_08_PIN PE15 + +#define EXP2_01_PIN -1 +#define EXP2_02_PIN -1 +#define EXP2_03_PIN PB2 // EN1 +#define EXP2_04_PIN -1 +#define EXP2_05_PIN PB1 // EN2 +#define EXP2_06_PIN -1 +#define EXP2_07_PIN -1 +#define EXP2_08_PIN -1 + // // LCD / Controller // + #if HAS_WIRED_LCD - #define BTN_EN1 PB2 - #define BTN_EN2 PB1 - #define BTN_ENC PE7 + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_RS PE10 - #define LCD_PINS_ENABLE PE9 - #define LCD_PINS_D4 PE12 + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS PE13 - #define DOGLCD_A0 PE14 + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_A0 EXP1_07_PIN #endif #if IS_ULTIPANEL - #define LCD_PINS_D5 PE13 - #define LCD_PINS_D6 PE14 - #define LCD_PINS_D7 PE15 + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder diff --git a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h index 4fb57985b993..d1a6da23b189 100644 --- a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h +++ b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h @@ -24,7 +24,7 @@ #define ALLOW_STM32DUINO #include "env_validate.h" -#if HOTENDS > 1 || E_STEPPERS > 1 +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "TH3D EZBoard only supports 1 hotend / E stepper." #endif @@ -45,7 +45,7 @@ #endif // -// Neopixels +// NeoPixel // #define NEOPIXEL_PIN PA8 @@ -61,7 +61,7 @@ // // Limit Switches // -#if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) +#if ANY(SENSORLESS_HOMING, SENSORLESS_PROBING) // Sensorless homing pins #if ENABLED(X_AXIS_SENSORLESS_HOMING) #define X_STOP_PIN PB4 @@ -132,9 +132,6 @@ #define E0_SERIAL_TX_PIN PC10 #define E0_SERIAL_RX_PIN PC11 - // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 - // Default TMC slave addresses #ifndef X_SLAVE_ADDRESS #define X_SLAVE_ADDRESS 0 @@ -148,7 +145,13 @@ #ifndef E0_SLAVE_ADDRESS #define E0_SLAVE_ADDRESS 3 #endif -#endif + + // Reduce baud rate to improve software serial reliability + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temp Sensors @@ -162,8 +165,8 @@ // #define HEATER_BED_PIN PC9 #define HEATER_0_PIN PC8 -#ifndef FAN_PIN - #define FAN_PIN PC6 +#ifndef FAN0_PIN + #define FAN0_PIN PC6 #endif #define FAN1_PIN PC7 @@ -233,7 +236,7 @@ #define BEEPER_PIN EXP1_01_PIN // Not connected in dev board #endif #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN //#define KILL_PIN -1 @@ -266,7 +269,7 @@ #endif -#if EITHER(CR10_STOCKDISPLAY, MKS_MINI_12864) +#if ANY(CR10_STOCKDISPLAY, MKS_MINI_12864) #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN #define BTN_ENC EXP1_02_PIN diff --git a/Marlin/src/pins/stm32f4/pins_TRONXY_V10.h b/Marlin/src/pins/stm32f4/pins_TRONXY_V10.h index 475dc42266a0..4e8e5158c0d9 100644 --- a/Marlin/src/pins/stm32f4/pins_TRONXY_V10.h +++ b/Marlin/src/pins/stm32f4/pins_TRONXY_V10.h @@ -73,9 +73,9 @@ #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x200000 // 2MB #define SPI_FLASH_CS_PIN PG15 // SPI2 - #define SPI_FLASH_MOSI_PIN PB5 - #define SPI_FLASH_MISO_PIN PB4 #define SPI_FLASH_SCK_PIN PB3 + #define SPI_FLASH_MISO_PIN PB4 + #define SPI_FLASH_MOSI_PIN PB5 #endif // @@ -152,12 +152,12 @@ #define HEATER_BED_PIN PE2 // HOT BED //#define HEATER_BED_INVERTING true -#define FAN_PIN PG0 // FAN0 +#define FAN0_PIN PG0 // FAN0 #define FAN1_PIN PB6 // FAN1 #define FAN2_PIN PG9 // FAN2 #define FAN3_PIN PF10 // FAN3 #define CONTROLLER_FAN_PIN PD7 // BOARD FAN -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED // // Laser / Spindle @@ -211,7 +211,7 @@ //#define TFT_PIXEL_OFFSET_X 48 //#define TFT_PIXEL_OFFSET_Y 32 //#define TFT_DRIVER ILI9488 - //#define TFT_BUFFER_SIZE 14400 + //#define TFT_BUFFER_WORDS 14400 #if NEED_TOUCH_PINS #define TOUCH_CS_PIN PD11 // SPI1_NSS @@ -253,14 +253,7 @@ // // SD Card // -#define SDIO_SUPPORT +#define ONBOARD_SDIO #define SD_DETECT_PIN -1 // PF0, but not connected #define SDIO_CLOCK 4500000 #define SDIO_READ_RETRIES 16 - -#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_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h deleted file mode 100644 index 21ab9d0e7019..000000000000 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ /dev/null @@ -1,226 +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 . - * - */ -#pragma once - -#define ALLOW_STM32DUINO -#include "env_validate.h" - -#if HOTENDS > 2 || E_STEPPERS > 2 - #error "STM32F4 VAkE supports up to 2 hotends / E steppers." -#endif - -#define DEFAULT_MACHINE_NAME "STM32F446VET6" -#define BOARD_INFO_NAME "STM32F4 VAkE" - -//#define I2C_EEPROM -#define MARLIN_EEPROM_SIZE 0x1000 // 4K - -// -// Servos -// -//#define SERVO0_PIN PE13 -//#define SERVO1_PIN PE14 - -// -// Limit Switches -// -#define X_STOP_PIN PE10 -#define Y_STOP_PIN PE9 -#define Z_STOP_PIN PE8 - -// -// Z Probe (when not Z_MIN_PIN) -// -#ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PA4 -#endif - -// -// Filament runout -// -#define FIL_RUNOUT_PIN PA3 - -// -// Steppers -// - -#define STEPPER_ENABLE_PIN PB2 - -#define X_STEP_PIN PC6 // X_STEP -#define X_DIR_PIN PC7 // X_DIR -#define X_ENABLE_PIN PB2 // -#ifndef X_CS_PIN - #define X_CS_PIN PC8 // X_CS -#endif - -#define Y_STEP_PIN PD9 // Y_STEP -#define Y_DIR_PIN PD10 // Y_DIR -#define Y_ENABLE_PIN PB2 // -#ifndef Y_CS_PIN - #define Y_CS_PIN PD11 // Y_CS -#endif - -#define Z_STEP_PIN PE15 // Z_STEP -#define Z_DIR_PIN PB10 // Z_DIR -#define Z_ENABLE_PIN PB2 -#ifndef Z_CS_PIN - #define Z_CS_PIN PD8 -#endif - -#define E0_STEP_PIN PB1 -#define E0_DIR_PIN PB13 -#define E0_ENABLE_PIN PB2 -#ifndef E0_CS_PIN - #define E0_CS_PIN PE11 -#endif - -#define E1_STEP_PIN PC4 -#define E1_DIR_PIN PC5 -#define E1_ENABLE_PIN PB2 -#ifndef E1_CS_PIN - #define E1_CS_PIN PB0 -#endif - -#define SD_SCK_PIN PE12 // PA5 // SPI1 for SD card -#define SD_MISO_PIN PE13 // PA6 -#define SD_MOSI_PIN PE14 // PA7 - -// added for SD card : optional or not ??? -//#define SD_CHIP_SELECT_PIN SDSS // The default chip select pin for the SD card is SS. -// The following three pins must not be redefined for hardware SPI. -//#define SPI_MOSI_PIN SD_MOSI_PIN // SPI Master Out Slave In pin -//#define SPI_MISO_PIN SD_MISO_PIN // SPI Master In Slave Out pin -//#define SPI_SCK_PIN SD_SCK_PIN // SPI Clock pin - -// -// Temperature Sensors (Analog inputs) -// - -#define TEMP_0_PIN PC0 // Analog Input -#define TEMP_1_PIN PC1 // Analog Input -#define TEMP_2_PIN PC2 // Analog Input -#define TEMP_3_PIN PC3 // Analog Input -#define TEMP_BED_PIN PC3 // Analog Input - -// -// Heaters / Fans -// - -#define HEATER_0_PIN PD15 -#define HEATER_1_PIN PD14 -#define HEATER_BED_PIN PD12 - -#ifndef FAN_PIN - #define FAN_PIN PD13 -#endif -#define FAN1_PIN PB5 // PA0 -#define FAN2_PIN PB4 // PA1 - -#ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN PD13 -#endif - -// -// Misc. Functions -// - -//#define CASE_LIGHT_PIN_CI PF13 -//#define CASE_LIGHT_PIN_DO PF14 -//#define NEOPIXEL_PIN PF13 - -// -// Průša i3 MK2 Multi Material Multiplexer Support -// -#if HAS_PRUSA_MMU1 - //#define E_MUX0_PIN PG3 - //#define E_MUX1_PIN PG4 -#endif - -#define LED_PIN PB14 // Alive -#define PS_ON_PIN PE0 -#define KILL_PIN PD5 -#define POWER_LOSS_PIN PA4 // ?? Power loss / nAC_FAULT - -#if ENABLED(SDSUPPORT) - #define SD_DETECT_PIN EXP2_07_PIN - #define SD_SS_PIN PB15 // USD_CS -> CS for onboard SD -#endif - -/** - * ------ ------ - * PC9 | 1 2 | PB12 ? | 1 2 | ? - * PD7 | 3 4 | PC12 PD6 | 3 4 | ? - * PD1 | 5 6 PD2 PD0 | 5 6 ? - * PD3 | 7 8 | PD4 PB7 | 7 8 | RESET - * GND | 9 10 | 5V GND | 9 10 | 3.3V - * ------ ------ - * EXP1 EXP2 - */ -#define EXP1_01_PIN PC9 -#define EXP1_02_PIN PB12 -#define EXP1_03_PIN PD7 -#define EXP1_04_PIN PC12 -#define EXP1_05_PIN PD1 -#define EXP1_06_PIN PD2 -#define EXP1_07_PIN PD3 -#define EXP1_08_PIN PD4 - -//#define EXP2_01_PIN ? -//#define EXP2_02_PIN ? -#define EXP2_03_PIN PD6 -//#define EXP2_04_PIN ? -#define EXP2_05_PIN PD0 -//#define EXP2_06_PIN ? -#define EXP2_07_PIN PB7 -#define EXP2_08_PIN -1 - -// -// LCD / Controller -// -#if HAS_WIRED_LCD - - #if ENABLED(SDSUPPORT) - #define SDSS PB6 // CS for SD card in LCD - #endif - - #define BEEPER_PIN EXP1_01_PIN - - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN - #define BTN_ENC EXP1_02_PIN - - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_RS EXP1_04_PIN - - #define LCD_PINS_D4 EXP1_05_PIN - #define LCD_PINS_D5 EXP1_06_PIN - #define LCD_PINS_D6 EXP1_07_PIN - #define LCD_PINS_D7 EXP1_08_PIN - -#endif - -// Alter timing for graphical display -#if IS_U8GLIB_ST7920 - #define BOARD_ST7920_DELAY_1 96 - #define BOARD_ST7920_DELAY_2 48 - #define BOARD_ST7920_DELAY_3 715 -#endif diff --git a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h index 48f986e2ca70..d9c542c6a281 100644 --- a/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h +++ b/Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h @@ -154,8 +154,8 @@ #define HEATER_0_PIN PA15 // PWM Capable, TIM2_CH1 #define HEATER_BED_PIN PB3 // PWM Capable, TIM2_CH2 -#ifndef FAN_PIN - #define FAN_PIN PB10 // PWM Capable, TIM2_CH3 +#ifndef FAN0_PIN + #define FAN0_PIN PB10 // PWM Capable, TIM2_CH3 #endif #define FAN1_PIN PB11 // PWM Capable, TIM2_CH4 @@ -181,12 +181,13 @@ // // LCD / Controller // + #if IS_RRD_FG_SC #define BEEPER_PIN PC7 // LCD_BEEPER #define BTN_ENC PE11 // BTN_ENC #define SD_DETECT_PIN PD14 #define LCD_PINS_RS PF12 // LCD_RS - #define LCD_PINS_ENABLE PD15 // LCD_EN + #define LCD_PINS_EN PD15 // LCD_EN #define LCD_PINS_D4 PB13 // LCD_D4 #define BTN_EN1 PF13 // BTN_EN1 #define BTN_EN2 PE9 // BTN_EN2 diff --git a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h index c4feba692fd8..2db21be45ed5 100644 --- a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h +++ b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h @@ -95,8 +95,8 @@ #define HEATER_0_PIN 33 #define HEATER_BED_PIN 31 -#ifndef FAN_PIN - #define FAN_PIN 30 // "FAN1" +#ifndef FAN0_PIN + #define FAN0_PIN 30 // "FAN1" #endif #define FAN1_PIN 32 // "FAN2" @@ -120,7 +120,7 @@ #define SD_DETECT_PIN 56 // SD_CARD_DET #define BEEPER_PIN 46 // LCD_BEEPER #define LCD_PINS_RS 49 // LCD_RS -#define LCD_PINS_ENABLE 48 // LCD_EN +#define LCD_PINS_EN 48 // LCD_EN #define LCD_PINS_D4 50 // LCD_D4 #define LCD_PINS_D5 51 // LCD_D5 #define LCD_PINS_D6 52 // LCD_D6 diff --git a/Marlin/src/pins/stm32g0/env_validate.h b/Marlin/src/pins/stm32g0/env_validate.h index a7be76bd8bb1..03887eb7a491 100644 --- a/Marlin/src/pins/stm32g0/env_validate.h +++ b/Marlin/src/pins/stm32g0/env_validate.h @@ -19,8 +19,11 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if NOT_TARGET(STM32G0xx) || NOT_TARGET(STM32G0B1xx) #error "Oops! Select an STM32G0 board in 'Tools > Board.'" #endif + +#endif diff --git a/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h b/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h index 3de67ea8d591..8b4590013537 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h @@ -38,7 +38,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #undef NO_EEPROM_SELECTED #ifndef FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION @@ -80,17 +80,6 @@ // // Steppers // -#define X_ENABLE_PIN -1 -#define X_STEP_PIN PA10 // Unused. Assigned so Marlin will compile -#define X_DIR_PIN -1 - -#define Y_ENABLE_PIN -1 -#define Y_STEP_PIN PA10 // Unused. Assigned so Marlin will compile -#define Y_DIR_PIN -1 - -#define Z_ENABLE_PIN -1 -#define Z_STEP_PIN PA10 // Unused. Assigned so Marlin will compile -#define Z_DIR_PIN -1 #define E0_ENABLE_PIN PD2 #define E0_STEP_PIN PD0 @@ -110,7 +99,9 @@ #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif // Default TMC slave addresses #ifndef E0_SLAVE_ADDRESS @@ -134,8 +125,9 @@ // // Heaters / Fans // -#define HEATER_0_PIN PA2 // "HE" -#define FAN_PIN PA0 // "FAN0" +#define HEATER_0_PIN PA2 // "HE" V1.1 +#define HEATER_1_PIN PB13 // "HE" V1.2 +#define FAN0_PIN PA0 // "FAN0" #define FAN1_PIN PA1 // "FAN1" // @@ -148,6 +140,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD #define BTN_EN1 PB7 #define BTN_EN2 PB5 diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h index 54c2c4c77b2d..c2c16ba696bd 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h @@ -35,7 +35,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #undef NO_EEPROM_SELECTED #ifndef FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION @@ -53,10 +53,8 @@ // // Probe enable // -#if ENABLED(PROBE_ENABLE_DISABLE) - #ifndef PROBE_ENABLE_PIN - #define PROBE_ENABLE_PIN SERVO0_PIN - #endif +#if ENABLED(PROBE_ENABLE_DISABLE) && !defined(PROBE_ENABLE_PIN) + #define PROBE_ENABLE_PIN SERVO0_PIN #endif // @@ -143,18 +141,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PC12 // Shared with SPI header, Pin 5 (SPI3) - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PC11 // Shared with SPI header, Pin 6 (SPI3) - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PC10 // Shared with SPI header, Pin 4 (SPI3) - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PC12 // Shared with SPI header, Pin 5 (SPI3) +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PC11 // Shared with SPI header, Pin 6 (SPI3) +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PC10 // Shared with SPI header, Pin 4 (SPI3) #endif #if HAS_TMC_UART @@ -174,8 +170,11 @@ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -191,7 +190,7 @@ #define HEATER_1_PIN PB10 // "HE1" #define HEATER_BED_PIN PB2 // "HB" -#define FAN_PIN PA8 // "FAN0" +#define FAN0_PIN PA8 // "FAN0" #define FAN1_PIN PB15 // "FAN1" #define FAN2_PIN PB14 // "FAN2" @@ -237,21 +236,36 @@ #define EXP1_10_PIN -1 #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI + /** + * ------ ------ --- + * (PC1) BEEP | 1 2 | | 1 2 | | 1 | (5V) + * | 3 4 | RX | 3 4 | TX | 2 | (GND) + * (PC0) ENT 5 6 | ENT 5 6 | BEEP | 3 | RX (PD8) + * (PA2) B | 7 8 | A (PA1) B | 7 8 | A | 4 | TX (PD9) + * GND | 9 10 | 5V GND | 9 10 | VCC | 5 | (RST) + * ------ ------ --- + * EXP1 DWIN TFT + * + * DWIN pins are labeled as printed on DWIN PCB. GND, VCC, A, B, ENT & BEEP can be connected in the same orientation as the + * existing plug/DWIN to EXP1. DWIN TX/RX need to be connected to the Manta E3 EZ's TFT port, with DWIN TX->PD9, DWIN RX->PD8. + * + * Needs custom cable: + * + * Board Adapter Display + * ------------------------------------------ + * (EXP1-1) PC1 <-----------> BEEP (DWIN-6) + * (EXP1-5) PC0 <-----------> ENT (DWIN-5) + * (TFT-4) PD9 <-----------> RX (DWIN-3) + * (TFT-3) PD8 <-----------> TX (DWIN-4) + * (EXP1-7) PA2 <-----------> B (DWIN-7) + * (EXP1-9) GND <-----------> GND (DWIN-9) + * (EXP1-8) PA1 <-----------> A (DWIN-8) + * (EXP1-10) 5V <-----------> VCC (DWIN-10) + */ #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! Ender-3 V2 display requires a custom cable with TX = PA0, RX = PC2. See 'pins_BTT_MANTA_E3_EZ_V1_0.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" #endif - /** - * Ender-3 V2 display Manta E3 EZ V1.0 Ender-3 V2 display --> Manta E3 EZ V1.0 - * ------ ------ RX 3 --> 5 P0_15 - * -- | 1 2 | -- (BEEPER) PC1 | 1 2 | PC2 (BTN_ENC) TX 4 --> 9 P0_16 - * (MANTA TX1) RX | 3 4 | TX (MANTA RX1) (BTN_EN1) PC3 | 3 4 | RESET BEEPER 6 --> 10 P2_08 - * (BTN_ENC) ENT 5 6 | BEEPER (BTN_EN2) PC0 5 6 | PA0 (LCD_D4) - * (BTN_E2) B | 7 8 | A (BTN_E1) (LCD_RS) PA2 | 7 8 | PA1 (LCD_EN) - * GND | 9 10 | 5V GND | 9 10 | 5V - * ------ ------ - */ - #define BEEPER_PIN EXP1_01_PIN #define BTN_EN1 EXP1_08_PIN #define BTN_EN2 EXP1_07_PIN @@ -268,7 +282,7 @@ #define BTN_ENC EXP1_02_PIN #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! @@ -278,14 +292,14 @@ #endif #define LCD_PINS_RS EXP1_06_PIN - #define LCD_PINS_ENABLE EXP1_02_PIN + #define LCD_PINS_EN EXP1_02_PIN #define LCD_PINS_D4 EXP1_07_PIN #define LCD_PINS_D5 EXP1_05_PIN #define LCD_PINS_D6 EXP1_03_PIN #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN PA7 // Repurpose default SERVO0_PIN for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN @@ -309,14 +323,13 @@ // // SD Support // - #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD #endif #define SD_DETECT_PIN -1 -#if SD_CONNECTION_IS(LCD) && (BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) +#if SD_CONNECTION_IS(LCD) && (ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) #define SD_SS_PIN EXP1_05_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "SD CUSTOM_CABLE is not compatible with Manta E3 EZ." diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V2_1.h similarity index 91% rename from Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V1_0.h rename to Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V2_1.h index 876475f88355..4d1f0fb51c8c 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V1_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V2_1.h @@ -26,7 +26,7 @@ //#define BOARD_CUSTOM_BUILD_FLAGS -DTONE_CHANNEL=4 -DTONE_TIMER=4 -DTIMER_TONE=4 #ifndef BOARD_INFO_NAME - #define BOARD_INFO_NAME "BTT Manta M4P V1.0" + #define BOARD_INFO_NAME "BTT Manta M4P V2.1" #endif #define USES_DIAG_JUMPERS @@ -37,7 +37,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #undef NO_EEPROM_SELECTED #ifndef FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION @@ -55,10 +55,8 @@ // // Probe enable // -#if ENABLED(PROBE_ENABLE_DISABLE) - #ifndef PROBE_ENABLE_PIN - #define PROBE_ENABLE_PIN SERVO0_PIN - #endif +#if ENABLED(PROBE_ENABLE_DISABLE) && !defined(PROBE_ENABLE_PIN) + #define PROBE_ENABLE_PIN SERVO0_PIN #endif // @@ -112,18 +110,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB15 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB14 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB13 #endif #if HAS_TMC_UART @@ -140,8 +136,11 @@ #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -155,7 +154,7 @@ #define HEATER_0_PIN PC8 // "HE" #define HEATER_BED_PIN PD8 // "HB" -#define FAN_PIN PD2 // "FAN0" +#define FAN0_PIN PD2 // "FAN0" #define FAN1_PIN PD3 // "FAN1" #define FAN2_PIN PD4 // "FAN2" @@ -209,8 +208,9 @@ #endif // -// LCDs and Controllers +// LCD / Controller // + #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) @@ -229,7 +229,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) @@ -246,7 +246,7 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -258,7 +258,7 @@ // results in LCD soft SPI mode 3, SD soft SPI mode 0 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h index f4ce5a16d3b0..35038ca2df67 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h @@ -35,7 +35,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #undef NO_EEPROM_SELECTED #ifndef FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION @@ -53,10 +53,8 @@ // // Probe enable // -#if ENABLED(PROBE_ENABLE_DISABLE) - #ifndef PROBE_ENABLE_PIN - #define PROBE_ENABLE_PIN SERVO0_PIN - #endif +#if ENABLED(PROBE_ENABLE_DISABLE) && !defined(PROBE_ENABLE_PIN) + #define PROBE_ENABLE_PIN SERVO0_PIN #endif // @@ -79,8 +77,8 @@ // Z Probe (when not Z_STOP_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PC13 // PROBE - //#define Z_MIN_PROBE_PIN PC15 // IND-DET (with adjustable pullup set via jumper) + #define Z_MIN_PROBE_PIN PC13 // PROBE + //#define Z_MIN_PROBE_PIN PC15 // IND-DET (with adjustable pullup set via jumper) #endif // @@ -129,18 +127,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 // Shared with SPI header, Pin 5 (SPI2) - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 // Shared with SPI header, Pin 6 (SPI2) - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 // Shared with SPI header, Pin 4 (SPI2) - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB15 // Shared with SPI header, Pin 5 (SPI2) +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB14 // Shared with SPI header, Pin 6 (SPI2) +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB13 // Shared with SPI header, Pin 4 (SPI2) #endif #if HAS_TMC_UART @@ -160,8 +156,11 @@ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -177,7 +176,7 @@ #define HEATER_1_PIN PA7 // "HE1" #define HEATER_BED_PIN PA5 // "HB" -#define FAN_PIN PA4 // "FAN0" +#define FAN0_PIN PA4 // "FAN0" #define FAN1_PIN PA3 // "FAN1" // @@ -237,8 +236,9 @@ #endif // -// LCDs and Controllers +// LCD / Controller // + #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) @@ -257,7 +257,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) @@ -274,7 +274,7 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -286,7 +286,7 @@ // results in LCD soft SPI mode 3, SD soft SPI mode 0 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_0.h index 4f8d30b6b7fa..824e44130f6e 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_0.h @@ -64,8 +64,11 @@ #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // NeoPixel LED diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_1.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_1.h index a21bb59e69c3..d7c15eaa047e 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_1.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_V1_1.h @@ -63,8 +63,11 @@ #define E3_SERIAL_RX_PIN E3_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // NeoPixel LED diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h index 6516538c4402..8fc2bdf33c18 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h @@ -33,7 +33,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #undef NO_EEPROM_SELECTED #ifndef FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION @@ -51,10 +51,8 @@ // // Probe enable // -#if ENABLED(PROBE_ENABLE_DISABLE) - #ifndef PROBE_ENABLE_PIN - #define PROBE_ENABLE_PIN SERVO0_PIN - #endif +#if ENABLED(PROBE_ENABLE_DISABLE) && !defined(PROBE_ENABLE_PIN) + #define PROBE_ENABLE_PIN SERVO0_PIN #endif // @@ -99,7 +97,7 @@ #else #define X_MIN_PIN E0_DIAG_PIN // MIN5 #endif -#elif EITHER(DUAL_X_CARRIAGE, NEEDS_X_MINMAX) +#elif ANY(DUAL_X_CARRIAGE, NEEDS_X_MINMAX) #ifndef X_MIN_PIN #define X_MIN_PIN X_DIAG_PIN // MIN1 #endif @@ -179,18 +177,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PA7 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PA6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PA5 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PA7 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PA6 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PA5 #endif #if HAS_TMC_UART @@ -210,8 +206,11 @@ #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -231,7 +230,7 @@ #define HEATER_2_PIN PB6 // HE2 #define HEATER_3_PIN PE1 // HE3 -#define FAN_PIN PE6 // FAN0 +#define FAN0_PIN PE6 // FAN0 #define FAN1_PIN PE0 // FAN1 #define FAN2_PIN PC12 // FAN2 #define FAN3_PIN PE5 // FAN3 @@ -301,8 +300,9 @@ #endif // -// LCDs and Controllers +// LCD / Controller // + #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) @@ -321,7 +321,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) @@ -338,7 +338,7 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -350,7 +350,7 @@ // results in LCD soft SPI mode 3, SD soft SPI mode 0 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h index f71b7b40ebd1..450e7b06b057 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h @@ -37,7 +37,7 @@ #define LED_PIN PD8 // Onboard I2C EEPROM -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #undef NO_EEPROM_SELECTED #define I2C_EEPROM #define SOFT_I2C_EEPROM // Force the use of Software I2C @@ -136,7 +136,7 @@ // #define HEATER_0_PIN PC8 // "HE" #define HEATER_BED_PIN PC9 // "HB" -#define FAN_PIN PC6 // "FAN0" +#define FAN0_PIN PC6 // "FAN0" #define FAN1_PIN PC7 // "FAN1" #define FAN2_PIN PB15 // "FAN2" @@ -196,7 +196,7 @@ * CS | 3 4 | SCK (EN1) PA10 | 3 4 | -- * MOSI | 5 6 | MISO (EN2) PA9 5 6 | MOSI * 3V3 | 7 8 | GND -- | 7 8 | -- - * ------ GND | 9 10| RESET (Kill) + * ------ GND | 9 10 | RESET (Kill) * SPI ------ * EXP2 * @@ -205,7 +205,7 @@ * PA9 | 3 4 | RESET (LCD CS) PB8 | 3 4 | PD6 (LCD_A0) * PA10 5 6 | PB9 (RESET) PB9 5 6 | PA15 (DIN) * PB8 | 7 8 | PD6 -- | 7 8 | -- - * GND | 9 10| 5V GND | 9 10| 5V + * GND | 9 10 | 5V GND | 9 10 | 5V * ------ ------ * EXP1 EXP1 */ @@ -238,7 +238,7 @@ #define BTN_EN2 EXP1_05_PIN #define LCD_PINS_RS EXP1_07_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! @@ -248,14 +248,14 @@ #endif #define LCD_PINS_RS EXP1_06_PIN - #define LCD_PINS_ENABLE EXP1_02_PIN + #define LCD_PINS_EN EXP1_02_PIN #define LCD_PINS_D4 EXP1_07_PIN #define LCD_PINS_D5 EXP1_05_PIN #define LCD_PINS_D6 EXP1_03_PIN #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP1_03_PIN @@ -322,7 +322,7 @@ * ------ ------ * (EN2) PB5 | 1 2 | PA15(BTN_ENC) 5V |10 9 | GND * (LCD_CS) PA9 | 3 4 | RST (RESET) -- | 8 7 | -- - * (LCD_A0) PA10 5 6 | PB9 (EN1) (DIN) | 6 5 (RESET) + * (LCD_A0) PA10 5 6 | PB9 (EN1) (DIN) | 6 5 (RESET) LCD_RESET * (LCD_SCK)PB8 | 7 8 | PD6 (MOSI) (LCD_A0) | 4 3 | (LCD_CS) * GND | 9 10 | 5V (BTN_ENC) | 2 1 | -- * ------ ------ @@ -330,7 +330,7 @@ * * ------ * -- |10 9 | -- - * --- (RESET) | 8 7 | -- + * --- RESET_BUTTON (RESET) | 8 7 | -- * | 3 | (MOSI) | 6 5 (EN2) * | 2 | (DIN) -- | 4 3 | (EN1) * | 1 | (LCD_SCK)| 2 1 | -- @@ -338,6 +338,7 @@ * Neopixel EXP2 * * Needs custom cable. Connect EN2-EN2, LCD_CS-LCD_CS and so on. + * Note: The RESET line is connected to 3 pins. * * Check the index/notch position twice!!! * On BTT boards pins from IDC10 connector are numbered in unusual order. @@ -363,7 +364,7 @@ #endif // HAS_WIRED_LCD -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" @@ -416,7 +417,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC3 -#elif SD_CONNECTION_IS(LCD) && (BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) +#elif SD_CONNECTION_IS(LCD) && (ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) #define SD_DETECT_PIN EXP1_01_PIN #define SD_SS_PIN EXP1_05_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) @@ -434,7 +435,7 @@ #define SD_MOSI_PIN PA7 // -// Default NEOPIXEL_PIN +// NeoPixel // #ifndef NEOPIXEL_PIN #define NEOPIXEL_PIN PA8 // LED driving pin diff --git a/Marlin/src/pins/stm32h7/env_validate.h b/Marlin/src/pins/stm32h7/env_validate.h index 0c515e5df6be..7feaf2095909 100644 --- a/Marlin/src/pins/stm32h7/env_validate.h +++ b/Marlin/src/pins/stm32h7/env_validate.h @@ -19,8 +19,11 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if NOT_TARGET(STM32H7) #error "Oops! Select an STM32H7 board in 'Tools > Board.'" #endif + +#endif diff --git a/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h b/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h index 13e30591ba6a..07c6d0d49960 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h @@ -28,7 +28,7 @@ #define USES_DIAG_JUMPERS // Onboard I2C EEPROM -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #undef NO_EEPROM_SELECTED #define I2C_EEPROM #define SOFT_I2C_EEPROM // Force the use of Software I2C @@ -45,20 +45,15 @@ // #define SERVO0_PIN PB14 -// -// Misc. Functions -// -#define LED_PIN PA14 - // // Trinamic Stallguard pins // #define X_DIAG_PIN PF0 // M1-STOP #define Y_DIAG_PIN PF2 // M2-STOP #define Z_DIAG_PIN PF4 // M3-STOP -#define Z2_DIAG_PIN PF3 // M4-STOP -#define E0_DIAG_PIN PF1 // M5-STOP -#define E1_DIAG_PIN PC15 // M6-STOP +#define Z2_DIAG_PIN PF3 // M4-DET +#define E0_DIAG_PIN PF1 // M5-DET +#define E1_DIAG_PIN PC15 // M6-DET #define E2_DIAG_PIN PF12 // PWRDET // @@ -91,16 +86,16 @@ #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN #if X_HOME_TO_MIN - #define X_MAX_PIN E0_DIAG_PIN // E0DET + #define X_MAX_PIN E0_DIAG_PIN // M4-DET #else - #define X_MIN_PIN E0_DIAG_PIN // E0DET + #define X_MIN_PIN E0_DIAG_PIN // M4-DET #endif -#elif EITHER(DUAL_X_CARRIAGE, NEEDS_X_MINMAX) +#elif ANY(DUAL_X_CARRIAGE, NEEDS_X_MINMAX) #ifndef X_MIN_PIN #define X_MIN_PIN X_DIAG_PIN // X-STOP #endif #ifndef X_MAX_PIN - #define X_MAX_PIN E0_DIAG_PIN // E0DET + #define X_MAX_PIN E0_DIAG_PIN // M4-DET #endif #else #define X_STOP_PIN X_DIAG_PIN // X-STOP @@ -109,16 +104,16 @@ #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN #if Y_HOME_TO_MIN - #define Y_MAX_PIN E1_DIAG_PIN // E1DET + #define Y_MAX_PIN E1_DIAG_PIN // M5-DET #else - #define Y_MIN_PIN E1_DIAG_PIN // E1DET + #define Y_MIN_PIN E1_DIAG_PIN // M5-DET #endif #elif ENABLED(NEEDS_Y_MINMAX) #ifndef Y_MIN_PIN #define Y_MIN_PIN Y_DIAG_PIN // Y-STOP #endif #ifndef Y_MAX_PIN - #define Y_MAX_PIN E1_DIAG_PIN // E1DET + #define Y_MAX_PIN E1_DIAG_PIN // M5-DET #endif #else #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP @@ -143,24 +138,17 @@ #endif // -// Filament Runout Sensor -// -#define FIL_RUNOUT_PIN PF1 // E0DET -#define FIL_RUNOUT2_PIN PF15 // E1DET - -// -// Power Supply Control +// Z Probe (when not Z_MIN_PIN) // -#ifndef PS_ON_PIN - #define PS_ON_PIN PF13 // PS-ON +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PB15 #endif // -// Power Loss Detection +// Filament Runout Sensor // -#ifndef POWER_LOSS_PIN - #define POWER_LOSS_PIN PF12 // PWRDET -#endif +#define FIL_RUNOUT_PIN PF1 // M5-DET +#define FIL_RUNOUT2_PIN PC15 // M6-DET // // Steppers @@ -253,7 +241,7 @@ #define HEATER_2_PIN PF9 // Heater2 #define HEATER_3_PIN PF7 // Heater3 -#define FAN_PIN PA6 // Fan0 +#define FAN0_PIN PA6 // Fan0 #define FAN1_PIN PA5 // Fan1 #define FAN2_PIN PA4 // Fan2 #define FAN3_PIN PA3 // Fan3 @@ -261,6 +249,31 @@ #define FAN5_PIN PF8 // 4 wire Fan5 #define FAN6_PIN PA2 // 4 wire Fan6 +// +// Power Supply Control +// +#ifndef PS_ON_PIN + #define PS_ON_PIN PF13 // PS-ON +#endif + +// +// Power Loss Detection +// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PF12 // PWRDET +#endif + +// +// Misc. Functions +// +#define LED_PIN PA14 +#ifndef FILWIDTH_PIN + #define FILWIDTH_PIN PC0 +#endif +#ifndef FILWIDTH2_PIN + #define FILWIDTH2_PIN PF10 +#endif + // // SD Support // @@ -273,18 +286,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// Default pins for TMC software SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PE14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PE13 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PE12 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PE14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PE13 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PE12 #endif #if HAS_TMC_UART @@ -337,10 +348,14 @@ #define E5_SERIAL_RX_PIN E3_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART /** + * 18-pin FPC Connector * ---- * (MISO) PE13 | 1 | * (SCK) PE12 | 2 | @@ -412,102 +427,39 @@ #endif // -// LCDs and Controllers +// LCD / Controller // -#if IS_TFTGLCD_PANEL - #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_03_PIN - #endif - -#elif HAS_WIRED_LCD +#if ENABLED(BTT_MINI_12864) // BTT Mini 12864 V2.0 connected via 18-pin FPC cable #define BEEPER_PIN EXP1_01_PIN #define BTN_ENC EXP1_02_PIN + #define LCD_PINS_RS EXP1_04_PIN - #if ENABLED(CR10_STOCKDISPLAY) - - #define LCD_PINS_RS EXP1_07_PIN - - #define BTN_EN1 EXP1_03_PIN - #define BTN_EN2 EXP1_05_PIN - - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN - - #else - - #define LCD_PINS_RS EXP1_04_PIN - - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN - - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN - - #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_03_PIN - #define DOGLCD_A0 EXP1_04_PIN - #define DOGLCD_SCK EXP2_02_PIN - #define DOGLCD_MOSI EXP2_06_PIN - - #define SOFTWARE_SPI - #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_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) - #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_06_PIN - #endif - #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_07_PIN - #endif - #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_08_PIN - #endif - #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_06_PIN - #endif - #endif // !FYSETC_MINI_12864 - - #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_06_PIN - #define LCD_PINS_D6 EXP1_07_PIN - #define LCD_PINS_D7 EXP1_08_PIN - - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder - #endif - - #endif + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #endif -#endif // HAS_WIRED_LCD + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN -// Alter timing for graphical display -#if IS_U8GLIB_ST7920 - #define BOARD_ST7920_DELAY_1 120 - #define BOARD_ST7920_DELAY_2 80 - #define BOARD_ST7920_DELAY_3 580 -#endif + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define DOGLCD_SCK EXP2_02_PIN + #define DOGLCD_MOSI EXP2_06_PIN -#if HAS_SPI_TFT - #define TFT_CS_PIN EXP2_04_PIN - #define TFT_A0_PIN EXP2_07_PIN - #define TFT_SCK_PIN EXP2_02_PIN - #define TFT_MISO_PIN EXP2_01_PIN - #define TFT_MOSI_PIN EXP2_06_PIN + #define SOFTWARE_SPI + #define FORCE_SOFT_SPI // Use this if Hardware SPI causes display problems. + // Results in LCD Software SPI mode 3, SD Software SPI mode 0. - #define TOUCH_INT_PIN EXP1_07_PIN - #define TOUCH_MISO_PIN EXP1_06_PIN - #define TOUCH_MOSI_PIN EXP1_03_PIN - #define TOUCH_SCK_PIN EXP1_05_PIN - #define TOUCH_CS_PIN EXP1_04_PIN + //#define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. + #define NEOPIXEL_PIN EXP1_06_PIN - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN - #define BTN_ENC EXP1_02_PIN +#elif HAS_WIRED_LCD + #error "Only BTT_MINI_12864 (BTT Mini 12864 V2.0 with FPC cable) is currently supported on the BIGTREE_OCTOPUS_MAX_EZ." #endif // @@ -516,28 +468,26 @@ #ifndef NEOPIXEL_PIN #define NEOPIXEL_PIN PE10 #endif - #ifndef NEOPIXEL2_PIN #define NEOPIXEL2_PIN PE9 #endif +// +// WiFi +// #if ENABLED(WIFISUPPORT) - // - // WIFI - // - /** - * ------- - * GND | 9 | | 8 | 3.3V - * (ESP-CS) PG1 | 10 | | 7 | PB15 (ESP-MOSI) - * 3.3V | 11 | | 6 | PB14 (ESP-MISO) - * (ESP-IO0) PG0 | 12 | | 5 | PB13 (ESP-CLK) - * (ESP-IO4) PF15 | 13 | | 4 | -- - * -- | 14 | | 3 | 3.3V (ESP-EN) - * (ESP-RX) PE7 | 15 | | 2 | -- - * (ESP-TX) PE8 | 16 | | 1 | PB2 (ESP-RST) - * ------- - * WIFI + * -------- + * GND | 9 8 | 3.3V + * (ESP-CS) PG1 | 10 7 | PB15 (ESP-MOSI) + * 3.3V | 11 6 | PB14 (ESP-MISO) + * (ESP-IO0) PG0 | 12 5 | PB13 (ESP-CLK) + * (ESP-IO4) PF15 | 13 4 | -- + * -- | 14 3 | 3.3V (ESP-EN) + * (ESP-RX) PE7 | 15 2 | -- + * (ESP-TX) PE8 | 16 1 | PB2 (ESP-RST) + * -------- + * WIFI */ #define ESP_WIFI_MODULE_COM 7 // Must also set either SERIAL_PORT or SERIAL_PORT_2 to this #define ESP_WIFI_MODULE_BAUDRATE BAUDRATE // Must use same BAUDRATE as SERIAL_PORT & SERIAL_PORT_2 diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h index d06e27d9c0b1..1d21dbde9b14 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h @@ -23,7 +23,7 @@ #include "env_validate.h" -#define DEFAULT_MACHINE_NAME "Biqu BX" +#define DEFAULT_MACHINE_NAME "BIQU BX" // Onboard I2C EEPROM #define I2C_EEPROM @@ -91,18 +91,16 @@ #define E1_CS_PIN PC8 // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PC6 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PG3 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PC7 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PC6 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PG3 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PC7 #endif #if HAS_TMC_UART @@ -143,8 +141,11 @@ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // Temperature Sensors @@ -160,7 +161,7 @@ #define HEATER_1_PIN PC5 #define HEATER_BED_PIN PA4 -#define FAN_PIN PA5 // "FAN0" +#define FAN0_PIN PA5 // "FAN0" #define FAN1_PIN PA6 // "FAN1" #define FAN2_PIN PA7 // "FAN2" diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h index b9e1ff10ad16..a3e4a84adcc9 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h @@ -23,12 +23,16 @@ #include "env_validate.h" +// +// https://github.com/bigtreetech/SKR-3 +// + // 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 -#if BOTH(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) - #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) +#if ALL(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) + #if ANY(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) #define EXP_MOT_USE_EXP2_ONLY 1 #else #error "You can't use both an LCD and a Motor Expansion Module on EXP1/EXP2 at the same time." @@ -38,7 +42,7 @@ #define USES_DIAG_JUMPERS // Onboard I2C EEPROM -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #undef NO_EEPROM_SELECTED #define I2C_EEPROM #define SOFT_I2C_EEPROM // Force the use of Software I2C @@ -119,6 +123,7 @@ #define Z_STOP_PIN PC0 // Z-STOP #endif #endif +#define ONBOARD_ENDSTOPPULLUPS // Board has built-in pullups // // Z Probe (when not Z_MIN_PIN) @@ -130,10 +135,8 @@ // // Probe enable // -#if ENABLED(PROBE_ENABLE_DISABLE) - #ifndef PROBE_ENABLE_PIN - #define PROBE_ENABLE_PIN SERVO0_PIN - #endif +#if ENABLED(PROBE_ENABLE_DISABLE) && !defined(PROBE_ENABLE_PIN) + #define PROBE_ENABLE_PIN SERVO0_PIN #endif // @@ -239,8 +242,8 @@ #ifndef HEATER_BED_PIN #define HEATER_BED_PIN PD7 // Hotbed #endif -#ifndef FAN_PIN - #define FAN_PIN PB7 // Fan0 +#ifndef FAN0_PIN + #define FAN0_PIN PB7 // Fan0 #endif #if HAS_CUTTER @@ -260,18 +263,16 @@ #endif // SPINDLE_FEATURE || LASER_FEATURE // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PE13 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PE15 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PE14 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PE13 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PE15 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PE14 #endif #if HAS_TMC_UART @@ -312,8 +313,11 @@ #define E1_SERIAL_RX_PIN E1_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif + +#endif // HAS_TMC_UART // // SD Connection @@ -362,7 +366,7 @@ #define SD_MOSI_PIN EXP2_06_PIN #define SD_DETECT_PIN EXP2_07_PIN #elif SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT + #define ONBOARD_SDIO #define SDIO_CLOCK 24000000 // 24MHz #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "No custom SD drive cable defined for this board." @@ -427,8 +431,9 @@ #endif // BTT_MOTOR_EXPANSION // -// LCDs and Controllers +// LCD / Controller // + #if IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) @@ -447,7 +452,7 @@ #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #define LCD_PINS_D4 EXP1_06_PIN #elif ENABLED(MKS_MINI_12864) @@ -457,6 +462,115 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN + #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI + + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #if ENABLED(BTT_TFT35_SPI_V1_0) + + /** + * ------ ------ + * BEEPER | 1 2 | LCD-BTN MISO | 1 2 | CLK + * T_MOSI | 3 4 | T_CS LCD-ENCA | 3 4 | TFTCS + * T_CLK | 5 6 T_MISO LCD-ENCB | 5 6 MOSI + * PENIRQ | 7 8 | F_CS RS | 7 8 | RESET + * GND | 9 10 | VCC GND | 9 10 | NC + * ------ ------ + * EXP1 EXP2 + * + * 480x320, 3.5", SPI Display with Rotary Encoder. + * Stock Display for the BIQU B1 SE Series. + * Schematic: https://github.com/bigtreetech/TFT35-SPI/blob/master/v1/Hardware/BTT%20TFT35-SPI%20V1-SCH.pdf + */ + #define TFT_CS_PIN EXP2_04_PIN + #define TFT_DC_PIN EXP2_07_PIN + #define TFT_A0_PIN TFT_DC_PIN + + #define TOUCH_CS_PIN EXP1_04_PIN + #define TOUCH_SCK_PIN EXP1_05_PIN + #define TOUCH_MISO_PIN EXP1_06_PIN + #define TOUCH_MOSI_PIN EXP1_03_PIN + #define TOUCH_INT_PIN EXP1_07_PIN + + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X 17540 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y -11388 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X -21 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y 337 + #endif + #ifndef TOUCH_ORIENTATION + #define TOUCH_ORIENTATION TOUCH_LANDSCAPE + #endif + + #elif ENABLED(MKS_TS35_V2_0) + + /** ------ ------ + * BEEPER | 1 2 | BTN_ENC SPI1_MISO | 1 2 | SPI1_SCK + * TFT_BKL / LCD_EN | 3 4 | TFT_RESET / LCD_RS BTN_EN1 | 3 4 | SPI1_CS + * TOUCH_CS / LCD_D4 | 5 6 TOUCH_INT / LCD_D5 BTN_EN2 | 5 6 SPI1_MOSI + * SPI1_CS / LCD_D6 | 7 8 | SPI1_RS / LCD_D7 SPI1_RS | 7 8 | RESET + * GND | 9 10 | VCC GND | 9 10 | VCC + * ------ ------ + * EXP1 EXP2 + */ + #define TFT_CS_PIN EXP1_07_PIN // SPI1_CS + #define TFT_DC_PIN EXP1_08_PIN // SPI1_RS + #define TFT_A0_PIN TFT_DC_PIN + + #define TFT_RESET_PIN EXP1_04_PIN + + #define LCD_BACKLIGHT_PIN EXP1_03_PIN + #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #define TOUCH_CS_PIN EXP1_05_PIN // SPI1_NSS + #define TOUCH_SCK_PIN EXP2_02_PIN // SPI1_SCK + #define TOUCH_MISO_PIN EXP2_01_PIN // SPI1_MISO + #define TOUCH_MOSI_PIN EXP2_06_PIN // SPI1_MOSI + + #define LCD_READ_ID 0xD3 + #define LCD_USE_DMA_SPI + + #define TFT_BUFFER_WORDS 14400 + + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X -17253 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 11579 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 514 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -24 + #endif + #ifndef TOUCH_ORIENTATION + #define TOUCH_ORIENTATION TOUCH_LANDSCAPE + #endif + + #endif + #else #define LCD_PINS_RS EXP1_04_PIN @@ -464,7 +578,7 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #if ENABLED(FYSETC_MINI_12864) @@ -472,7 +586,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif @@ -515,27 +629,6 @@ #endif #endif -#if HAS_SPI_TFT - // - // e.g., BTT_TFT35_SPI_V1_0 (480x320, 3.5", SPI Stock Display with Rotary Encoder in BIQU B1 SE) - // - #define TFT_CS_PIN EXP2_04_PIN - #define TFT_A0_PIN EXP2_07_PIN - #define TFT_SCK_PIN EXP2_02_PIN - #define TFT_MISO_PIN EXP2_01_PIN - #define TFT_MOSI_PIN EXP2_06_PIN - - #define TOUCH_INT_PIN EXP1_07_PIN - #define TOUCH_MISO_PIN EXP1_06_PIN - #define TOUCH_MOSI_PIN EXP1_03_PIN - #define TOUCH_SCK_PIN EXP1_05_PIN - #define TOUCH_CS_PIN EXP1_04_PIN - - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN - #define BTN_ENC EXP1_02_PIN -#endif - // // NeoPixel LED // diff --git a/Marlin/src/pins/teensy2/env_validate.h b/Marlin/src/pins/teensy2/env_validate.h index 5f0ea4f3b672..8fd6fba31932 100644 --- a/Marlin/src/pins/teensy2/env_validate.h +++ b/Marlin/src/pins/teensy2/env_validate.h @@ -19,10 +19,13 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if NOT_TARGET(__AVR_AT90USB1286__) && (DISABLED(ALLOW_AT90USB1286P) || NOT_TARGET(__AVR_AT90USB1286P__)) #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" #endif #undef ALLOW_AT90USB1286P + +#endif diff --git a/Marlin/src/pins/teensy2/pins_5DPRINT.h b/Marlin/src/pins/teensy2/pins_5DPRINT.h index 9eb1da36f413..798f98dae509 100644 --- a/Marlin/src/pins/teensy2/pins_5DPRINT.h +++ b/Marlin/src/pins/teensy2/pins_5DPRINT.h @@ -133,8 +133,8 @@ #define HEATER_0_PIN 15 // C5 #define HEATER_BED_PIN 14 // C4 -#ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A +#ifndef FAN0_PIN + #define FAN0_PIN 16 // C6 PWM3A #endif // diff --git a/Marlin/src/pins/teensy2/pins_BRAINWAVE.h b/Marlin/src/pins/teensy2/pins_BRAINWAVE.h index bbda3730ee00..900eae6dd49e 100644 --- a/Marlin/src/pins/teensy2/pins_BRAINWAVE.h +++ b/Marlin/src/pins/teensy2/pins_BRAINWAVE.h @@ -120,8 +120,8 @@ #define HEATER_0_PIN 32 // A4 Extruder #define HEATER_BED_PIN 18 // E6 Bed -#ifndef FAN_PIN - #define FAN_PIN 31 // A3 Fan +#ifndef FAN0_PIN + #define FAN0_PIN 31 // A3 Fan #endif // diff --git a/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h b/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h index 969ec845588f..a1ef48e524e6 100644 --- a/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h +++ b/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h @@ -126,8 +126,8 @@ // #define HEATER_0_PIN 27 // B7 #define HEATER_BED_PIN 26 // B6 Bed -#ifndef FAN_PIN - #define FAN_PIN 16 // C6 Fan, PWM3A +#ifndef FAN0_PIN + #define FAN0_PIN 16 // C6 Fan, PWM3A #endif // diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h index 1fb7387d160c..ab4427a8892d 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h @@ -118,8 +118,8 @@ #define HEATER_2_PIN 45 // F7 #define HEATER_BED_PIN 14 // C4 PWM3C -#ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A +#ifndef FAN0_PIN + #define FAN0_PIN 16 // C6 PWM3A #endif // @@ -130,16 +130,17 @@ // // LCD / Controller // + #if HAS_WIRED_LCD && IS_NEWPANEL #define LCD_PINS_RS 9 // E1 JP11-11 - #define LCD_PINS_ENABLE 8 // E0 JP11-10 + #define LCD_PINS_EN 8 // E0 JP11-10 #define LCD_PINS_D4 7 // D7 JP11-8 #define LCD_PINS_D5 6 // D6 JP11-7 #define LCD_PINS_D6 5 // D5 JP11-6 #define LCD_PINS_D7 4 // D4 JP11-5 - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define BEEPER_PIN 8 // E0 JP11-10 #define DOGLCD_A0 40 // F2 JP2-2 diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h index 5ce106b485cc..62922399d827 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h @@ -203,8 +203,8 @@ #endif #endif -#ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A +#ifndef FAN0_PIN + #define FAN0_PIN 16 // C6 PWM3A #endif // @@ -214,13 +214,13 @@ #if HAS_WIRED_LCD #define LCD_PINS_RS 9 // E1 JP11-11 - #define LCD_PINS_ENABLE 8 // E0 JP11-10 + #define LCD_PINS_EN 8 // E0 JP11-10 #define LCD_PINS_D4 7 // D7 JP11-8 #define LCD_PINS_D5 6 // D6 JP11-7 #define LCD_PINS_D6 5 // D5 JP11-6 #define LCD_PINS_D7 4 // D4 JP11-5 - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define BEEPER_PIN 8 // E0 JP11-10 #define DOGLCD_A0 40 // F2 JP2-2 diff --git a/Marlin/src/pins/teensy2/pins_SAV_MKI.h b/Marlin/src/pins/teensy2/pins_SAV_MKI.h index a469bba59b32..9f590cbbb4e0 100644 --- a/Marlin/src/pins/teensy2/pins_SAV_MKI.h +++ b/Marlin/src/pins/teensy2/pins_SAV_MKI.h @@ -116,8 +116,8 @@ #define HEATER_0_PIN 15 // C5 PWM3B - Extruder #define HEATER_BED_PIN 14 // C4 PWM3C - Bed -#ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A +#ifndef FAN0_PIN + #define FAN0_PIN 16 // C6 PWM3A #endif // @@ -155,7 +155,7 @@ // #define BEEPER_PIN -1 #define LCD_PINS_RS -1 -#define LCD_PINS_ENABLE -1 +#define LCD_PINS_EN -1 #if ENABLED(SAV_3DLCD) // For LCD SHIFT register LCD @@ -163,7 +163,7 @@ #define SR_CLK_PIN EXT_AUX_SCL_D0 #endif -#if EITHER(SAV_3DLCD, SAV_3DGLCD) +#if ANY(SAV_3DLCD, SAV_3DGLCD) #define BTN_EN1 EXT_AUX_A1_IO #define BTN_EN2 EXT_AUX_A0_IO @@ -172,7 +172,7 @@ #define KILL_PIN EXT_AUX_A2_IO #define HOME_PIN EXT_AUX_A4_IO -#else // Use the expansion header for spindle control +#else // Use the expansion header for spindle control // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/teensy2/pins_TEENSY2.h b/Marlin/src/pins/teensy2/pins_TEENSY2.h index b95e9cae48a1..dac4c6c94006 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSY2.h +++ b/Marlin/src/pins/teensy2/pins_TEENSY2.h @@ -149,8 +149,8 @@ // #define HEATER_0_PIN 15 // C5 PWM3B Extruder #define HEATER_BED_PIN 14 // C4 PWM3C -#ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A Fan +#ifndef FAN0_PIN + #define FAN0_PIN 16 // C6 PWM3A Fan #endif // @@ -167,9 +167,10 @@ // // LCD / Controller // + #if IS_ULTIPANEL #define LCD_PINS_RS 8 // E0 - #define LCD_PINS_ENABLE 9 // E1 + #define LCD_PINS_EN 9 // E1 #define LCD_PINS_D4 10 // C0 #define LCD_PINS_D5 11 // C1 #define LCD_PINS_D6 12 // C2 @@ -182,6 +183,8 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 5 // D5 Pin should have a pullup! -#define SPINDLE_LASER_PWM_PIN 0 // D0 PWM0B MUST BE HARDWARE PWM -#define SPINDLE_DIR_PIN 7 // D7 +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 0 // D0 PWM0B MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENA_PIN 5 // D5 Pin should have a pullup! + #define SPINDLE_DIR_PIN 7 // D7 +#endif diff --git a/Marlin/src/pins/teensy2/pins_TEENSYLU.h b/Marlin/src/pins/teensy2/pins_TEENSYLU.h index 294a289cdb0d..a6a16f2be158 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSYLU.h +++ b/Marlin/src/pins/teensy2/pins_TEENSYLU.h @@ -133,8 +133,8 @@ #define HEATER_0_PIN 15 // C5 PWM3B - Extruder #define HEATER_BED_PIN 14 // C4 PWM3C -#ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A +#ifndef FAN0_PIN + #define FAN0_PIN 16 // C6 PWM3A #endif // @@ -149,6 +149,7 @@ // // LCD / Controller // + #if HAS_WIRED_LCD && IS_NEWPANEL #define BEEPER_PIN -1 @@ -167,6 +168,8 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 24 // B4 IO-3 PWM2A - MUST BE HARDWARE PWM -#define SPINDLE_LASER_ENA_PIN 39 // F1 IO-11 - Pin should have a pullup! -#define SPINDLE_DIR_PIN 40 // F2 IO-9 +#if HAS_CUTTER + #define SPINDLE_LASER_PWM_PIN 24 // B4 IO-3 PWM2A - MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENA_PIN 39 // F1 IO-11 - Pin should have a pullup! + #define SPINDLE_DIR_PIN 40 // F2 IO-9 +#endif diff --git a/Marlin/src/pins/teensy3/pins_TEENSY31_32.h b/Marlin/src/pins/teensy3/pins_TEENSY31_32.h index 0edb5cb19dbd..a6aa4fd86dfe 100644 --- a/Marlin/src/pins/teensy3/pins_TEENSY31_32.h +++ b/Marlin/src/pins/teensy3/pins_TEENSY31_32.h @@ -71,8 +71,8 @@ #define HEATER_0_PIN 20 //#define HEATER_1_PIN 36 #define HEATER_BED_PIN 21 -#ifndef FAN_PIN - #define FAN_PIN 22 +#ifndef FAN0_PIN + #define FAN0_PIN 22 #endif // @@ -100,7 +100,7 @@ /* #if HAS_WIRED_LCD #define LCD_PINS_RS 40 - #define LCD_PINS_ENABLE 41 + #define LCD_PINS_EN 41 #define LCD_PINS_D4 42 #define LCD_PINS_D5 43 #define LCD_PINS_D6 44 diff --git a/Marlin/src/pins/teensy3/pins_TEENSY35_36.h b/Marlin/src/pins/teensy3/pins_TEENSY35_36.h index 71c348536a7f..54bf6f883545 100644 --- a/Marlin/src/pins/teensy3/pins_TEENSY35_36.h +++ b/Marlin/src/pins/teensy3/pins_TEENSY35_36.h @@ -57,7 +57,7 @@ * 3.3V | | GND * Z_STOP_PIN 24 | 40 * * 53 | A22 DAC1 * AUX2 25 | 41 * * 52 | A21 DAC0 - * AUX2 FAN_PIN SCL2 TX1 26 | 42 * * 51 | 39 A20 MISO0 SDSS + * AUX2 FAN0_PIN SCL2 TX1 26 | 42 * * 51 | 39 A20 MISO0 SDSS * AUX2 Z-PROBE PWR SCK0 RX1 27 | * * * * * | 38 A19 PWM SDA1 * AUX2 SOL1_PIN MOSI0 28 | 43 * * 50 | 37 A18 PWM SCL1 * D10 CONTROLLER_FAN_PIN CAN0TX PWM 29 | 44 * * 49 | 36 A17 PWM @@ -67,7 +67,7 @@ * * Interior pins: * LCD_PINS_RS 40 * * 53 SCK2 - * LCD_PINS_ENABLE 41 * * 52 MOSI2 + * LCD_PINS_EN 41 * * 52 MOSI2 * LCD_PINS_D4 42 * * 51 MISO2 * LCD_PINS_D5 CS2 43 * * 50 A24 * LCD_PINS_D6 MOSI2 44 * * 49 A23 @@ -109,8 +109,8 @@ #define HEATER_0_PIN 30 #define HEATER_1_PIN 36 #define HEATER_BED_PIN 31 -#ifndef FAN_PIN - #define FAN_PIN 2 +#ifndef FAN0_PIN + #define FAN0_PIN 2 #endif #define TEMP_0_PIN 2 // Extruder / Analog pin numbering: 2 => A2 @@ -132,7 +132,7 @@ #if HAS_WIRED_LCD #define LCD_PINS_RS 40 - #define LCD_PINS_ENABLE 41 + #define LCD_PINS_EN 41 #define LCD_PINS_D4 42 #define LCD_PINS_D5 43 #define LCD_PINS_D6 44 diff --git a/Marlin/src/pins/teensy4/env_validate.h b/Marlin/src/pins/teensy4/env_validate.h new file mode 100644 index 000000000000..5a89e8a409a8 --- /dev/null +++ b/Marlin/src/pins/teensy4/env_validate.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if NOT_TARGET(IS_TEENSY41) + #error "Oops! Select 'Teensy 4.1' in 'Tools > Board.'" +#endif diff --git a/Marlin/src/pins/teensy4/pins_T41U5XBB.h b/Marlin/src/pins/teensy4/pins_T41U5XBB.h index 5f62bb05a64b..2ee4f2970e8a 100644 --- a/Marlin/src/pins/teensy4/pins_T41U5XBB.h +++ b/Marlin/src/pins/teensy4/pins_T41U5XBB.h @@ -27,9 +27,7 @@ * https://www.pjrc.com/teensy/teensyduino.html ****************************************************************************************/ -#if NOT_TARGET(IS_TEENSY41) - #error "Oops! Select 'Teensy 4.1' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Teensy4.1" diff --git a/Marlin/src/pins/teensy4/pins_TEENSY41.h b/Marlin/src/pins/teensy4/pins_TEENSY41.h index 21a1ff675f24..2a8a76f17c56 100644 --- a/Marlin/src/pins/teensy4/pins_TEENSY41.h +++ b/Marlin/src/pins/teensy4/pins_TEENSY41.h @@ -27,9 +27,7 @@ * https://www.pjrc.com/teensy/teensyduino.html ****************************************************************************************/ -#if NOT_TARGET(IS_TEENSY41) - #error "Oops! Select 'Teensy 4.1' in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "Teensy4.1" @@ -53,10 +51,10 @@ * 3.3V | | GND * Z_STOP_PIN PWM 24 | | 41 A17 * E0_ENABLE_PIN PWM 25 | | 40 A16 - * FAN_PIN MOSI1 26 | | 39 A15 MISO1 X_STOP_PIN + * FAN0_PIN MOSI1 26 | | 39 A15 MISO1 X_STOP_PIN * Z-PROBE PWR SCK1 27 | * * * * * | 38 A14 Y_STOP_PIN * SOL1_PIN RX7 PWM 28 | | 37 PWM HEATER_0_PIN - * FAN_PIN TX7 PWM 29 | | 36 PWM HEATER_BED_PIN + * FAN0_PIN TX7 PWM 29 | | 36 PWM HEATER_BED_PIN * X_CS_PIN 30 | | 35 TX8 E1_ENABLE_PIN * y_CS_PIN 31 | SDCARD | 34 RX8 E1_DIR_PIN * Z_CS_PIN 32 |_______________| 33 PWM E1_STEP_PIN @@ -107,8 +105,8 @@ #define HEATER_0_PIN 37 #define HEATER_1_PIN 18 #define HEATER_BED_PIN 36 -#ifndef FAN_PIN - #define FAN_PIN 29 +#ifndef FAN0_PIN + #define FAN0_PIN 29 #endif // diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 81cc03230483..25fc35e6ab93 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -40,6 +40,37 @@ #include "../MarlinCore.h" +#if DISABLED(SD_NO_DEFAULT_TIMEOUT) + #ifndef SD_INIT_TIMEOUT + #define SD_INIT_TIMEOUT 2000u // (ms) Init timeout + #elif SD_INIT_TIMEOUT < 0 + #error "SD_INIT_TIMEOUT must be greater than or equal to 0." + #endif + #ifndef SD_ERASE_TIMEOUT + #define SD_ERASE_TIMEOUT 10000u // (ms) Erase timeout + #elif SD_ERASE_TIMEOUT < 0 + #error "SD_ERASE_TIMEOUT must be greater than or equal to 0." + #endif + #ifndef SD_READ_TIMEOUT + #define SD_READ_TIMEOUT 300u // (ms) Read timeout + #elif SD_READ_TIMEOUT < 0 + #error "SD_READ_TIMEOUT must be greater than or equal to 0." + #endif + #ifndef SD_WRITE_TIMEOUT + #define SD_WRITE_TIMEOUT 600u // (ms) Write timeout + #elif SD_WRITE_TIMEOUT < 0 + #error "SD_WRITE_TIMEOUT must be greater than or equal to 0." + #endif +#endif // SD_NO_DEFAULT_TIMEOUT + +#if ENABLED(SD_CHECK_AND_RETRY) + #ifndef SD_RETRY_COUNT + #define SD_RETRY_COUNT 3 + #elif SD_RETRY_COUNT < 1 + #error "SD_RETRY_COUNT must be greater than or equal to 1." + #endif +#endif + #if ENABLED(SD_CHECK_AND_RETRY) static bool crcSupported = true; @@ -74,7 +105,7 @@ #else static uint8_t CRC7(const uint8_t *data, uint8_t n) { uint8_t crc = 0; - LOOP_L_N(i, n) { + for (uint8_t i = 0; i < n; ++i) { uint8_t d = data[i]; d ^= crc << 1; if (d & 0x80) d ^= 9; @@ -97,21 +128,22 @@ uint8_t DiskIODriver_SPI_SD::cardCommand(const uint8_t cmd, const uint32_t arg) // Select card chipSelect(); - // Wait up to 300 ms if busy - waitNotBusy(SD_WRITE_TIMEOUT); + #if SD_WRITE_TIMEOUT + waitNotBusy(SD_WRITE_TIMEOUT); // Wait up to 600 ms (by default) if busy + #endif uint8_t *pa = (uint8_t *)(&arg); #if ENABLED(SD_CHECK_AND_RETRY) // Form message - uint8_t d[6] = {(uint8_t) (cmd | 0x40), pa[3], pa[2], pa[1], pa[0] }; + uint8_t d[6] = { uint8_t(cmd | 0x40), pa[3], pa[2], pa[1], pa[0] }; // Add crc d[5] = CRC7(d, 5); // Send message - LOOP_L_N(k, 6) spiSend(d[k]); + for (uint8_t k = 0; k < 6; ++k) spiSend(d[k]); #else // Send command @@ -186,33 +218,42 @@ void DiskIODriver_SPI_SD::chipSelect() { bool DiskIODriver_SPI_SD::erase(uint32_t firstBlock, uint32_t lastBlock) { if (ENABLED(SDCARD_READONLY)) return false; - csd_t csd; - if (!readCSD(&csd)) goto FAIL; - - // check for single block erase - if (!csd.v1.erase_blk_en) { - // erase size mask - uint8_t m = (csd.v1.sector_size_high << 1) | csd.v1.sector_size_low; - if ((firstBlock & m) != 0 || ((lastBlock + 1) & m) != 0) { - // error card can't erase specified area - error(SD_CARD_ERROR_ERASE_SINGLE_BLOCK); - goto FAIL; + bool success = false; + do { + + csd_t csd; + if (!readCSD(&csd)) break; + + // check for single block erase + if (!csd.v1.erase_blk_en) { + // erase size mask + uint8_t m = (csd.v1.sector_size_high << 1) | csd.v1.sector_size_low; + if ((firstBlock & m) || ((lastBlock + 1) & m)) { + // error card can't erase specified area + error(SD_CARD_ERROR_ERASE_SINGLE_BLOCK); + break; + } } - } - if (type_ != SD_CARD_TYPE_SDHC) { firstBlock <<= 9; lastBlock <<= 9; } - if (cardCommand(CMD32, firstBlock) || cardCommand(CMD33, lastBlock) || cardCommand(CMD38, 0)) { - error(SD_CARD_ERROR_ERASE); - goto FAIL; - } - if (!waitNotBusy(SD_ERASE_TIMEOUT)) { - error(SD_CARD_ERROR_ERASE_TIMEOUT); - goto FAIL; - } - chipDeselect(); - return true; - FAIL: + if (type_ != SD_CARD_TYPE_SDHC) { firstBlock <<= 9; lastBlock <<= 9; } + if (cardCommand(CMD32, firstBlock) || cardCommand(CMD33, lastBlock) || cardCommand(CMD38, 0)) { + error(SD_CARD_ERROR_ERASE); + break; + } + #if SD_ERASE_TIMEOUT + if (!waitNotBusy(SD_ERASE_TIMEOUT)) { + error(SD_CARD_ERROR_ERASE_TIMEOUT); + break; + } + #else + while (spiRec() != 0xFF) {} + #endif + + success = true; + + } while (0); + chipDeselect(); - return false; + return success; } /** @@ -245,8 +286,15 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi errorCode_ = type_ = 0; chipSelectPin_ = chipSelectPin; + // 16-bit init start time allows over a minute - const millis_t init_timeout = millis() + SD_INIT_TIMEOUT; + #if SD_INIT_TIMEOUT + const millis_t init_timeout = millis() + SD_INIT_TIMEOUT; + #define INIT_TIMEOUT() ELAPSED(millis(), init_timeout) + #else + #define INIT_TIMEOUT() false + #endif + uint32_t arg; hal.watchdog_refresh(); // In case init takes too long @@ -268,13 +316,13 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi spiInit(spiRate_); // Must supply min of 74 clock cycles with CS high. - LOOP_L_N(i, 10) spiSend(0xFF); + for (uint8_t i = 0; i < 10; ++i) spiSend(0xFF); hal.watchdog_refresh(); // In case init takes too long // Command to go idle in SPI mode while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) { - if (ELAPSED(millis(), init_timeout)) { + if (INIT_TIMEOUT()) { error(SD_CARD_ERROR_CMD0); goto FAIL; } @@ -294,13 +342,13 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi } // Get the last byte of r7 response - LOOP_L_N(i, 4) status_ = spiRec(); + for (uint8_t i = 0; i < 4; ++i) status_ = spiRec(); if (status_ == 0xAA) { type(SD_CARD_TYPE_SD2); break; } - if (ELAPSED(millis(), init_timeout)) { + if (INIT_TIMEOUT()) { error(SD_CARD_ERROR_CMD8); goto FAIL; } @@ -312,11 +360,12 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi arg = type() == SD_CARD_TYPE_SD2 ? 0x40000000 : 0; while ((status_ = cardAcmd(ACMD41, arg)) != R1_READY_STATE) { // Check for timeout - if (ELAPSED(millis(), init_timeout)) { + if (INIT_TIMEOUT()) { error(SD_CARD_ERROR_ACMD41); goto FAIL; } } + // If SD2 read OCR register to check for SDHC card if (type() == SD_CARD_TYPE_SD2) { if (cardCommand(CMD58, 0)) { @@ -325,8 +374,9 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi } if ((spiRec() & 0xC0) == 0xC0) type(SD_CARD_TYPE_SDHC); // Discard rest of ocr - contains allowed voltage range - LOOP_L_N(i, 3) spiRec(); + for (uint8_t i = 0; i < 3; ++i) spiRec(); } + chipDeselect(); ready = true; @@ -353,7 +403,7 @@ bool DiskIODriver_SPI_SD::readBlock(uint32_t blockNumber, uint8_t * const dst) { if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; // Use address if not SDHC card #if ENABLED(SD_CHECK_AND_RETRY) - uint8_t retryCnt = 3; + uint8_t retryCnt = SD_RETRY_COUNT; for (;;) { if (cardCommand(CMD17, blockNumber)) error(SD_CARD_ERROR_CMD17); @@ -458,9 +508,15 @@ bool DiskIODriver_SPI_SD::readData(uint8_t * const dst) { bool DiskIODriver_SPI_SD::readData(uint8_t * const dst, const uint16_t count) { bool success = false; - const millis_t read_timeout = millis() + SD_READ_TIMEOUT; + #if SD_READ_TIMEOUT + const millis_t read_timeout = millis() + SD_READ_TIMEOUT; + #define READ_TIMEOUT() ELAPSED(millis(), read_timeout) + #else + #define READ_TIMEOUT() false + #endif + while ((status_ = spiRec()) == 0xFF) { // Wait for start block token - if (ELAPSED(millis(), read_timeout)) { + if (READ_TIMEOUT()) { error(SD_CARD_ERROR_READ_TIMEOUT); goto FAIL; } @@ -469,7 +525,7 @@ bool DiskIODriver_SPI_SD::readData(uint8_t * const dst, const uint16_t count) { if (status_ == DATA_START_BLOCK) { spiRead(dst, count); // Transfer data - const uint16_t recvCrc = (spiRec() << 8) | spiRec(); + const uint16_t recvCrc = ((uint16_t)spiRec() << 8) | (uint16_t)spiRec(); #if ENABLED(SD_CHECK_AND_RETRY) success = !crcSupported || recvCrc == CRC_CCITT(dst, count); if (!success) error(SD_CARD_ERROR_READ_CRC); @@ -574,20 +630,23 @@ bool DiskIODriver_SPI_SD::writeBlock(uint32_t blockNumber, const uint8_t * const return 0 == SDHC_CardWriteBlock(src, blockNumber); #endif - bool success = false; - if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; // Use address if not SDHC card - if (!cardCommand(CMD24, blockNumber)) { - if (writeData(DATA_START_BLOCK, src)) { - if (waitNotBusy(SD_WRITE_TIMEOUT)) { // Wait for flashing to complete - success = !(cardCommand(CMD13, 0) || spiRec()); // Response is r2 so get and check two bytes for nonzero - if (!success) error(SD_CARD_ERROR_WRITE_PROGRAMMING); - } - else - error(SD_CARD_ERROR_WRITE_TIMEOUT); + if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; // Use address if not SDHC card + bool success = !cardCommand(CMD24, blockNumber); + if (!success) { + error(SD_CARD_ERROR_CMD24); + } + else if (writeData(DATA_START_BLOCK, src)) { + #if SD_WRITE_TIMEOUT + success = waitNotBusy(SD_WRITE_TIMEOUT); // Wait for flashing to complete + if (!success) error(SD_CARD_ERROR_WRITE_TIMEOUT); + #else + while (spiRec() != 0xFF) {} + #endif + if (success) { + success = !(cardCommand(CMD13, 0) || spiRec()); // Response is r2 so get and check two bytes for nonzero + if (!success) error(SD_CARD_ERROR_WRITE_PROGRAMMING); } } - else - error(SD_CARD_ERROR_CMD24); chipDeselect(); return success; @@ -601,13 +660,25 @@ bool DiskIODriver_SPI_SD::writeBlock(uint32_t blockNumber, const uint8_t * const bool DiskIODriver_SPI_SD::writeData(const uint8_t * const src) { if (ENABLED(SDCARD_READONLY)) return false; - bool success = true; chipSelect(); - // Wait for previous write to finish - if (!waitNotBusy(SD_WRITE_TIMEOUT) || !writeData(WRITE_MULTIPLE_TOKEN, src)) { - error(SD_CARD_ERROR_WRITE_MULTIPLE); - success = false; - } + + bool success = false; + do { + + // Wait for previous write to finish + #if SD_WRITE_TIMEOUT + if (!waitNotBusy(SD_WRITE_TIMEOUT)) { + error(SD_CARD_ERROR_WRITE_MULTIPLE); + break; + } + #else + while (spiRec() != 0xFF) {} + #endif + + success = writeData(WRITE_MULTIPLE_TOKEN, src); + + } while (0); + chipDeselect(); return success; } @@ -665,14 +736,31 @@ bool DiskIODriver_SPI_SD::writeStart(uint32_t blockNumber, const uint32_t eraseC bool DiskIODriver_SPI_SD::writeStop() { if (ENABLED(SDCARD_READONLY)) return false; - bool success = false; chipSelect(); - if (waitNotBusy(SD_WRITE_TIMEOUT)) { + + bool success = false; + do { + + #if SD_WRITE_TIMEOUT + if (!waitNotBusy(SD_WRITE_TIMEOUT)) { + error(SD_CARD_ERROR_STOP_TRAN); + break; + } + #else + while (spiRec() != 0xFF) {} + #endif + spiSend(STOP_TRAN_TOKEN); - success = waitNotBusy(SD_WRITE_TIMEOUT); - } - else - error(SD_CARD_ERROR_STOP_TRAN); + + #if SD_WRITE_TIMEOUT + if (!waitNotBusy(SD_WRITE_TIMEOUT)) break; + #else + while (spiRec() != 0xFF) {} + #endif + + success = true; + + } while (0); chipDeselect(); return success; diff --git a/Marlin/src/sd/Sd2Card.h b/Marlin/src/sd/Sd2Card.h index 23677b24fa4b..dd021364e033 100644 --- a/Marlin/src/sd/Sd2Card.h +++ b/Marlin/src/sd/Sd2Card.h @@ -39,11 +39,6 @@ #include -uint16_t const SD_INIT_TIMEOUT = 2000, // (ms) Init timeout - SD_ERASE_TIMEOUT = 10000, // (ms) Erase timeout - SD_READ_TIMEOUT = 300, // (ms) Read timeout - SD_WRITE_TIMEOUT = 600; // (ms) Write timeout - // SD card errors typedef enum : uint8_t { SD_CARD_ERROR_CMD0 = 0x01, // Timeout error for command CMD0 (initialize card in SPI mode) @@ -70,7 +65,7 @@ typedef enum : uint8_t { SD_CARD_ERROR_WRITE_PROGRAMMING = 0x16, // Card returned an error to a CMD13 status check after a write SD_CARD_ERROR_WRITE_TIMEOUT = 0x17, // Timeout occurred during write programming SD_CARD_ERROR_SCK_RATE = 0x18, // Incorrect rate selected - SD_CARD_ERROR_INIT_NOT_CALLED = 0x19, // Init() not called + SD_CARD_ERROR_INIT_NOT_CALLED = 0x19, // init() not called // 0x1A is unused now, it was: card returned an error for CMD59 (CRC_ON_OFF) SD_CARD_ERROR_READ_CRC = 0x1B // Invalid read CRC } sd_error_code_t; @@ -83,7 +78,7 @@ uint8_t const SD_CARD_TYPE_SD1 = 1, // Standard capacity V1 SD card /** * Define SOFTWARE_SPI to use bit-bang SPI */ -#if EITHER(MEGA_SOFT_SPI, USE_SOFTWARE_SPI) +#if ANY(MEGA_SOFT_SPI, USE_SOFTWARE_SPI) #define SOFTWARE_SPI #endif diff --git a/Marlin/src/sd/SdBaseFile.cpp b/Marlin/src/sd/SdBaseFile.cpp index 2dcbb9fad985..f878118d2f0d 100644 --- a/Marlin/src/sd/SdBaseFile.cpp +++ b/Marlin/src/sd/SdBaseFile.cpp @@ -35,7 +35,7 @@ #include "../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "SdBaseFile.h" @@ -209,7 +209,7 @@ bool SdBaseFile::dirEntry(dir_t *dir) { */ void SdBaseFile::dirName(const dir_t &dir, char *name) { uint8_t j = 0; - LOOP_L_N(i, 11) { + for (uint8_t i = 0; i < 11; ++i) { if (dir.name[i] == ' ')continue; if (i == 8) name[j++] = '.'; name[j++] = dir.name[i]; @@ -322,12 +322,12 @@ void SdBaseFile::getpos(filepos_t * const pos) { * \param[in] indent Amount of space before file name. Used for recursive * list to indicate subdirectory level. */ -void SdBaseFile::ls(uint8_t flags, uint8_t indent) { +void SdBaseFile::ls(const uint8_t flags/*=0*/, const uint8_t indent/*=0*/) { rewind(); int8_t status; while ((status = lsPrintNext(flags, indent))) { if (status > 1 && (flags & LS_R)) { - uint16_t index = curPosition() / 32 - 1; + const uint16_t index = curPosition() / 32 - 1; SdBaseFile s; if (s.open(this, index, O_READ)) s.ls(flags, indent + 2); seekSet(32 * (index + 1)); @@ -350,10 +350,10 @@ int8_t SdBaseFile::lsPrintNext(const uint8_t flags, const uint8_t indent) { && DIR_IS_FILE_OR_SUBDIR(&dir)) break; } // indent for dir level - LOOP_L_N(i, indent) SERIAL_CHAR(' '); + for (uint8_t i = 0; i < indent; ++i) SERIAL_CHAR(' '); // print name - LOOP_L_N(i, 11) { + for (uint8_t i = 0; i < 11; ++i) { if (dir.name[i] == ' ')continue; if (i == 8) { SERIAL_CHAR('.'); @@ -504,7 +504,7 @@ bool SdBaseFile::mkdir(SdBaseFile * const parent, const uint8_t dname[11] dir_t d; memcpy(&d, p, sizeof(d)); d.name[0] = '.'; - LOOP_S_L_N(i, 1, 11) d.name[i] = ' '; + for (uint8_t i = 1; i < 11; ++i) d.name[i] = ' '; // cache block for '.' and '..' uint32_t block = vol_->clusterStartBlock(firstCluster_); @@ -708,7 +708,7 @@ bool SdBaseFile::open(SdBaseFile * const dirFile, const uint8_t dname[11] } // Get LFN sequence number lfnSequenceNumber = pvFat->sequenceNumber & 0x1F; - if WITHIN(lfnSequenceNumber, 1, reqEntriesNum) { + if (WITHIN(lfnSequenceNumber, 1, reqEntriesNum)) { // Check checksum for all other entries with the starting checksum fetched before if (lfnChecksum == pvFat->checksum) { // Set chunk of LFN from VFAT entry into lfnName @@ -771,7 +771,7 @@ bool SdBaseFile::open(SdBaseFile * const dirFile, const uint8_t dname[11] if (!dirFile->seekSet(32 * index)) return false; // Dir entries write loop: [LFN] + SFN(1) - LOOP_L_N(dirWriteIdx, reqEntriesNum) { + for (uint8_t dirWriteIdx = 0; dirWriteIdx < reqEntriesNum; ++dirWriteIdx) { index = (dirFile->curPosition_ / 32) & 0xF; p = dirFile->readDirCache(); // LFN or SFN Entry? @@ -1002,7 +1002,8 @@ bool SdBaseFile::openNext(SdBaseFile *dirFile, const uint8_t oflag) { bool SdBaseFile::isDirLFN(const dir_t* dir) { if (DIR_IS_LONG_NAME(dir)) { vfat_t *VFAT = (vfat_t*)dir; - // Sanity-check the VFAT entry. The first cluster is always set to zero. And the sequence number should be higher than 0 + // Sanity-check the VFAT entry. The first cluster is always set to zero. + // The sequence number should be higher than 0 and lower than maximum allowed by VFAT spec if ((VFAT->firstClusterLow == 0) && WITHIN((VFAT->sequenceNumber & 0x1F), 1, MAX_VFAT_ENTRIES)) return true; } return false; @@ -1136,7 +1137,7 @@ bool SdBaseFile::openNext(SdBaseFile *dirFile, const uint8_t oflag) { */ void SdBaseFile::getLFNName(vfat_t *pFatDir, char *lname, const uint8_t sequenceNumber) { const uint8_t startOffset = (sequenceNumber - 1) * FILENAME_LENGTH; - LOOP_L_N(i, FILENAME_LENGTH) { + for (uint8_t i = 0; i < FILENAME_LENGTH; ++i) { const uint16_t utf16_ch = (i >= 11) ? pFatDir->name3[i - 11] : (i >= 5) ? pFatDir->name2[i - 5] : pFatDir->name1[i]; #if ENABLED(UTF_FILENAME_SUPPORT) // We can't reconvert to UTF-8 here as UTF-8 is variable-size encoding, but joining LFN blocks @@ -1157,7 +1158,7 @@ bool SdBaseFile::openNext(SdBaseFile *dirFile, const uint8_t oflag) { void SdBaseFile::setLFNName(vfat_t *pFatDir, char *lname, const uint8_t sequenceNumber) { const uint8_t startOffset = (sequenceNumber - 1) * FILENAME_LENGTH, nameLength = strlen(lname); - LOOP_L_N(i, FILENAME_LENGTH) { + for (uint8_t i = 0; i < FILENAME_LENGTH; ++i) { uint16_t ch = 0; if ((startOffset + i) < nameLength) ch = lname[startOffset + i]; @@ -1294,7 +1295,6 @@ static void print2u(const uint8_t v) { * \param[in] fatDate The date field from a directory entry. */ - /** * %Print a directory date field. * @@ -1311,7 +1311,6 @@ void SdBaseFile::printFatDate(const uint16_t fatDate) { print2u(FAT_DAY(fatDate)); } - /** * %Print a directory time field. * @@ -1421,11 +1420,13 @@ int16_t SdBaseFile::read(void * const buf, uint16_t nbyte) { * * \param[out] dir The dir_t struct that will receive the data. * - * \return For success readDir() returns the number of bytes read. - * A value of zero will be returned if end of file is reached. - * If an error occurs, readDir() returns -1. Possible errors include - * readDir() called before a directory has been opened, this is not - * a directory file or an I/O error occurred. + * \return For success return a non-zero value (number of bytes read). + * A value of zero will be returned if end of dir is reached. + * If an error occurs, readDir() returns -1. Possible errors: + * - readDir() called on unopened dir + * - not a directory file + * - bad dir entry + * - I/O error */ int8_t SdBaseFile::readDir(dir_t * const dir, char * const longFilename) { int16_t n; @@ -1462,7 +1463,7 @@ int8_t SdBaseFile::readDir(dir_t * const dir, char * const longFilename) { // Sanity-check the VFAT entry. The first cluster is always set to zero. And the sequence number should be higher than 0 if (VFAT->firstClusterLow == 0) { const uint8_t seq = VFAT->sequenceNumber & 0x1F; - if (WITHIN(seq, 1, MAX_VFAT_ENTRIES)) { + if (WITHIN(seq, 1, VFAT_ENTRIES_LIMIT)) { if (seq == 1) { checksum = VFAT->checksum; checksum_error = 0; @@ -1478,7 +1479,7 @@ int8_t SdBaseFile::readDir(dir_t * const dir, char * const longFilename) { n = (seq - 1) * (FILENAME_LENGTH); - LOOP_L_N(i, FILENAME_LENGTH) { + for (uint8_t i = 0; i < FILENAME_LENGTH; ++i) { const uint16_t utf16_ch = (i >= 11) ? VFAT->name3[i - 11] : (i >= 5) ? VFAT->name2[i - 5] : VFAT->name1[i]; #if ENABLED(UTF_FILENAME_SUPPORT) // We can't reconvert to UTF-8 here as UTF-8 is variable-size encoding, but joining LFN blocks @@ -1487,7 +1488,7 @@ int8_t SdBaseFile::readDir(dir_t * const dir, char * const longFilename) { longFilename[idx] = utf16_ch & 0xFF; longFilename[idx + 1] = (utf16_ch >> 8) & 0xFF; #else - // Replace all multibyte characters to '_' + // Replace multibyte character with '_' longFilename[n + i] = (utf16_ch > 0xFF) ? '_' : (utf16_ch & 0xFF); #endif } @@ -1626,7 +1627,7 @@ bool SdBaseFile::remove() { // Check if the entry has a LFN bool lastEntry = false; // loop back to search for any LFN entries related to this file - LOOP_S_LE_N(sequenceNumber, 1, MAX_VFAT_ENTRIES) { + for (uint8_t sequenceNumber = 1; sequenceNumber <= VFAT_ENTRIES_LIMIT; ++sequenceNumber) { dirIndex_ = (dirIndex_ - 1) & 0xF; if (dirBlock_ == 0) break; if (dirIndex_ == 0xF) dirBlock_--; @@ -2268,4 +2269,4 @@ int16_t SdBaseFile::write(const void *buf, const uint16_t nbyte) { return -1; } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/sd/SdBaseFile.h b/Marlin/src/sd/SdBaseFile.h index 3ac23138b154..dc31e8492d2c 100644 --- a/Marlin/src/sd/SdBaseFile.h +++ b/Marlin/src/sd/SdBaseFile.h @@ -67,7 +67,6 @@ uint8_t const LS_DATE = 1, // ls() flag to print modify date LS_SIZE = 2, // ls() flag to print file size LS_R = 4; // ls() flag for recursive list of subdirectories - // flags for timestamp uint8_t const T_ACCESS = 1, // Set the file's last access date T_CREATE = 2, // Set the file's creation date and time @@ -283,7 +282,7 @@ class SdBaseFile { bool isRoot() const { return type_ == FAT_FILE_TYPE_ROOT_FIXED || type_ == FAT_FILE_TYPE_ROOT32; } bool getDosName(char * const name); - void ls(uint8_t flags=0, uint8_t indent=0); + void ls(const uint8_t flags=0, const uint8_t indent=0); bool mkdir(SdBaseFile *parent, const char *path, const bool pFlag=true); bool open(SdBaseFile * const dirFile, uint16_t index, const uint8_t oflag); diff --git a/Marlin/src/sd/SdFatConfig.h b/Marlin/src/sd/SdFatConfig.h index dfba64129526..0979a592a3bc 100644 --- a/Marlin/src/sd/SdFatConfig.h +++ b/Marlin/src/sd/SdFatConfig.h @@ -109,4 +109,4 @@ #define LONG_FILENAME_CHARSIZE TERN(UTF_FILENAME_SUPPORT, 2, 1) // Total bytes needed to store a single long filename -#define LONG_FILENAME_LENGTH (FILENAME_LENGTH * LONG_FILENAME_CHARSIZE * MAX_VFAT_ENTRIES + 1) +#define LONG_FILENAME_LENGTH (FILENAME_LENGTH * LONG_FILENAME_CHARSIZE * VFAT_ENTRIES_LIMIT + 1) diff --git a/Marlin/src/sd/SdFatUtil.cpp b/Marlin/src/sd/SdFatUtil.cpp index e6f7a9a01305..a68bd73ebea0 100644 --- a/Marlin/src/sd/SdFatUtil.cpp +++ b/Marlin/src/sd/SdFatUtil.cpp @@ -31,7 +31,7 @@ #include "../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "SdFatUtil.h" #include @@ -59,4 +59,4 @@ #endif -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/sd/SdFile.cpp b/Marlin/src/sd/SdFile.cpp index a1dd79372747..c6a3577e1d0c 100644 --- a/Marlin/src/sd/SdFile.cpp +++ b/Marlin/src/sd/SdFile.cpp @@ -31,7 +31,7 @@ #include "../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "SdFile.h" @@ -95,4 +95,4 @@ void SdFile::writeln_P(PGM_P const str) { write_P(PSTR("\r\n")); } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/sd/SdVolume.cpp b/Marlin/src/sd/SdVolume.cpp index 8c06c745371b..1b8cdbdcae31 100644 --- a/Marlin/src/sd/SdVolume.cpp +++ b/Marlin/src/sd/SdVolume.cpp @@ -31,7 +31,7 @@ #include "../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA #include "SdVolume.h" @@ -402,4 +402,4 @@ bool SdVolume::init(DiskIODriver * const dev, const uint8_t part) { return true; } -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 830533969b9b..e4e3cf5021dd 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -22,7 +22,7 @@ #include "../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA //#define DEBUG_CARDREADER @@ -56,7 +56,7 @@ #include "../feature/pause.h" #endif -#define DEBUG_OUT EITHER(DEBUG_CARDREADER, MARLIN_DEV_MODE) +#define DEBUG_OUT ANY(DEBUG_CARDREADER, MARLIN_DEV_MODE) #include "../core/debug_out.h" #include "../libs/hex_print.h" @@ -81,13 +81,14 @@ IF_DISABLED(NO_SD_AUTOSTART, uint8_t CardReader::autofile_index); // = 0 MediaFile CardReader::root, CardReader::workDir, CardReader::workDirParents[MAX_DIR_DEPTH]; uint8_t CardReader::workDirDepth; +int16_t CardReader::nrItems = -1; #if ENABLED(SDCARD_SORT_ALPHA) - uint16_t CardReader::sort_count; + int16_t CardReader::sort_count; #if ENABLED(SDSORT_GCODE) - bool CardReader::sort_alpha; - int CardReader::sort_folders; + SortFlag CardReader::sort_alpha; + int8_t CardReader::sort_folders; //bool CardReader::sort_reverse; #endif @@ -100,7 +101,6 @@ uint8_t CardReader::workDirDepth; #if ENABLED(SDSORT_USES_RAM) #if ENABLED(SDSORT_CACHE_NAMES) - uint16_t CardReader::nrFiles; // Cached total file count #if ENABLED(SDSORT_DYNAMIC_RAM) char **CardReader::sortshort, **CardReader::sortnames; #else @@ -156,8 +156,8 @@ CardReader::CardReader() { #if ENABLED(SDCARD_SORT_ALPHA) sort_count = 0; #if ENABLED(SDSORT_GCODE) - sort_alpha = true; - sort_folders = FOLDER_SORTING; + sort_alpha = TERN(SDSORT_REVERSE, AS_REV, AS_FWD); + sort_folders = SDSORT_FOLDERS; //sort_reverse = false; #endif #endif @@ -172,7 +172,7 @@ CardReader::CardReader() { workDirDepth = 0; ZERO(workDirParents); - #if BOTH(SDSUPPORT, HAS_SD_DETECT) + #if ALL(HAS_MEDIA, HAS_SD_DETECT) SET_INPUT_PULLUP(SD_DETECT_PIN); #endif @@ -186,7 +186,7 @@ CardReader::CardReader() { // char *createFilename(char * const buffer, const dir_t &p) { char *pos = buffer; - LOOP_L_N(i, 11) { + for (uint8_t i = 0; i < 11; ++i) { if (p.name[i] == ' ') continue; if (i == 8) *pos++ = '.'; *pos++ = p.name[i]; @@ -228,25 +228,20 @@ bool CardReader::is_visible_entity(const dir_t &p OPTARG(CUSTOM_FIRMWARE_UPLOAD, // // Get the number of (compliant) items in the folder // -int CardReader::countItems(MediaFile dir) { +int16_t CardReader::countVisibleItems(MediaFile dir) { dir_t p; - int c = 0; - while (dir.readDir(&p, longFilename) > 0) - c += is_visible_entity(p); - - #if ALL(SDCARD_SORT_ALPHA, SDSORT_USES_RAM, SDSORT_CACHE_NAMES) - nrFiles = c; - #endif - + int16_t c = 0; + dir.rewind(); + while (dir.readDir(&p, longFilename) > 0) c += is_visible_entity(p); return c; } // // Get file/folder info for an item by index // -void CardReader::selectByIndex(MediaFile dir, const uint8_t index) { +void CardReader::selectByIndex(MediaFile dir, const int16_t index) { dir_t p; - for (uint8_t cnt = 0; dir.readDir(&p, longFilename) > 0;) { + for (int16_t cnt = 0; dir.readDir(&p, longFilename) > 0;) { if (is_visible_entity(p)) { if (cnt == index) { createFilename(filename, p); @@ -295,7 +290,7 @@ void CardReader::printListing(MediaFile parent, const char * const prepend, cons while (parent.readDir(&p, longFilename) > 0) { if (DIR_IS_SUBDIR(&p)) { - size_t lenPrepend = prepend ? strlen(prepend) + 1 : 0; + const 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] = '/'; } @@ -354,7 +349,7 @@ void CardReader::printListing(MediaFile parent, const char * const prepend, cons // // List all files on the SD card // -void CardReader::ls(const uint8_t lsflags) { +void CardReader::ls(const uint8_t lsflags/*=0*/) { if (flag.mounted) { root.rewind(); printListing(root, nullptr, lsflags); @@ -446,6 +441,7 @@ void CardReader::printSelectedFilename() { void CardReader::mount() { flag.mounted = false; + nrItems = -1; if (root.isOpen()) root.close(); if (!driver->init(SD_SPI_SPEED, SDSS) @@ -465,7 +461,7 @@ void CardReader::mount() { if (flag.mounted) cdroot(); else { - #if EITHER(HAS_SD_DETECT, USB_FLASH_DRIVE_SUPPORT) + #if ANY(HAS_SD_DETECT, USB_FLASH_DRIVE_SUPPORT) if (marlin_state != MF_INITIALIZING) LCD_ALERTMESSAGE(MSG_MEDIA_INIT_FAIL); #endif } @@ -515,20 +511,25 @@ void CardReader::manage_media() { if (!stat) return; // Exit if no media is present - if (old_stat != 2) return; // First mount? - - DEBUG_ECHOLNPGM("First mount."); + bool do_auto = true; UNUSED(do_auto); - // Load settings the first time media is inserted (not just during init) - TERN_(SDCARD_EEPROM_EMULATION, settings.first_load()); + // First mount on boot? Load emulated EEPROM and look for PLR file. + if (old_stat == 2) { + DEBUG_ECHOLNPGM("First mount."); - bool do_auto = true; UNUSED(do_auto); + // Load settings the first time media is inserted (not just during init) + TERN_(SDCARD_EEPROM_EMULATION, settings.first_load()); - // Check for PLR file. - TERN_(POWER_LOSS_RECOVERY, if (recovery.check()) do_auto = false); + // Check for PLR file. Skip One-Click and auto#.g if found + TERN_(POWER_LOSS_RECOVERY, if (recovery.check()) do_auto = false); + } - // Look for auto0.g on the next idle() - IF_DISABLED(NO_SD_AUTOSTART, if (do_auto) autofile_begin()); + // Also for the first mount run auto#.g for machine init. + // (Skip if PLR or One-Click Print was invoked.) + if (old_stat == 2) { + // Look for auto0.g on the next idle() + IF_DISABLED(NO_SD_AUTOSTART, if (do_auto) autofile_begin()); + } } /** @@ -544,10 +545,10 @@ void CardReader::release() { flag.mounted = false; flag.workDirIsRoot = true; - #if ALL(SDCARD_SORT_ALPHA, SDSORT_USES_RAM, SDSORT_CACHE_NAMES) - nrFiles = 0; - #endif + nrItems = -1; SERIAL_ECHO_MSG(STR_SD_CARD_RELEASED); + + TERN_(NO_SD_DETECT, ui.refresh()); } /** @@ -615,7 +616,7 @@ void CardReader::getAbsFilenameInCWD(char *dst) { if (cnt < MAXPATHNAMELENGTH) { *dst = '/'; dst++; cnt++; } }; - LOOP_L_N(i, workDirDepth) // Loop down to current work dir + for (uint8_t i = 0; i < workDirDepth; ++i) // Loop down to current work dir appendAtom(workDirParents[i]); if (cnt < MAXPATHNAMELENGTH - (FILENAME_LENGTH) - 1) { // Leave room for filename and nul @@ -880,12 +881,12 @@ void CardReader::closefile(const bool store_location/*=false*/) { // // Get info for a file in the working directory by index // -void CardReader::selectFileByIndex(const uint16_t nr) { +void CardReader::selectFileByIndex(const int16_t nr) { #if ENABLED(SDSORT_CACHE_NAMES) if (nr < sort_count) { strcpy(filename, sortshort[nr]); strcpy(longFilename, sortnames[nr]); - flag.filenameIsDir = IS_DIR(nr); + TERN_(HAS_FOLDER_SORTING, flag.filenameIsDir = IS_DIR(nr)); setBinFlag(strcmp_P(strrchr(filename, '.'), PSTR(".BIN")) == 0); return; } @@ -899,11 +900,11 @@ void CardReader::selectFileByIndex(const uint16_t nr) { // void CardReader::selectFileByName(const char * const match) { #if ENABLED(SDSORT_CACHE_NAMES) - for (uint16_t nr = 0; nr < sort_count; nr++) + for (int16_t nr = 0; nr < sort_count; nr++) if (strcasecmp(match, sortshort[nr]) == 0) { strcpy(filename, sortshort[nr]); strcpy(longFilename, sortnames[nr]); - flag.filenameIsDir = IS_DIR(nr); + TERN_(HAS_FOLDER_SORTING, flag.filenameIsDir = IS_DIR(nr)); setBinFlag(strcmp_P(strrchr(filename, '.'), PSTR(".BIN")) == 0); return; } @@ -912,11 +913,6 @@ void CardReader::selectFileByName(const char * const match) { selectByName(workDir, match); } -uint16_t CardReader::countFilesInWorkDir() { - workDir.rewind(); - return countItems(workDir); -} - /** * Dive to the given DOS 8.3 file path, with optional echo of the dive paths. * @@ -971,7 +967,6 @@ const char* CardReader::diveToFile(const bool update_cwd, MediaFile* &inDirPtr, const uint8_t len = name_end - atom_ptr; char dosSubdirname[len + 1]; strncpy(dosSubdirname, atom_ptr, len); - dosSubdirname[len] = 0; if (echo) SERIAL_ECHOLN(dosSubdirname); @@ -1029,6 +1024,7 @@ void CardReader::cd(const char * relpath) { flag.workDirIsRoot = false; if (workDirDepth < MAX_DIR_DEPTH) workDirParents[workDirDepth++] = workDir; + nrItems = -1; TERN_(SDCARD_SORT_ALPHA, presort()); } else @@ -1037,6 +1033,7 @@ void CardReader::cd(const char * relpath) { int8_t CardReader::cdup() { if (workDirDepth > 0) { // At least 1 dir has been saved + nrItems = -1; workDir = --workDirDepth ? workDirParents[workDirDepth - 1] : root; // Use parent, or root if none TERN_(SDCARD_SORT_ALPHA, presort()); } @@ -1048,6 +1045,7 @@ void CardReader::cdroot() { workDir = root; flag.workDirIsRoot = true; workDirDepth = 0; + nrItems = -1; TERN_(SDCARD_SORT_ALPHA, presort()); } @@ -1056,9 +1054,8 @@ void CardReader::cdroot() { /** * Get the name of a file in the working directory by sort-index */ - void CardReader::getfilename_sorted(const uint16_t nr) { - selectFileByIndex(TERN1(SDSORT_GCODE, sort_alpha) && (nr < sort_count) - ? sort_order[nr] : nr); + void CardReader::selectFileByIndexSorted(const int16_t nr) { + selectFileByIndex(SortFlag(TERN1(SDSORT_GCODE, sort_alpha != AS_OFF)) && (nr < sort_count) ? sort_order[nr] : nr); } #if ENABLED(SDSORT_USES_RAM) @@ -1099,20 +1096,20 @@ void CardReader::cdroot() { * - Most RAM: Buffer the directory and return filenames from RAM */ void CardReader::presort() { - // Throw away old sort index flush_presort(); + int16_t fileCnt = get_num_items(); + // Sorting may be turned off - if (TERN0(SDSORT_GCODE, !sort_alpha)) return; + if (TERN0(SDSORT_GCODE, sort_alpha == AS_OFF)) return; // If there are files, sort up to the limit - uint16_t fileCnt = countFilesInWorkDir(); if (fileCnt > 0) { // Never sort more than the max allowed // If you use folders to organize, 20 may be enough - NOMORE(fileCnt, uint16_t(SDSORT_LIMIT)); + NOMORE(fileCnt, int16_t(SDSORT_LIMIT)); // Sort order is always needed. May be static or dynamic. TERN_(SDSORT_DYNAMIC_RAM, sort_order = new uint8_t[fileCnt]); @@ -1134,9 +1131,9 @@ void CardReader::cdroot() { // Folder sorting needs 1 bit per entry for flags. #if HAS_FOLDER_SORTING #if ENABLED(SDSORT_DYNAMIC_RAM) - isDir = new uint8_t[(fileCnt + 7) >> 3]; + isDir = new uint8_t[(fileCnt + 7) >> 3]; // Allocate space with 'new' #elif ENABLED(SDSORT_USES_STACK) - uint8_t isDir[(fileCnt + 7) >> 3]; + uint8_t isDir[(fileCnt + 7) >> 3]; // Use stack in this scope #endif #endif @@ -1152,7 +1149,7 @@ void CardReader::cdroot() { if (fileCnt > 1) { // Init sort order. - for (uint16_t i = 0; i < fileCnt; i++) { + for (int16_t i = 0; i < fileCnt; i++) { sort_order[i] = i; // If using RAM then read all filenames now. #if ENABLED(SDSORT_USES_RAM) @@ -1171,9 +1168,9 @@ void CardReader::cdroot() { } // Bubble Sort - for (uint16_t i = fileCnt; --i;) { + for (int16_t i = fileCnt; --i;) { bool didSwap = false; - uint8_t o1 = sort_order[0]; + int16_t o1 = sort_order[0]; #if DISABLED(SDSORT_USES_RAM) selectFileByIndex(o1); // Pre-fetch the first entry and save it strcpy(name1, longest_filename()); // so the loop only needs one fetch @@ -1182,22 +1179,22 @@ void CardReader::cdroot() { #endif #endif - for (uint16_t j = 0; j < i; ++j) { - const uint16_t o2 = sort_order[j + 1]; + for (int16_t j = 0; j < i; ++j) { + const int16_t o2 = sort_order[j + 1]; // Compare names from the array or just the two buffered names - #if ENABLED(SDSORT_USES_RAM) - #define _SORT_CMP_NODIR() (strcasecmp(sortnames[o1], sortnames[o2]) > 0) - #else - #define _SORT_CMP_NODIR() (strcasecmp(name1, name2) > 0) - #endif + auto _sort_cmp_file = [](char * const n1, char * const n2) -> bool { + const bool sort = strcasecmp(n1, n2) > 0; + return (TERN(SDSORT_GCODE, card.sort_alpha == AS_REV, ENABLED(SDSORT_REVERSE))) ? !sort : sort; + }; + #define _SORT_CMP_FILE() _sort_cmp_file(TERN(SDSORT_USES_RAM, sortnames[o1], name1), TERN(SDSORT_USES_RAM, sortnames[o2], name2)) #if HAS_FOLDER_SORTING #if ENABLED(SDSORT_USES_RAM) // Folder sorting needs an index and bit to test for folder-ness. - #define _SORT_CMP_DIR(fs) (IS_DIR(o1) == IS_DIR(o2) ? _SORT_CMP_NODIR() : IS_DIR(fs > 0 ? o1 : o2)) + #define _SORT_CMP_DIR(fs) (IS_DIR(o1) == IS_DIR(o2) ? _SORT_CMP_FILE() : IS_DIR(fs > 0 ? o1 : o2)) #else - #define _SORT_CMP_DIR(fs) ((dir1 == flag.filenameIsDir) ? _SORT_CMP_NODIR() : (fs > 0 ? dir1 : !dir1)) + #define _SORT_CMP_DIR(fs) ((dir1 == flag.filenameIsDir) ? _SORT_CMP_FILE() : (fs > 0 ? dir1 : !dir1)) #endif #endif @@ -1213,12 +1210,12 @@ void CardReader::cdroot() { if ( #if HAS_FOLDER_SORTING #if ENABLED(SDSORT_GCODE) - sort_folders ? _SORT_CMP_DIR(sort_folders) : _SORT_CMP_NODIR() + sort_folders ? _SORT_CMP_DIR(sort_folders) : _SORT_CMP_FILE() #else - _SORT_CMP_DIR(FOLDER_SORTING) + _SORT_CMP_DIR(SDSORT_FOLDERS) #endif #else - _SORT_CMP_NODIR() + _SORT_CMP_FILE() #endif ) { // Reorder the index, indicate that sorting happened @@ -1241,23 +1238,25 @@ void CardReader::cdroot() { // Using RAM but not keeping names around #if ENABLED(SDSORT_USES_RAM) && DISABLED(SDSORT_CACHE_NAMES) #if ENABLED(SDSORT_DYNAMIC_RAM) - for (uint16_t i = 0; i < fileCnt; ++i) free(sortnames[i]); + for (int16_t i = 0; i < fileCnt; ++i) free(sortnames[i]); TERN_(HAS_FOLDER_SORTING, delete [] isDir); #endif #endif } else { sort_order[0] = 0; - #if BOTH(SDSORT_USES_RAM, SDSORT_CACHE_NAMES) + #if ALL(SDSORT_USES_RAM, SDSORT_CACHE_NAMES) #if ENABLED(SDSORT_DYNAMIC_RAM) sortnames = new char*[1]; sortshort = new char*[1]; - isDir = new uint8_t[1]; #endif selectFileByIndex(0); SET_SORTNAME(0); SET_SORTSHORT(0); - isDir[0] = flag.filenameIsDir; + #if ALL(HAS_FOLDER_SORTING, SDSORT_DYNAMIC_RAM) + isDir = new uint8_t[1]; + isDir[0] = flag.filenameIsDir; + #endif #endif } @@ -1270,7 +1269,7 @@ void CardReader::cdroot() { #if ENABLED(SDSORT_DYNAMIC_RAM) delete [] sort_order; #if ENABLED(SDSORT_CACHE_NAMES) - LOOP_L_N(i, sort_count) { + for (uint8_t i = 0; i < sort_count; ++i) { free(sortshort[i]); // strdup free(sortnames[i]); // strdup } @@ -1284,15 +1283,10 @@ void CardReader::cdroot() { #endif // SDCARD_SORT_ALPHA -uint16_t CardReader::get_num_Files() { +int16_t CardReader::get_num_items() { if (!isMounted()) return 0; - return ( - #if ALL(SDCARD_SORT_ALPHA, SDSORT_USES_RAM, SDSORT_CACHE_NAMES) - nrFiles // no need to access the SD card for filenames - #else - countFilesInWorkDir() - #endif - ); + if (nrItems < 0) nrItems = countVisibleItems(workDir); + return nrItems; } // @@ -1353,4 +1347,4 @@ void CardReader::fileHasFinished() { #endif // POWER_LOSS_RECOVERY -#endif // SDSUPPORT +#endif // HAS_MEDIA diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 86acb1b8628c..518c2fff6ba3 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -23,7 +23,7 @@ #include "../inc/MarlinConfig.h" -#if ENABLED(SDSUPPORT) +#if HAS_MEDIA extern const char M23_STR[], M24_STR[]; @@ -31,17 +31,14 @@ extern const char M23_STR[], M24_STR[]; #if ENABLED(SDSORT_DYNAMIC_RAM) #define SD_RESORT 1 #endif - #if FOLDER_SORTING || ENABLED(SDSORT_GCODE) + #ifndef SDSORT_FOLDERS + #define SDSORT_FOLDERS 0 + #endif + #if SDSORT_FOLDERS || ENABLED(SDSORT_GCODE) #define HAS_FOLDER_SORTING 1 #endif #endif -#if ENABLED(SDCARD_RATHERRECENTFIRST) && DISABLED(SDCARD_SORT_ALPHA) - #define SD_ORDER(N,C) ((C) - 1 - (N)) -#else - #define SD_ORDER(N,C) N -#endif - #define MAX_DIR_DEPTH 10 // Maximum folder depth #define MAXDIRNAMELENGTH 8 // DOS folder name size #define MAXPATHNAMELENGTH (1 + (MAXDIRNAMELENGTH + 1) * (MAX_DIR_DEPTH) + 1 + FILENAME_LENGTH) // "/" + N * ("ADIRNAME/") + "filename.ext" @@ -90,6 +87,7 @@ typedef struct { } card_flags_t; enum ListingFlags : uint8_t { LS_LONG_FILENAME, LS_ONLY_BIN, LS_TIMESTAMP }; +enum SortFlag : int8_t { AS_REV = -1, AS_OFF, AS_FWD, AS_ALSO_REV }; #if ENABLED(AUTO_REPORT_SD_STATUS) #include "../libs/autoreport.h" @@ -110,8 +108,6 @@ class CardReader { #endif #endif - // // // Methods // // // - CardReader(); static void changeMedia(DiskIODriver *_driver) { driver = _driver; } @@ -152,11 +148,10 @@ class CardReader { static void cdroot(); static void cd(const char *relpath); static int8_t cdup(); - static uint16_t countFilesInWorkDir(); - static uint16_t get_num_Files(); + static int16_t get_num_items(); // Select a file - static void selectFileByIndex(const uint16_t nr); + static void selectFileByIndex(const int16_t nr); static void selectFileByName(const char * const match); // (working directory only) // Print job @@ -199,17 +194,19 @@ class CardReader { #if ENABLED(SDCARD_SORT_ALPHA) static void presort(); - static void getfilename_sorted(const uint16_t nr); + static void selectFileByIndexSorted(const int16_t nr); #if ENABLED(SDSORT_GCODE) - FORCE_INLINE static void setSortOn(bool b) { sort_alpha = b; presort(); } - FORCE_INLINE static void setSortFolders(int i) { sort_folders = i; presort(); } + FORCE_INLINE static void setSortOn(const SortFlag f) { sort_alpha = (f == AS_ALSO_REV) ? AS_REV : f; presort(); } + FORCE_INLINE static void setSortFolders(const int8_t i) { sort_folders = i; presort(); } //FORCE_INLINE static void setSortReverse(bool b) { sort_reverse = b; } #endif #else - FORCE_INLINE static void getfilename_sorted(const uint16_t nr) { selectFileByIndex(nr); } + FORCE_INLINE static void selectFileByIndexSorted(const int16_t nr) { + selectFileByIndex(TERN(SDCARD_RATHERRECENTFIRST, get_num_items() - 1 - nr, (nr))); + } #endif - static void ls(const uint8_t lsflags); + static void ls(const uint8_t lsflags=0); #if ENABLED(POWER_LOSS_RECOVERY) static bool jobRecoverFileExists(); @@ -264,26 +261,27 @@ class CardReader { // static MediaFile root, workDir, workDirParents[MAX_DIR_DEPTH]; static uint8_t workDirDepth; + static int16_t nrItems; // Cache the total count // // Alphabetical file and folder sorting // #if ENABLED(SDCARD_SORT_ALPHA) - static uint16_t sort_count; // Count of sorted items in the current directory + static int16_t sort_count; // Count of sorted items in the current directory #if ENABLED(SDSORT_GCODE) - static bool sort_alpha; // Flag to enable / disable the feature - static int sort_folders; // Folder sorting before/none/after + static SortFlag sort_alpha; // Sorting: REV, OFF, FWD + static int8_t sort_folders; // Folder sorting before/none/after //static bool sort_reverse; // Flag to enable / disable reverse sorting #endif - // By default the sort index is static + // By default the sort index is statically allocated #if ENABLED(SDSORT_DYNAMIC_RAM) static uint8_t *sort_order; #else static uint8_t sort_order[SDSORT_LIMIT]; #endif - #if BOTH(SDSORT_USES_RAM, SDSORT_CACHE_NAMES) && DISABLED(SDSORT_DYNAMIC_RAM) + #if ALL(SDSORT_USES_RAM, SDSORT_CACHE_NAMES) && DISABLED(SDSORT_DYNAMIC_RAM) #define SORTED_LONGNAME_MAXLEN (SDSORT_CACHE_VFATS) * (FILENAME_LENGTH) #define SORTED_LONGNAME_STORAGE (SORTED_LONGNAME_MAXLEN + 1) #else @@ -296,7 +294,6 @@ class CardReader { // If using dynamic ram for names, allocate on the heap. #if ENABLED(SDSORT_CACHE_NAMES) - static uint16_t nrFiles; // Cache the total count #if ENABLED(SDSORT_DYNAMIC_RAM) static char **sortshort, **sortnames; #else @@ -341,8 +338,8 @@ class CardReader { // Directory items // static bool is_visible_entity(const dir_t &p OPTARG(CUSTOM_FIRMWARE_UPLOAD, const bool onlyBin=false)); - static int countItems(MediaFile dir); - static void selectByIndex(MediaFile dir, const uint8_t index); + static int16_t countVisibleItems(MediaFile dir); + static void selectByIndex(MediaFile dir, const int16_t index); static void selectByName(MediaFile dir, const char * const match); static void printListing( MediaFile parent, const char * const prepend, const uint8_t lsflags @@ -370,7 +367,7 @@ class CardReader { extern CardReader card; -#else // !SDSUPPORT +#else // !HAS_MEDIA #define IS_SD_PRINTING() false #define IS_SD_FETCHING() false @@ -379,4 +376,4 @@ extern CardReader card; #define LONG_FILENAME_LENGTH 0 -#endif // !SDSUPPORT +#endif // !HAS_MEDIA diff --git a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h index 3390bc51becc..f722c873ae0a 100644 --- a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h +++ b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h @@ -33,7 +33,7 @@ /** * Define SOFTWARE_SPI to use bit-bang SPI */ - #if EITHER(MEGA_SOFT_SPI, USE_SOFTWARE_SPI) + #if ANY(MEGA_SOFT_SPI, USE_SOFTWARE_SPI) #define SOFTWARE_SPI #endif diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp index 75421f4482a8..016500d2d68c 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp @@ -201,7 +201,7 @@ uint8_t USB::ctrlReq(uint8_t addr, uint8_t ep, uint8_t bmReqType, uint8_t bReque * Keep sending INs and writes data to memory area pointed by 'data' * rcode 0 if no errors. rcode 01-0f is relayed from dispatchPkt(). Rcode f0 means RCVDAVIRQ error, fe = USB xfer timeout */ -uint8_t USB::inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval /*= 0*/) { +uint8_t USB::inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval/*=0*/) { EpInfo *pep = nullptr; uint16_t nak_limit = 0; @@ -215,7 +215,7 @@ uint8_t USB::inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t * return InTransfer(pep, nak_limit, nbytesptr, data, bInterval); } -uint8_t USB::InTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval /*= 0*/) { +uint8_t USB::InTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval/*=0*/) { uint8_t rcode = 0; uint8_t pktsize; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h index 2b6e1be52274..16b8c092cc67 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h @@ -201,8 +201,6 @@ typedef struct { uint16_t wLength; // 6 Depends on bRequest } __attribute__((packed)) SETUP_PKT, *PSETUP_PKT; - - // Base class for incoming data parser class USBReadParser { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp index 1aeef1703fec..551fb274d781 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp @@ -796,7 +796,6 @@ uint8_t BulkOnly::RequestSense(uint8_t lun, uint16_t size, uint8_t *buf) { return Transaction(&cbw, size, buf); } - //////////////////////////////////////////////////////////////////////////////// // USB code //////////////////////////////////////////////////////////////////////////////// @@ -1148,7 +1147,6 @@ uint8_t BulkOnly::HandleSCSIError(uint8_t status) { } // switch } - //////////////////////////////////////////////////////////////////////////////// // Debugging code //////////////////////////////////////////////////////////////////////////////// diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h index aafb91624b00..fa56b6857368 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h @@ -22,7 +22,6 @@ * Web : https://www.circuitsathome.com * e-mail : support@circuitsathome.com */ - #pragma once // Cruft removal, makes driver smaller, faster. diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/parsetools.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/parsetools.h index 403766da8ff1..21c6cd495178 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/parsetools.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/parsetools.h @@ -141,5 +141,5 @@ class PTPListParser { theParser.Initialize(p); } - bool Parse(uint8_t **pp, uint16_t *pcntdn, PTP_ARRAY_EL_FUNC pf, const void *me = nullptr); + bool Parse(uint8_t **pp, uint16_t *pcntdn, PTP_ARRAY_EL_FUNC pf, const void *me=nullptr); }; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h index 268c0e1d1dcd..1d46dc69b395 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h @@ -22,7 +22,6 @@ * Web : https://www.circuitsathome.com * e-mail : support@circuitsathome.com */ - #pragma once #include "../../../inc/MarlinConfig.h" diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usb_ch9.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usb_ch9.h index 99c628f888d3..f4d2af517655 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usb_ch9.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usb_ch9.h @@ -79,7 +79,6 @@ #define HID_DESCRIPTOR_HID 0x21 - /* OTG SET FEATURE Constants */ #define OTG_FEATURE_B_HNP_ENABLE 3 // SET FEATURE OTG - Enable B device to perform HNP #define OTG_FEATURE_A_HNP_SUPPORT 4 // SET FEATURE OTG - A device supports HNP @@ -92,7 +91,6 @@ #define USB_TRANSFER_TYPE_INTERRUPT 0x03 // Endpoint is an interrupt endpoint. #define bmUSB_TRANSFER_TYPE 0x03 // bit mask to separate transfer type from ISO attributes - /* Standard Feature Selectors for CLEAR_FEATURE Requests */ #define USB_FEATURE_ENDPOINT_STALL 0 // Endpoint recipient #define USB_FEATURE_DEVICE_REMOTE_WAKEUP 1 // Device recipient diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt b/Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt index 378786f940f3..f543bbaa6421 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt @@ -5,14 +5,12 @@ The lib-uhs3/ folder contains a subset of the files from the USB Host Shield https://github.com/felis/UHS30 - ==== LICENSE SUMMARY ==== Source Path: Repository: License: ------------ ----------- -------- usb_flashdrive/lib github.com/felis/UHS30 GPLv2 or later - ==== MARLIN INTEGRATION WORK ==== All additional work done to integrate USB into Marlin was performed by diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE.h index b35e53686e8a..c94e7ab990d9 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE.h @@ -27,7 +27,6 @@ e-mail : support@circuitsathome.com #ifndef __UHS_BULK_STORAGE_H__ #define __UHS_BULK_STORAGE_H__ - //////////////////////////////////////////////////////////////////////////////// // Define any of these options at the top of your sketch to override // the defaults contained herewith. Do NOT do modifications here. @@ -201,7 +200,6 @@ class UHS_Bulk_Storage : public UHS_USBInterface { uint8_t SCSITransaction6(SCSI_CDB6_t *cdb, uint16_t buf_size, void *buf, uint8_t dir); uint8_t SCSITransaction10(SCSI_CDB10_t *cdb, uint16_t buf_size, void *buf, uint8_t dir); - // Configure and internal methods, these should never be called by a user's sketch. uint8_t Start(); bool OKtoEnumerate(ENUMERATION_INFO *ei); @@ -211,12 +209,10 @@ class UHS_Bulk_Storage : public UHS_USBInterface { return bAddress; }; - void Poll(); void DriverDefaults(); - private: void Reset(); void CheckMedia(); diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE_INLINE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE_INLINE.h index 37ba681c5c7b..06deb7a0ae8b 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE_INLINE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE_INLINE.h @@ -41,9 +41,7 @@ e-mail : support@circuitsathome.com #endif //////////////////////////////////////////////////////////////////////////////// - // Interface code - //////////////////////////////////////////////////////////////////////////////// /** @@ -298,9 +296,7 @@ uint8_t UHS_NI UHS_Bulk_Storage::Write(uint8_t lun, uint32_t addr, uint16_t bsiz // Only developer serviceable parts below! //////////////////////////////////////////////////////////////////////////////// - // Main driver code - //////////////////////////////////////////////////////////////////////////////// UHS_NI UHS_Bulk_Storage::UHS_Bulk_Storage(UHS_USB_HOST_BASE *p) { @@ -637,11 +633,7 @@ void UHS_NI UHS_Bulk_Storage::Poll() { } //////////////////////////////////////////////////////////////////////////////// - - // SCSI code - - //////////////////////////////////////////////////////////////////////////////// /** @@ -794,13 +786,8 @@ uint8_t UHS_NI UHS_Bulk_Storage::RequestSense(uint8_t lun, uint16_t size, uint8_ return v; } - //////////////////////////////////////////////////////////////////////////////// - - // USB code - - //////////////////////////////////////////////////////////////////////////////// /** @@ -954,7 +941,6 @@ uint8_t UHS_NI UHS_Bulk_Storage::HandleUsbError(uint8_t error, uint8_t index) { if(index != epDataInIndex) return UHS_BULK_ERR_WRITE_STALL; return UHS_BULK_ERR_STALL; - case UHS_HOST_ERROR_TOGERR: // Handle a very super rare corner case, where toggles become de-synched. // I have only ran into one device that has this firmware bug, and this is @@ -1171,13 +1157,8 @@ uint8_t UHS_NI UHS_Bulk_Storage::HandleSCSIError(uint8_t status) { } // switch } - //////////////////////////////////////////////////////////////////////////////// - - // Debugging code - - //////////////////////////////////////////////////////////////////////////////// /** diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_UsbCore.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_UsbCore.h index 58d7ba200cb5..9ec18fbf4122 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_UsbCore.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_UsbCore.h @@ -59,7 +59,6 @@ e-mail : support@circuitsathome.com // D6-5 Type (0- standard, 1 - class, 2 - vendor, 3 - reserved) // D4-0 Recipient (0 - device, 1 - interface, 2 - endpoint, 3 - other, 4..31 - reserved) - // TO-DO: Use the python script to generate these. // TO-DO: Add _all_ subclasses here. // USB Device Classes, Subclasses and Protocols @@ -165,7 +164,6 @@ e-mail : support@circuitsathome.com //////////////////////////////////////////////////////////////////////////////// - /* USB state machine states */ #define UHS_USB_HOST_STATE_MASK 0xF0U @@ -324,7 +322,6 @@ typedef struct { // 8 bytes total } __attribute__((packed)) SETUP_PKT, *PSETUP_PKT; - // little endian :-) 8 8 8 8 16 16 #define mkSETUP_PKT8(bmReqType, bRequest, wValLo, wValHi, wInd, total) ((uint64_t)(((uint64_t)(bmReqType)))|(((uint64_t)(bRequest))<<8)|(((uint64_t)(wValLo))<<16)|(((uint64_t)(wValHi))<<24)|(((uint64_t)(wInd))<<32)|(((uint64_t)(total)<<48))) #define mkSETUP_PKT16(bmReqType, bRequest, wVal, wInd, total) ((uint64_t)(((uint64_t)(bmReqType)))|(((uint64_t)(bRequest))<<8)|(((uint64_t)(wVal ))<<16) |(((uint64_t)(wInd))<<32)|(((uint64_t)(total)<<48))) diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_address.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_address.h index 4d9d35bd6da0..3b47bbd892eb 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_address.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_address.h @@ -29,8 +29,6 @@ e-mail : support@circuitsathome.com #else #define __ADDRESS_H__ - - /* NAK powers. To save space in endpoint data structure, amount of retries before giving up and returning 0x4 is stored in */ /* bmNakPower as a power of 2. The actual nak_limit is then calculated as nak_limit = ( 2^bmNakPower - 1) */ #define UHS_USB_NAK_MAX_POWER 14 // NAK binary order maximum value @@ -192,7 +190,6 @@ class AddressPool { return (!index) ? NULL : &thePool[index]; }; - // Allocates new address uint8_t UHS_NI AllocAddress(uint8_t parent, bool is_hub = false, uint8_t port = 1) { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h index f78a3bb8f0fa..d87b40fea299 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h @@ -47,7 +47,6 @@ UHS_EpInfo* UHS_USB_HOST_BASE::getEpInfoEntry(uint8_t addr, uint8_t ep) { if(!p || !p->epinfo) return NULL; - UHS_EpInfo *pep; for(uint8_t j = 0; j < UHS_HOST_MAX_INTERFACE_DRIVERS; j++) { pep = (UHS_EpInfo *)(p->epinfo[j]); @@ -311,7 +310,6 @@ uint8_t UHS_USB_HOST_BASE::Configuring(uint8_t parent, uint8_t port, uint8_t spe return rcode; } - #if UHS_DEVICE_WINDOWS_USB_SPEC_VIOLATION_DESCRIPTOR_DEVICE ei.address = addrPool.AllocAddress(parent, false, port); @@ -1111,7 +1109,6 @@ uint8_t UHS_USB_HOST_BASE::enumerateInterface(ENUMERATION_INFO *ei) { return devConfigIndex; }; - //////////////////////////////////////////////////////////////////////////////// // Vendor Specific Interface Class //////////////////////////////////////////////////////////////////////////////// @@ -1168,7 +1165,6 @@ uint8_t UHS_NI UHS_VSI::SetInterface(ENUMERATION_INFO *ei) { //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// - #if 0 /* TO-DO: Move this silliness to a NONE driver. diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_macros.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_macros.h index bb2a87cf0382..6e9bb8b7835b 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_macros.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_macros.h @@ -31,7 +31,6 @@ e-mail : support@circuitsathome.com * Universal Arduino(tm) "IDE" fixups. */ - // Just in case... #ifndef SERIAL_PORT_MONITOR #define SERIAL_PORT_MONITOR Serial @@ -57,7 +56,6 @@ e-mail : support@circuitsathome.com #endif #endif - #ifndef UHS_DEVICE_WINDOWS_USB_SPEC_VIOLATION_DESCRIPTOR_DEVICE #ifndef UHS_BIG_FLASH @@ -160,7 +158,6 @@ e-mail : support@circuitsathome.com #define UHS_KIO_SETBIT_ATOMIC(r, m) (*(uint32_t *)UHS_KIO_BITBAND_ADDR((r), BITNR((m)))) = 1 #define UHS_KIO_CLRBIT_ATOMIC(r, m) (*(uint32_t *)UHS_KIO_BITBAND_ADDR((r), BITNR((m)))) = 0 - #define VALUE_BETWEEN(v,l,h) (((v)>(l)) && ((v)<(h))) #define VALUE_WITHIN(v,l,h) (((v)>=(l)) && ((v)<=(h))) #define output_pgm_message(wa,fp,mp,el) wa = &mp, fp((char *)pgm_read_pointer(wa), el) diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printf_HELPER.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printf_HELPER.h index 4fc9b94079ab..bb464d7adf82 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printf_HELPER.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printf_HELPER.h @@ -167,8 +167,6 @@ extern "C" { #error no STDIO #endif // defined(ARDUINO_ARCH_PIC32) - - #ifdef __AVR__ // The only wierdo in the bunch... void UHS_AVR_printf_HELPER_init() { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printhex.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printhex.h index edf673a4fbe7..af8917e14dbb 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printhex.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printhex.h @@ -91,6 +91,4 @@ template void D_PrintBin(NOTUSED(T val), NOTUSED(int lvl)) { #endif } - - #endif // __PRINTHEX_H__ diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_settings.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_settings.h index c516599d6b3f..03bf1c1c07ec 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_settings.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_settings.h @@ -55,7 +55,6 @@ e-mail : support@circuitsathome.com // //////////////////////////////////////////////////////////////////////////////// - //////////////////////////////////////////////////////////////////////////////// // DEBUGGING //////////////////////////////////////////////////////////////////////////////// diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usb_ch9.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usb_ch9.h index 6486482d961a..013be2a9d46f 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usb_ch9.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usb_ch9.h @@ -97,7 +97,6 @@ e-mail : support@circuitsathome.com #define USB_SETUP_RECIPIENT_PORT 0x04 // Wireless USB 1.0 #define USB_SETUP_RECIPIENT_RPIPE 0x05 // Wireless USB 1.0 - /* USB descriptors */ #define USB_DESCRIPTOR_DEVICE 0x01 // bDescriptorType for a Device Descriptor. #define USB_DESCRIPTOR_CONFIGURATION 0x02 // bDescriptorType for a Configuration Descriptor. @@ -123,7 +122,6 @@ e-mail : support@circuitsathome.com #define USB_HID_DESCRIPTOR 0x21 - // Conventional codes for class-specific descriptors. "Common Class" Spec (3.11) #define USB_DESCRIPTOR_CS_DEVICE 0x21 #define USB_DESCRIPTOR_CS_CONFIG 0x22 @@ -131,8 +129,6 @@ e-mail : support@circuitsathome.com #define USB_DESCRIPTOR_CS_INTERFACE 0x24 #define USB_DESCRIPTOR_CS_ENDPOINT 0x25 - - /* USB Endpoint Transfer Types */ #define USB_TRANSFER_TYPE_CONTROL 0x00 // Endpoint is a control endpoint. #define USB_TRANSFER_TYPE_ISOCHRONOUS 0x01 // Endpoint is an isochronous endpoint. diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD.h index 79c06a492b97..eb4f35eb136f 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD.h @@ -27,7 +27,6 @@ e-mail : support@circuitsathome.com #include "UHS_max3421e.h" #include - #ifndef SPI_HAS_TRANSACTION #error "Your SPI library installation is too old." #else @@ -58,8 +57,6 @@ e-mail : support@circuitsathome.com #define USB_HOST_SHIELD_USE_ISR 1 #endif - - #if !USB_HOST_SHIELD_USE_ISR #error NOISR Polled mode _NOT SUPPORTED YET_ @@ -180,8 +177,6 @@ e-mail : support@circuitsathome.com #endif #endif - - #ifdef NO_AUTO_SPEED // Ugly details section... // MAX3421E characteristics @@ -466,7 +461,6 @@ public UHS_USB_HOST_BASE interrupts(); }; - int16_t UHS_NI Init(int16_t mseconds); int16_t UHS_NI Init() { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD_INLINE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD_INLINE.h index 57352a351873..f126a6fcef74 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD_INLINE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD_INLINE.h @@ -28,7 +28,6 @@ #error digitalPinToInterrupt not defined, complain to your board maintainer. #endif - #if USB_HOST_SHIELD_USE_ISR // allow two slots. this makes the maximum allowed shield count TWO @@ -47,7 +46,6 @@ } #endif - void UHS_NI MAX3421E_HOST::resume_host() { // Used on MCU that lack control of IRQ priority (AVR). // Resumes ISRs. @@ -875,7 +873,6 @@ void UHS_NI MAX3421E_HOST::ISRbottom() { DDSB(); } - /* USB main task. Services the MAX3421e */ #if !USB_HOST_SHIELD_USE_ISR void UHS_NI MAX3421E_HOST::ISRTask() {} diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h index eeaa4f81d9fe..1318ea8b287f 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h @@ -126,12 +126,10 @@ AJK_IIF(AJK_BITAND(AJK_IS_COMPARABLE(x))(AJK_IS_COMPARABLE(y)) ) \ #define AJK_EQUAL(x, y) AJK_COMPL(AJK_NOT_EQUAL(x, y)) - #define AJK_COMMA() , #define AJK_COMMA_IF(n) AJK_IF(n)(AJK_COMMA, AJK_EAT)() - #define AJK_COMMA_VAR(AJK_count, AJK_v) AJK_COMMA_IF(AJK_count) AJK_v ## AJK_count #define AJK_MAKE_LIST(AJK_v, AJK_count) AJK_EVAL(AJK_REPEAT(AJK_count, AJK_COMMA_VAR, AJK_v)) diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/SWI_INLINE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/SWI_INLINE.h index f86054cad8a4..f50b3bd4c1e8 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/SWI_INLINE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/SWI_INLINE.h @@ -29,8 +29,6 @@ #define SWI_MAXIMUM_ALLOWED 4 #endif - - #if defined(__arm__) || defined(ARDUINO_ARCH_PIC32) static char dyn_SWI_initied = 0; static dyn_SWI* dyn_SWI_LIST[SWI_MAXIMUM_ALLOWED]; @@ -79,7 +77,6 @@ void softISR() { // TO-DO: Perhaps limit to 8, and inline this? // - // Make a working copy, while clearing the queue. noInterrupts(); #ifdef ARDUINO_ARCH_PIC32 @@ -117,7 +114,6 @@ void softISR() { #define DDSB() __DSB() #endif - #ifdef __arm__ #ifndef interruptsStatus #define interruptsStatus() __interruptsStatus() diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/dyn_SWI.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/dyn_SWI.h index 07f4ae054dcf..652b43fd2e36 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/dyn_SWI.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/dyn_SWI.h @@ -22,7 +22,6 @@ #ifndef DYN_SWI_H #define DYN_SWI_H - #if defined(__arm__) || defined(ARDUINO_ARCH_PIC32) #ifdef ARDUINO_ARCH_PIC32 #include @@ -135,7 +134,6 @@ extern "C" #error Do not know how to relocate IRQ vectors or perform SWI #endif // SWI_IRQ_NUM - #ifndef SWI_IRQ_NUM #error SWI_IRQ_NUM not defined #else diff --git a/buildroot/bin/build_all_examples b/buildroot/bin/build_all_examples index a6d6ede47d79..a77259bb360f 100755 --- a/buildroot/bin/build_all_examples +++ b/buildroot/bin/build_all_examples @@ -14,7 +14,9 @@ # build_all_examples [...] branch [resume-from] # -. mfutil +HERE=`dirname $0` + +. "$HERE/mfutil" GITREPO=https://github.com/MarlinFirmware/Configurations.git STAT_FILE=./.pio/.buildall @@ -123,7 +125,7 @@ CONF_TREE=$( ls -d "$TMP"/config/examples/*/ "$TMP"/config/examples/*/*/ "$TMP"/ for CONF in $CONF_TREE ; do # Get a config's directory name - DIR=$( echo $CONF | sed "s|$TMP/config/examples/||" ) + DIR=$( echo $CONF | "$SED" "s|$TMP/config/examples/||" ) # If looking for a config, skip others [[ $FIRST_CONF ]] && [[ $FIRST_CONF != $DIR && "$FIRST_CONF/" != $DIR ]] && continue diff --git a/buildroot/bin/build_example b/buildroot/bin/build_example index 34549769bbb1..dabc4c572cdf 100755 --- a/buildroot/bin/build_example +++ b/buildroot/bin/build_example @@ -5,7 +5,9 @@ # Usage: build_example internal config-home config-folder # -. mfutil +HERE=`dirname $0` + +. "$HERE/mfutil" # Require 'internal' as the first argument [[ "$1" == "internal" ]] || { echo "Don't call this script directly, use build_all_examples instead." ; exit 1 ; } @@ -32,7 +34,10 @@ $SED -i~ -e "20,30{/#error/d}" Marlin/Configuration.h rm Marlin/Configuration.h~ unset IFS; set +f +# Suppress fatal warnings +echo -e "\n#define NO_CONTROLLER_CUSTOM_WIRING_WARNING" >> Marlin/Configuration.h + echo "Building the firmware now..." -$HERE/mftest -s -a -n1 || { echo "Failed"; exit 1; } +"$HERE/mftest" -s -a -n1 || { echo "Failed"; exit 1; } echo "Success" diff --git a/buildroot/bin/mftest b/buildroot/bin/mftest index e4132f02a75c..5ccfd1df558e 100755 --- a/buildroot/bin/mftest +++ b/buildroot/bin/mftest @@ -8,6 +8,8 @@ [[ -d Marlin/src ]] || { echo "Please 'cd' to the Marlin repo root." ; exit 1 ; } +which pio || { echo "Make sure 'pio' is in your execution PATH." ; exit 1 ; } + perror() { echo -e "$0: \033[0;31m$1 -- $2\033[0m" ; } errout() { echo -e "\033[0;31m$1\033[0m" ; } bugout() { ((DEBUG)) && echo -e "\033[0;32m$1\033[0m" ; } diff --git a/buildroot/bin/mfutil b/buildroot/bin/mfutil index 75a2791cfedf..1699dd9adf6d 100755 --- a/buildroot/bin/mfutil +++ b/buildroot/bin/mfutil @@ -7,13 +7,12 @@ which curl 1>/dev/null 2>&1 || { echo "curl not found! Please install it."; exit ; } which git 1>/dev/null 2>&1 || { echo "git not found! Please install it."; exit ; } -SED=$(command -v gsed 2>/dev/null || command -v sed 2>/dev/null) +SED=$(which gsed sed | head -n1) [[ -z "$SED" ]] && { echo "No sed found, please install sed" ; exit 1 ; } OPEN=$( which gnome-open xdg-open open | head -n1 ) SELF=`basename "$0"` -HERE=`dirname "$0"` # Check if called in the right location [[ -e "Marlin/src" ]] || { echo -e "This script must be called from a Marlin working copy with:\n ./buildroot/bin/$SELF $1" ; exit ; } diff --git a/buildroot/bin/pins_set b/buildroot/bin/pins_set index 31b4480449a5..216eabc07686 100755 --- a/buildroot/bin/pins_set +++ b/buildroot/bin/pins_set @@ -9,7 +9,8 @@ SED=$(which gsed sed | head -n1) shift while [[ $# > 1 ]]; do PIN=$1 ; VAL=$2 - eval "${SED} -i '/^[[:blank:]]*\(\/\/\)*[[:blank:]]*\(#define \+${PIN}\b\).*$/{s//\2 ${VAL}/;h};\${x;/./{x;q0};x;q9}' Marlin/src/pins/$DIR/pins_${NAM}.h" || - (echo "ERROR: pins_set Can't find ${PIN}" >&2 && exit 9) + FOUT="${DIR}/pins_${NAM}.h" + eval "${SED} -i '/^[[:blank:]]*\(\/\/\)*[[:blank:]]*\(#define \+${PIN}\b\).*$/{s//\2 ${VAL}/;h};\${x;/./{x;q0};x;q9}' Marlin/src/pins/${FOUT}" || + (echo "ERROR: pins_set Can't find ${PIN} in ${FOUT}" >&2 && exit 9) shift 2 done diff --git a/buildroot/bin/uncrust b/buildroot/bin/uncrust index 7898f73c8c77..7c894174b8b5 100755 --- a/buildroot/bin/uncrust +++ b/buildroot/bin/uncrust @@ -4,9 +4,10 @@ # TMPDIR=`mktemp -d` +HERE=`dirname "$0"` # Reformat a single file to tmp/ -if uncrustify -l CPP -c ./buildroot/share/extras/uncrustify.cfg -f "$1" >$TMPDIR/uncrustify.out ; then +if uncrustify -l CPP -c "$HERE/../share/extras/uncrustify.cfg" -f "$1" >$TMPDIR/uncrustify.out ; then cp "$TMPDIR/uncrustify.out" "$1" ; # Replace the original file else echo "Something went wrong with uncrustify." diff --git a/buildroot/bin/use_example_configs b/buildroot/bin/use_example_configs index 1fdab1de6c5b..282e057dde46 100755 --- a/buildroot/bin/use_example_configs +++ b/buildroot/bin/use_example_configs @@ -8,28 +8,37 @@ # use_example_configs release-2.0.9.4:Creality/CR-10/CrealityV1 # # If a configpath has spaces (or quotes) escape them or enquote the path +# If no branch: prefix is given use configs based on the current branch name. +# e.g., For `latest-2.1.x` name the working branch something like "my_work-2.1.x." +# The branch or tag must first exist at MarlinFirmware/Configurations. +# The fallback branch is bugfix-2.1.x. # which curl >/dev/null && TOOL='curl -L -s -S -f -o wgot' which wget >/dev/null && TOOL='wget -q -O wgot' CURR=$(git branch 2>/dev/null | grep ^* | sed 's/\* //g') -[[ $CURR == "bugfix-2.0.x" ]] && BRANCH=bugfix-2.0.x || BRANCH=bugfix-2.1.x - -REPO=$BRANCH +case "$CURR" in + bugfix-2.*.x ) BRANCH=$CURR ;; + *-2.1.x|2.1.x ) BRANCH=latest-2.1.x ;; + *-2.0.x|2.0.x ) BRANCH=latest-2.0.x ;; + *-1.1.x|1.1.x ) BRANCH=latest-1.1.x ;; + *-1.0.x|1.0.x ) BRANCH=latest-1.0.x ;; + * ) BRANCH=bugfix-2.1.x ;; +esac if [[ $# > 0 ]]; then IFS=: read -r PART1 PART2 <<< "$@" - [[ -n $PART2 ]] && { UDIR="$PART2" ; REPO="$PART1" ; } \ + [[ -n $PART2 ]] && { UDIR="$PART2" ; BRANCH="$PART1" ; } \ || { UDIR="$PART1" ; } RDIR="${UDIR// /%20}" - echo "Fetching $UDIR configurations from $REPO..." + echo "Fetching $UDIR configurations from $BRANCH..." EXAMPLES="examples/$RDIR" else EXAMPLES="default" fi -CONFIGS="https://raw.githubusercontent.com/MarlinFirmware/Configurations/$REPO/config/${EXAMPLES}" +CONFIGS="https://raw.githubusercontent.com/MarlinFirmware/Configurations/$BRANCH/config/${EXAMPLES}" restore_configs diff --git a/buildroot/share/PlatformIO/boards/marlin_CREALITY_STM32F401RC.json b/buildroot/share/PlatformIO/boards/marlin_CREALITY_STM32F401RE.json similarity index 85% rename from buildroot/share/PlatformIO/boards/marlin_CREALITY_STM32F401RC.json rename to buildroot/share/PlatformIO/boards/marlin_CREALITY_STM32F401RE.json index 82f49fa815d6..31739c3a386a 100644 --- a/buildroot/share/PlatformIO/boards/marlin_CREALITY_STM32F401RC.json +++ b/buildroot/share/PlatformIO/boards/marlin_CREALITY_STM32F401RE.json @@ -15,11 +15,11 @@ ] ], "ldscript": "ldscript.ld", - "mcu": "stm32f401rct6", - "variant": "MARLIN_CREALITY_STM32F401RC" + "mcu": "stm32f401ret6", + "variant": "MARLIN_CREALITY_STM32F401RE" }, "debug": { - "jlink_device": "STM32F401RC", + "jlink_device": "STM32F401RE", "openocd_target": "stm32f4x", "svd_path": "STM32F40x.svd", "tools": { @@ -45,11 +45,11 @@ "arduino", "stm32cube" ], - "name": "STM32F401RC (64k RAM. 256k Flash)", + "name": "STM32F401RE (64k RAM. 512k Flash)", "upload": { "disable_flushing": false, "maximum_ram_size": 65536, - "maximum_size": 262144, + "maximum_size": 514288, "protocol": "stlink", "protocols": [ "stlink", @@ -60,6 +60,6 @@ "use_1200bps_touch": false, "wait_for_upload_port": false }, - "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f401rc.html", + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f401re.html", "vendor": "Generic" } diff --git a/buildroot/share/PlatformIO/boards/marlin_FYSETC_CHEETAH_V30.json b/buildroot/share/PlatformIO/boards/marlin_FYSETC_CHEETAH_V30.json new file mode 100644 index 000000000000..8c46404f3812 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_FYSETC_CHEETAH_V30.json @@ -0,0 +1,35 @@ +{ + "build": { + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F446xx", + "f_cpu": "180000000L", + "mcu": "stm32f446ret6", + "variant": "MARLIN_F446VE" + }, + "connectivity": [ + "can" + ], + "debug": { + "jlink_device": "STM32F446RE", + "openocd_target": "stm32f4x", + "svd_path": "STM32F446x.svd" + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "3D Printer control board", + "upload": { + "maximum_ram_size": 131072, + "maximum_size": 524288, + "protocol": "stlink", + "protocols": [ + "jlink", + "stlink", + "blackmagic", + "serial" + ] + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f446.html", + "vendor": "FYSETC" +} diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32H723Vx.json b/buildroot/share/PlatformIO/boards/marlin_STM32H723VG.json similarity index 86% rename from buildroot/share/PlatformIO/boards/marlin_STM32H723Vx.json rename to buildroot/share/PlatformIO/boards/marlin_STM32H723VG.json index a2154d448a9e..44a37e94ec21 100644 --- a/buildroot/share/PlatformIO/boards/marlin_STM32H723Vx.json +++ b/buildroot/share/PlatformIO/boards/marlin_STM32H723VG.json @@ -4,16 +4,16 @@ "cpu": "cortex-m7", "extra_flags": "-DSTM32H7xx -DSTM32H723xx", "f_cpu": "550000000L", - "mcu": "stm32h723vet6", + "mcu": "stm32h723vgt6", "product_line": "STM32H723xx", - "variant": "MARLIN_H723Vx" + "variant": "MARLIN_H723VG" }, "connectivity": [ "can", "ethernet" ], "debug": { - "jlink_device": "STM32H723VE", + "jlink_device": "STM32H723VG", "openocd_target": "stm32h7x", "svd_path": "STM32H7x3.svd", "tools": { @@ -39,11 +39,11 @@ "arduino", "stm32cube" ], - "name": "STM32H723VE (564k RAM. 512k Flash)", + "name": "STM32H723VG (564k RAM. 1024k Flash)", "upload": { "disable_flushing": false, "maximum_ram_size": 577536, - "maximum_size": 524288, + "maximum_size": 1048576, "protocol": "stlink", "protocols": [ "stlink", @@ -56,6 +56,6 @@ "use_1200bps_touch": false, "wait_for_upload_port": false }, - "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32h723ze.html", + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32h723vg.html", "vendor": "ST" } diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32H723Zx.json b/buildroot/share/PlatformIO/boards/marlin_STM32H723ZE.json similarity index 97% rename from buildroot/share/PlatformIO/boards/marlin_STM32H723Zx.json rename to buildroot/share/PlatformIO/boards/marlin_STM32H723ZE.json index 8525793c4e01..f4bb75b5dae9 100644 --- a/buildroot/share/PlatformIO/boards/marlin_STM32H723Zx.json +++ b/buildroot/share/PlatformIO/boards/marlin_STM32H723ZE.json @@ -6,7 +6,7 @@ "f_cpu": "550000000L", "mcu": "stm32h723zet6", "product_line": "STM32H723xx", - "variant": "MARLIN_H723Zx" + "variant": "MARLIN_H723ZE" }, "connectivity": [ "can", diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32H743Vx.json b/buildroot/share/PlatformIO/boards/marlin_STM32H743VI.json similarity index 97% rename from buildroot/share/PlatformIO/boards/marlin_STM32H743Vx.json rename to buildroot/share/PlatformIO/boards/marlin_STM32H743VI.json index 4ec34e5b3502..56e853cad43e 100644 --- a/buildroot/share/PlatformIO/boards/marlin_STM32H743Vx.json +++ b/buildroot/share/PlatformIO/boards/marlin_STM32H743VI.json @@ -6,7 +6,7 @@ "f_cpu": "480000000L", "mcu": "stm32h743vit6", "product_line": "STM32H743xx", - "variant": "MARLIN_H743Vx" + "variant": "MARLIN_H743VI" }, "connectivity": [ "can", diff --git a/buildroot/share/PlatformIO/debugging/launch.json b/buildroot/share/PlatformIO/debugging/launch.json index f9936ebcedf9..ddd9ba7483a3 100644 --- a/buildroot/share/PlatformIO/debugging/launch.json +++ b/buildroot/share/PlatformIO/debugging/launch.json @@ -45,6 +45,15 @@ //"program": "${workspaceRoot}/.pio/build/simulator_windows/MarlinSimulator", //"targetArchitecture": "arm64", "MIMode": "lldb" + }, + { + "name": "Launch Sim (Windows gdb)", + "request": "launch", + "type": "cppdbg", + "cwd": "${workspaceRoot}", + "program": "${workspaceRoot}/.pio/build/simulator_windows/debug/MarlinSimulator.exe", + "MIMode": "gdb", + "miDebuggerPath": "C:/msys64/mingw64/bin/gdb.exe" } ] } diff --git a/buildroot/share/PlatformIO/ldscripts/creality.ld b/buildroot/share/PlatformIO/ldscripts/creality.ld index 785345543c0c..8b330c9457b2 100644 --- a/buildroot/share/PlatformIO/ldscripts/creality.ld +++ b/buildroot/share/PlatformIO/ldscripts/creality.ld @@ -1,7 +1,7 @@ MEMORY { ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K - 40 - rom (rx) : ORIGIN = 0x08007000, LENGTH = 512K - 28K + rom (rx) : ORIGIN = 0x08007000, LENGTH = 512K - 64K } /* Provide memory region aliases for common.inc */ diff --git a/buildroot/share/PlatformIO/ldscripts/creality256k.ld b/buildroot/share/PlatformIO/ldscripts/creality256k.ld new file mode 100644 index 000000000000..1ed03caa0a56 --- /dev/null +++ b/buildroot/share/PlatformIO/ldscripts/creality256k.ld @@ -0,0 +1,14 @@ +MEMORY +{ + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K - 40 + rom (rx) : ORIGIN = 0x08007000, LENGTH = 256K - 28K +} + +/* Provide memory region aliases for common.inc */ +REGION_ALIAS("REGION_TEXT", rom); +REGION_ALIAS("REGION_DATA", ram); +REGION_ALIAS("REGION_BSS", ram); +REGION_ALIAS("REGION_RODATA", rom); + +/* Let common.inc handle the real work. */ +INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/scripts/chitu_crypt.py b/buildroot/share/PlatformIO/scripts/chitu_crypt.py index 4e81061a19ad..1458e5f8509d 100644 --- a/buildroot/share/PlatformIO/scripts/chitu_crypt.py +++ b/buildroot/share/PlatformIO/scripts/chitu_crypt.py @@ -9,7 +9,7 @@ board = marlin.env.BoardConfig() def calculate_crc(contents, seed): - accumulating_xor_value = seed; + accumulating_xor_value = seed for i in range(0, len(contents), 4): value = struct.unpack(')', feat['build_src_filter']) - cur_srcs = re.findall(r'[+-](<.*?>)', build_src_filter) - for d in my_srcs: - if d in cur_srcs: - build_src_filter = re.sub(r'[+-]' + d, '', build_src_filter) - - build_src_filter = feat['build_src_filter'] + ' ' + build_src_filter - set_env_field('build_src_filter', [build_src_filter]) - env.Replace(SRC_FILTER=build_src_filter) + build_filters = build_filters + ' ' + feat['build_src_filter'] + # Just append the filter in the order that the build environment specifies. + # Important here is the order of entries in the "features.ini" file. 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) + build_src_filter = "" + if True: + # Build the actual equivalent build_src_filter list based on the inclusions by the features. + # PlatformIO doesn't do it this way, but maybe in the future.... + cur_srcs = set() + # Remove the references to the same folder + my_srcs = re.findall(r'([+-]<.*?>)', build_filters) + for d in my_srcs: + # Assume normalized relative paths + plain = d[2:-1] + if d[0] == '+': + def addentry(fullpath, info=None): + relp = os.path.relpath(fullpath, marlinbasedir) + if srcfilepattern.match(relp): + if info: + blab("Added src file %s (%s)" % (relp, str(info)), 3) + else: + blab("Added src file %s " % relp, 3) + cur_srcs.add(relp) + # Special rule: If a direct folder is specified add all files within. + fullplain = os.path.join(marlinbasedir, plain) + if os.path.isdir(fullplain): + blab("Directory content addition for %s " % plain, 3) + gpattern = os.path.join(fullplain, "**") + for fname in glob.glob(gpattern, recursive=True): + addentry(fname, "dca") + else: + # Add all the things from the pattern by GLOB. + def srepl(matchi): + g0 = matchi.group(0) + return r"**" + g0[1:] + gpattern = re.sub(r'[*]($|[^*])', srepl, plain) + gpattern = os.path.join(marlinbasedir, gpattern) + + for fname in glob.glob(gpattern, recursive=True): + addentry(fname) + else: + # Special rule: If a direct folder is specified then remove all files within. + def onremove(relp, info=None): + if info: + blab("Removed src file %s (%s)" % (relp, str(info)), 3) + else: + blab("Removed src file %s " % relp, 3) + fullplain = os.path.join(marlinbasedir, plain) + if os.path.isdir(fullplain): + blab("Directory content removal for %s " % plain, 2) + def filt(x): + common = os.path.commonpath([plain, x]) + if not common == os.path.normpath(plain): return True + onremove(x, "dcr") + return False + cur_srcs = set(filter(filt, cur_srcs)) + else: + # Remove matching source entries. + def filt(x): + if not fnmatch.fnmatch(x, plain): return True + onremove(x) + return False + cur_srcs = set(filter(filt, cur_srcs)) + # Transform the resulting set into a string. + for x in cur_srcs: + if build_src_filter != "": build_src_filter += ' ' + build_src_filter += "+<" + x + ">" + + #blab("Final build_src_filter: " + build_src_filter, 3) + else: + build_src_filter = build_filters + + # Update in PlatformIO + set_env_field('build_src_filter', [build_src_filter]) + env.Replace(SRC_FILTER=build_src_filter) + # # Use the compiler to get a list of all enabled features # @@ -213,7 +281,7 @@ def load_marlin_features(): # def MarlinHas(env, feature): load_marlin_features() - r = re.compile('^' + feature + '$') + r = re.compile('^' + feature + '$', re.IGNORECASE) found = list(filter(r.match, env['MARLIN_FEATURES'])) # Defines could still be 'false' or '0', so check @@ -226,6 +294,8 @@ def MarlinHas(env, feature): elif val in env['MARLIN_FEATURES']: some_on = env.MarlinHas(val) + #blab("%s is %s" % (feature, str(some_on)), 2) + return some_on validate_pio() diff --git a/buildroot/share/PlatformIO/scripts/configuration.py b/buildroot/share/PlatformIO/scripts/configuration.py old mode 100644 new mode 100755 index 250d9bbd7f11..e0387a219da4 --- a/buildroot/share/PlatformIO/scripts/configuration.py +++ b/buildroot/share/PlatformIO/scripts/configuration.py @@ -1,8 +1,9 @@ +#!/usr/bin/env python3 # # configuration.py # Apply options from config.ini to the existing Configuration headers # -import re, shutil, configparser +import re, shutil, configparser, datetime from pathlib import Path verbose = 0 @@ -43,6 +44,7 @@ def apply_opt(name, val, conf=None): if val in ("on", "", None): newline = re.sub(r'^(\s*)//+\s*(#define)(\s{1,3})?(\s*)', r'\1\2 \4', line) elif val == "off": + # TODO: Comment more lines in a multi-line define with \ continuation newline = re.sub(r'^(\s*)(#define)(\s{1,3})?(\s*)', r'\1//\2 \4', line) else: # For options with values, enable and set the value @@ -88,9 +90,38 @@ def apply_opt(name, val, conf=None): elif not isdef: break linenum += 1 - lines.insert(linenum, f"{prefix}#define {added:30} // Added by config.ini\n") + currtime = datetime.datetime.now().strftime("%Y-%m-%d %H:%M:%S") + lines.insert(linenum, f"{prefix}#define {added:30} // Added by config.ini {currtime}\n") fullpath.write_text(''.join(lines), encoding='utf-8') +# Disable all (most) defined options in the configuration files. +# Everything in the named sections. Section hint for exceptions may be added. +def disable_all_options(): + # Create a regex to match the option and capture parts of the line + regex = re.compile(r'^(\s*)(#define\s+)([A-Z0-9_]+\b)(\s?)(\s*)(.*?)(\s*)(//.*)?$', re.IGNORECASE) + + # Disable all enabled options in both Config files + for file in ("Configuration.h", "Configuration_adv.h"): + fullpath = config_path(file) + lines = fullpath.read_text(encoding='utf-8').split('\n') + found = False + for i in range(len(lines)): + line = lines[i] + match = regex.match(line) + if match: + name = match[3].upper() + if name in ('CONFIGURATION_H_VERSION', 'CONFIGURATION_ADV_H_VERSION'): continue + if name.startswith('_'): continue + found = True + # Comment out the define + # TODO: Comment more lines in a multi-line define with \ continuation + lines[i] = re.sub(r'^(\s*)(#define)(\s{1,3})?(\s*)', r'\1//\2 \4', line) + blab(f"Disable {name}") + + # If the option was found, write the modified lines + if found: + fullpath.write_text('\n'.join(lines), encoding='utf-8') + # Fetch configuration files from GitHub given the path. # Return True if any files were fetched. def fetch_example(url): @@ -130,7 +161,7 @@ def fetch_example(url): def section_items(cp, sectkey): return cp.items(sectkey) if sectkey in cp.sections() else [] -# Apply all items from a config section +# Apply all items from a config section. Ignore ini_ items outside of config:base and config:root. def apply_ini_by_name(cp, sect): iniok = True if sect in ('config:base', 'config:root'): @@ -194,7 +225,7 @@ def apply_config_ini(cp): cp2 = configparser.ConfigParser() cp2.read(config_path(ckey)) apply_sections(cp2, sect) - ckey = 'base'; + ckey = 'base' # (Allow 'example/' as a shortcut for 'examples/') elif ckey.startswith('example/'): @@ -206,7 +237,17 @@ def apply_config_ini(cp): fetch_example(ckey) ckey = 'base' - if ckey == 'all': + # + # [flatten] Write out Configuration.h and Configuration_adv.h files with + # just the enabled options and all other content removed. + # + #if ckey == '[flatten]': + # write_flat_configs() + + if ckey == '[disable]': + disable_all_options() + + elif ckey == 'all': apply_sections(cp) else: diff --git a/buildroot/share/PlatformIO/scripts/download_mks_assets.py b/buildroot/share/PlatformIO/scripts/download_mks_assets.py index 661fb2e438e4..0186f59896ea 100644 --- a/buildroot/share/PlatformIO/scripts/download_mks_assets.py +++ b/buildroot/share/PlatformIO/scripts/download_mks_assets.py @@ -14,7 +14,7 @@ assets_path = Path(env.Dictionary("PROJECT_BUILD_DIR"), env.Dictionary("PIOENV"), "assets") def download_mks_assets(): - print("Downloading MKS Assets") + print("Downloading MKS Assets for TFT_LVGL_UI") r = requests.get(url, stream=True) # the user may have a very clean workspace, # so create the PROJECT_LIBDEPS_DIR directory if not exits @@ -25,7 +25,7 @@ def download_mks_assets(): fd.write(chunk) def copy_mks_assets(): - print("Copying MKS Assets") + print("Copying MKS Assets for TFT_LVGL_UI") output_path = Path(tempfile.mkdtemp()) zip_obj = zipfile.ZipFile(zip_path, 'r') zip_obj.extractall(output_path) diff --git a/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py b/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py index 879a7da3d49b..e149d1d62b3e 100644 --- a/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py +++ b/buildroot/share/PlatformIO/scripts/fix_framework_weakness.py @@ -23,7 +23,7 @@ assert isfile(original_file) and isfile(src_file) shutil.copyfile(original_file, backup_file) - shutil.copyfile(src_file, original_file); + shutil.copyfile(src_file, original_file) def _touch(path): with open(path, "w") as fp: diff --git a/buildroot/share/PlatformIO/scripts/generic_create_variant.py b/buildroot/share/PlatformIO/scripts/generic_create_variant.py index 49d4c98d3e15..54aeed5d1df6 100644 --- a/buildroot/share/PlatformIO/scripts/generic_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -5,7 +5,8 @@ # the appropriate framework variants folder, so that its contents # will be picked up by PlatformIO just like any other variant. # -import pioutil +import pioutil, re +marlin_variant_pattern = re.compile("marlin_.*") if pioutil.is_pio_build(): import shutil,marlin from pathlib import Path @@ -30,10 +31,11 @@ } 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", "biqu-bx-workaround", "main" ]: - platform_name = "framework-arduinoststm32" + spec = PackageSpec(platform_packages[0]) + if spec.uri and '@' in spec.uri: + platform_name = re.sub(r'@.+', '', spec.uri) + else: + platform_name = spec.name FRAMEWORK_DIR = Path(platform.get_package_dir(platform_name)) assert FRAMEWORK_DIR.is_dir() @@ -44,15 +46,20 @@ variant = board.get("build.variant") #series = mcu_type[:7].upper() + "xx" - # Prepare a new empty folder at the destination - variant_dir = FRAMEWORK_DIR / "variants" / variant - if variant_dir.is_dir(): - shutil.rmtree(variant_dir) - if not variant_dir.is_dir(): - variant_dir.mkdir() + # Only prepare a new variant if the PlatformIO configuration provides it (board_build.variant). + # This check is important to avoid deleting official board config variants. + if marlin_variant_pattern.match(str(variant).lower()): + # Prepare a new empty folder at the destination + variant_dir = FRAMEWORK_DIR / "variants" / variant + if variant_dir.is_dir(): + shutil.rmtree(variant_dir) + if not variant_dir.is_dir(): + variant_dir.mkdir() + + # Source dir is a local variant sub-folder + source_dir = Path("buildroot/share/PlatformIO/variants", variant) + assert source_dir.is_dir() - # Source dir is a local variant sub-folder - source_dir = Path("buildroot/share/PlatformIO/variants", variant) - assert source_dir.is_dir() + print("Copying variant " + str(variant) + " to framework directory...") - marlin.copytree(source_dir, variant_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 9256751096c5..4400ebe1614e 100644 --- a/buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py +++ b/buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py @@ -32,4 +32,4 @@ def addboot(source, target, env): fw_path.rename(fws_path) import marlin - marlin.add_post_action(addboot); + marlin.add_post_action(addboot) diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py index 8d8dbb5b63d4..4a77651307bd 100644 --- a/buildroot/share/PlatformIO/scripts/marlin.py +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -70,4 +70,4 @@ def encrypt_mks(source, target, env, new_name): fwpath.unlink() def add_post_action(action): - env.AddPostAction(str(Path("$BUILD_DIR", "${PROGNAME}.bin")), action); + env.AddPostAction(str(Path("$BUILD_DIR", "${PROGNAME}.bin")), action) diff --git a/buildroot/share/PlatformIO/scripts/offset_and_rename.py b/buildroot/share/PlatformIO/scripts/offset_and_rename.py index de14ccbbbf5f..353518600853 100644 --- a/buildroot/share/PlatformIO/scripts/offset_and_rename.py +++ b/buildroot/share/PlatformIO/scripts/offset_and_rename.py @@ -1,7 +1,7 @@ # # offset_and_rename.py # -# - If 'build.offset' is provided, either by JSON or by the environment... +# - If 'board_build.offset' is provided, either by JSON or by the environment... # - Set linker flag LD_FLASH_OFFSET and relocate the VTAB based on 'build.offset'. # - Set linker flag LD_MAX_DATA_SIZE based on 'build.maximum_ram_size'. # - Define STM32_FLASH_SIZE from 'upload.maximum_size' for use by Flash-based EEPROM emulation. @@ -60,6 +60,10 @@ def encrypt(source, target, env): def rename_target(source, target, env): from pathlib import Path - Path(target[0].path).replace(Path(target[0].dir.path, new_name)) + from datetime import datetime + from os import path + _newpath = Path(target[0].dir.path, datetime.now().strftime(new_name.replace('{date}', '%Y%m%d').replace('{time}', '%H%M%S'))) + Path(target[0].path).replace(_newpath) + env['PROGNAME'] = path.splitext(_newpath)[0] marlin.add_post_action(rename_target) diff --git a/buildroot/share/PlatformIO/scripts/preflight-checks.py b/buildroot/share/PlatformIO/scripts/preflight-checks.py index 3f7c97af9d78..2e4ab5c92d54 100644 --- a/buildroot/share/PlatformIO/scripts/preflight-checks.py +++ b/buildroot/share/PlatformIO/scripts/preflight-checks.py @@ -72,7 +72,7 @@ def sanity_check_target(): result = check_envs("env:"+build_env, board_envs, config) if not result: - err = "Error: Build environment '%s' is incompatible with %s. Use one of these: %s" % \ + err = "Error: Build environment '%s' is incompatible with %s. Use one of these environments: %s" % \ ( build_env, motherboard, ", ".join([ e[4:] for e in board_envs if e.startswith("env:") ]) ) raise SystemExit(err) @@ -90,7 +90,7 @@ def sanity_check_target(): # Find the name.cpp.o or name.o and remove it # def rm_ofile(subdir, name): - build_dir = Path(env['PROJECT_BUILD_DIR'], build_env); + build_dir = Path(env['PROJECT_BUILD_DIR'], build_env) for outdir in (build_dir, build_dir / "debug"): for ext in (".cpp.o", ".o"): fpath = outdir / "src/src" / subdir / (name + ext) diff --git a/buildroot/share/PlatformIO/scripts/random-bin.py b/buildroot/share/PlatformIO/scripts/random-bin.py deleted file mode 100644 index dc8634ea7d64..000000000000 --- a/buildroot/share/PlatformIO/scripts/random-bin.py +++ /dev/null @@ -1,9 +0,0 @@ -# -# random-bin.py -# Set a unique firmware name based on current date and time -# -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/schema.py b/buildroot/share/PlatformIO/scripts/schema.py index 103aa1f072dc..381ee57a9543 100755 --- a/buildroot/share/PlatformIO/scripts/schema.py +++ b/buildroot/share/PlatformIO/scripts/schema.py @@ -2,8 +2,14 @@ # # schema.py # -# Used by signature.py via common-dependencies.py to generate a schema file during the PlatformIO build. -# This script can also be run standalone from within the Marlin repo to generate all schema files. +# Used by signature.py via common-dependencies.py to generate a schema file during the PlatformIO build +# when CONFIG_EXPORT is defined in the configuration. +# +# This script can also be run standalone from within the Marlin repo to generate JSON and YAML schema files. +# +# This script is a companion to abm/js/schema.js in the MarlinFirmware/AutoBuildMarlin project, which has +# been extended to evaluate conditions and can determine what options are actually enabled, not just which +# options are uncommented. That will be migrated to this script for standalone migration. # import re,json from pathlib import Path @@ -74,7 +80,26 @@ def load_boards(): return '' # -# Extract a schema from the current configuration files +# Extract the current configuration files in the form of a structured schema. +# Contains the full schema for the configuration files, not just the enabled options, +# Contains the current values of the options, not just data structure, so "schema" is a slight misnomer. +# +# The returned object is a nested dictionary with the following indexing: +# +# - schema[filekey][section][define_name] = define_info +# +# Where the define_info contains the following keyed fields: +# - section = The @section the define is in +# - name = The name of the define +# - enabled = True if the define is enabled (not commented out) +# - line = The line number of the define +# - sid = A serial ID for the define +# - value = The value of the define, if it has one +# - type = The type of the define, if it has one +# - requires = The conditions that must be met for the define to be enabled +# - comment = The comment for the define, if it has one +# - units = The units for the define, if it has one +# - options = The options for the define, if it has one # def extract(): # Load board names from boards.h @@ -85,7 +110,8 @@ class Parse: NORMAL = 0 # No condition yet BLOCK_COMMENT = 1 # Looking for the end of the block comment EOL_COMMENT = 2 # EOL comment started, maybe add the next comment? - GET_SENSORS = 3 # Gathering temperature sensor options + SLASH_COMMENT = 3 # Block-like comment, starting with aligned // + GET_SENSORS = 4 # Gathering temperature sensor options ERROR = 9 # Syntax error # List of files to process, with shorthand @@ -94,6 +120,8 @@ class Parse: sch_out = { 'basic':{}, 'advanced':{} } # Regex for #define NAME [VALUE] [COMMENT] with sanitized line defgrep = re.compile(r'^(//)?\s*(#define)\s+([A-Za-z0-9_]+)\s*(.*?)\s*(//.+)?$') + # Pattern to match a float value + flt = r'[-+]?\s*(\d+\.|\d*\.\d+)([eE][-+]?\d+)?[fF]?' # Defines to ignore ignore = ('CONFIGURATION_H_VERSION', 'CONFIGURATION_ADV_H_VERSION', 'CONFIG_EXAMPLES_DIR', 'CONFIG_EXPORT') # Start with unknown state @@ -107,6 +135,7 @@ class Parse: line_number = 0 # Counter for the line number of the file conditions = [] # Create a condition stack for the current file comment_buff = [] # A temporary buffer for comments + prev_comment = '' # Copy before reset for an EOL comment options_json = '' # A buffer for the most recent options JSON found eol_options = False # The options came from end of line, so only apply once join_line = False # A flag that the line should be joined with the previous one @@ -143,9 +172,13 @@ class Parse: if not defmatch and the_line.startswith('//'): comment_buff.append(the_line[2:].strip()) else: - last_added_ref['comment'] = ' '.join(comment_buff) - comment_buff = [] state = Parse.NORMAL + cline = ' '.join(comment_buff) + comment_buff = [] + if cline != '': + # A (block or slash) comment was already added + cfield = 'notes' if 'comment' in last_added_ref else 'comment' + last_added_ref[cfield] = cline def use_comment(c, opt, sec, bufref): if c.startswith(':'): # If the comment starts with : then it has magic JSON @@ -162,6 +195,15 @@ def use_comment(c, opt, sec, bufref): bufref.append(c) return opt, sec + # For slash comments, capture consecutive slash comments. + # The comment will be applied to the next #define. + if state == Parse.SLASH_COMMENT: + if not defmatch and the_line.startswith('//'): + use_comment(the_line[2:].strip(), options_json, section, comment_buff) + continue + else: + state = Parse.NORMAL + # In a block comment, capture lines up to the end of the comment. # Assume nothing follows the comment closure. if state in (Parse.BLOCK_COMMENT, Parse.GET_SENSORS): @@ -178,19 +220,19 @@ def use_comment(c, opt, sec, bufref): state = Parse.NORMAL # Strip the leading '*' from block comments - if cline.startswith('*'): cline = cline[1:].strip() + cline = re.sub(r'^\* ?', '', cline) # Collect temperature sensors if state == Parse.GET_SENSORS: sens = re.match(r'^(-?\d+)\s*:\s*(.+)$', cline) if sens: s2 = sens[2].replace("'","''") - options_json += f"{sens[1]}:'{s2}', " + options_json += f"{sens[1]}:'{sens[1]} - {s2}', " elif state == Parse.BLOCK_COMMENT: # Look for temperature sensors - if cline == "Temperature sensors available:": + if re.match(r'temperature sensors.*:', cline, re.IGNORECASE): state, cline = Parse.GET_SENSORS, "Temperature Sensors" options_json, section = use_comment(cline, options_json, section, comment_buff) @@ -216,15 +258,19 @@ def use_comment(c, opt, sec, bufref): # Comment after a define may be continued on the following lines if defmatch != None and cpos > 10: state = Parse.EOL_COMMENT + prev_comment = '\n'.join(comment_buff) comment_buff = [] + else: + state = Parse.SLASH_COMMENT # Process the start of a new comment if cpos != -1: + comment_buff = [] cline, line = line[cpos+2:].strip(), line[:cpos].strip() if state == Parse.BLOCK_COMMENT: # Strip leading '*' from block comments - if cline.startswith('*'): cline = cline[1:].strip() + cline = re.sub(r'^\* ?', '', cline) else: # Expire end-of-line options after first use if cline.startswith(':'): eol_options = True @@ -295,32 +341,33 @@ def atomize(s): } # Type is based on the value - if val == '': - value_type = 'switch' - elif re.match(r'^(true|false)$', val): - value_type = 'bool' - val = val == 'true' - elif re.match(r'^[-+]?\s*\d+$', val): - value_type = 'int' - val = int(val) - elif re.match(r'[-+]?\s*(\d+\.|\d*\.\d+)([eE][-+]?\d+)?[fF]?', val): - value_type = 'float' - val = float(val.replace('f','')) - else: - value_type = 'string' if val[0] == '"' \ - else 'char' if val[0] == "'" \ - else 'state' if re.match(r'^(LOW|HIGH)$', val) \ - else 'enum' if re.match(r'^[A-Za-z0-9_]{3,}$', val) \ - else 'int[]' if re.match(r'^{(\s*[-+]?\s*\d+\s*(,\s*)?)+}$', val) \ - else 'float[]' if re.match(r'^{(\s*[-+]?\s*(\d+\.|\d*\.\d+)([eE][-+]?\d+)?[fF]?\s*(,\s*)?)+}$', val) \ - else 'array' if val[0] == '{' \ - else '' + value_type = \ + 'switch' if val == '' \ + else 'bool' if re.match(r'^(true|false)$', val) \ + else 'int' if re.match(r'^[-+]?\s*\d+$', val) \ + else 'ints' if re.match(r'^([-+]?\s*\d+)(\s*,\s*[-+]?\s*\d+)+$', val) \ + else 'floats' if re.match(rf'({flt}(\s*,\s*{flt})+)', val) \ + else 'float' if re.match(f'^({flt})$', val) \ + else 'string' if val[0] == '"' \ + else 'char' if val[0] == "'" \ + else 'state' if re.match(r'^(LOW|HIGH)$', val) \ + else 'enum' if re.match(r'^[A-Za-z0-9_]{3,}$', val) \ + else 'int[]' if re.match(r'^{\s*[-+]?\s*\d+(\s*,\s*[-+]?\s*\d+)*\s*}$', val) \ + else 'float[]' if re.match(r'^{{\s*{flt}(\s*,\s*{flt})*\s*}}$', val) \ + else 'array' if val[0] == '{' \ + else '' + + val = (val == 'true') if value_type == 'bool' \ + else int(val) if value_type == 'int' \ + else val.replace('f','') if value_type == 'floats' \ + else float(val.replace('f','')) if value_type == 'float' \ + else val if val != '': define_info['value'] = val if value_type != '': define_info['type'] = value_type # Join up accumulated conditions with && - if conditions: define_info['requires'] = ' && '.join(sum(conditions, [])) + if conditions: define_info['requires'] = '(' + ') && ('.join(sum(conditions, [])) + ')' # If the comment_buff is not empty, add the comment to the info if comment_buff: @@ -383,25 +430,35 @@ def main(): if schema: - # Get the first command line argument + # Get the command line arguments after the script name import sys - if len(sys.argv) > 1: - arg = sys.argv[1] - else: - arg = 'some' + args = sys.argv[1:] + if len(args) == 0: args = ['some'] + + # Does the given array intersect at all with args? + def inargs(c): return len(set(args) & set(c)) > 0 + + # Help / Unknown option + unk = not inargs(['some','json','jsons','group','yml','yaml']) + if (unk): print(f"Unknown option: '{args[0]}'") + if inargs(['-h', '--help']) or unk: + print("Usage: schema.py [some|json|jsons|group|yml|yaml]...") + print(" some = json + yml") + print(" jsons = json + group") + return # JSON schema - if arg in ['some', 'json', 'jsons']: + if inargs(['some', 'json', 'jsons']): print("Generating JSON ...") dump_json(schema, Path('schema.json')) # JSON schema (wildcard names) - if arg in ['group', 'jsons']: + if inargs(['group', 'jsons']): group_options(schema) dump_json(schema, Path('schema_grouped.json')) # YAML - if arg in ['some', 'yml', 'yaml']: + if inargs(['some', 'yml', 'yaml']): try: import yaml except ImportError: diff --git a/buildroot/share/PlatformIO/scripts/signature.py b/buildroot/share/PlatformIO/scripts/signature.py old mode 100644 new mode 100755 index 84312da01bd9..2d024c366287 --- a/buildroot/share/PlatformIO/scripts/signature.py +++ b/buildroot/share/PlatformIO/scripts/signature.py @@ -1,3 +1,4 @@ +#!/usr/bin/env python3 # # signature.py # @@ -7,24 +8,54 @@ from datetime import datetime from pathlib import Path -# -# Return all macro names in a header as an array, so we can take -# the intersection with the preprocessor output, giving a decent -# reflection of all enabled options that (probably) came from the -# configuration files. We end up with the actual configured state, -# better than what the config files say. You can then use the -# resulting config.ini to produce more exact configuration files. -# -def extract_defines(filepath): +def enabled_defines(filepath): + ''' + Return all enabled #define items from a given C header file in a dictionary. + A "#define" in a multi-line comment could produce a false positive if it's not + preceded by a non-space character (like * in a multi-line comment). + + Output: + Each entry is a dictionary with a 'name' and a 'section' key. We end up with: + { MOTHERBOARD: { name: "MOTHERBOARD", section: "hardware" }, ... } + + The 'name' key might get dropped as redundant, but it's useful for debugging. + + Because the option names are the keys, only the last occurrence is retained. + Use the Schema class for a more complete list of options, soon with full parsing. + + This list is used to filter what is actually a config-defined option versus + defines from elsewhere. + + While the Schema class parses the configurations on its own, this script will + get the preprocessor output and get the intersection of the enabled options from + our crude scraping method and the actual compiler output. + We end up with the actual configured state, + better than what the config files say. You can then use the + a decent reflection of all enabled options that (probably) came from + resulting config.ini to produce more exact configuration files. + ''' + outdict = {} + section = "user" + spatt = re.compile(r".*@section +([-a-zA-Z0-9_\s]+)$") # must match @section ... + f = open(filepath, encoding="utf8").read().split("\n") + + # Get the full contents of the file and remove all block comments. + # This will avoid false positives from #defines in comments + f = re.sub(r'/\*.*?\*/', '', '\n'.join(f), flags=re.DOTALL).split("\n") + a = [] for line in f: sline = line.strip() + m = re.match(spatt, sline) # @section ... + if m: + section = m.group(1).strip() + continue 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 + outdict[kv[0]] = { 'name':kv[0], 'section': section } + return outdict # Compute the SHA256 hash of a file def get_file_sha256sum(filepath): @@ -43,160 +74,247 @@ def compress_file(filepath, storedname, outpath): with zipfile.ZipFile(outpath, 'w', compression=zipfile.ZIP_BZIP2, compresslevel=9) as zipf: zipf.write(filepath, arcname=storedname, 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' ] + ''' + Compute the build signature by extracting all configuration settings and + building a unique reversible signature that can be included in the binary. + The signature can be reversed to get a 1:1 equivalent configuration file. + ''' + if 'BUILD_SIGNATURE' in env: return + env.Append(BUILD_SIGNATURE=1) build_path = Path(env['PROJECT_BUILD_DIR'], env['PIOENV']) + marlin_json = build_path / 'marlin_config.json' + marlin_zip = build_path / 'mc.zip' + + # Definitions from these files will be kept + header_paths = [ 'Marlin/Configuration.h', 'Marlin/Configuration_adv.h' ] # Check if we can skip processing hashes = '' - for header in files_to_keep: + for header in header_paths: hashes += get_file_sha256sum(header)[0:10] - marlin_json = build_path / 'marlin_config.json' - marlin_zip = build_path / 'mc.zip' - - # Read existing config file + # Read a previously exported JSON file + # Same configuration, skip recomputing the build signature + same_hash = False try: with marlin_json.open() as infile: conf = json.load(infile) - if conf['__INITIAL_HASH'] == hashes: - # Same configuration, skip recomputing the building signature + same_hash = conf['__INITIAL_HASH'] == hashes + if same_hash: compress_file(marlin_json, 'marlin_config.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 + # Extract "enabled" #define lines by scraping the configuration files. + # This data also contains the @section for each option. conf_defines = {} - all_defines = [] - for header in files_to_keep: - defines = extract_defines(header) - # To filter only the define we want - all_defines += defines - # To remember from which file it cames from - conf_defines[header.split('/')[-1]] = defines + conf_names = [] + for hpath in header_paths: + # Get defines in the form of { name: { name:..., section:... }, ... } + defines = enabled_defines(hpath) + # Get all unique define names into a flat array + conf_names += defines.keys() + # Remember which file these defines came from + conf_defines[hpath.split('/')[-1]] = defines + + # Get enabled config options based on running GCC to preprocess the config files. + # The result is a list of line strings, each starting with '#define'. + from preprocessor import run_preprocessor + build_output = run_preprocessor(env) + # Dumb regex to filter out some dumb macros 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 + # Extract all the #define lines in the build output as key/value pairs + build_defines = {} + for line in build_output: + # 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 - + if len(key) > 2 and key[0:2] == "__": continue + # Ignore values containing parentheses (likely a function macro) + if '(' in key and ')' in key: continue # Then filter dumb values - if r.match(value): - continue + if r.match(value): continue - defines[key] = value if len(value) else "" + build_defines[key] = value if len(value) else "" # # Continue to gather data for CONFIGURATION_EMBEDDING or CONFIG_EXPORT # - if not ('CONFIGURATION_EMBEDDING' in defines or 'CONFIG_EXPORT' in defines): + if not ('CONFIGURATION_EMBEDDING' in build_defines or 'CONFIG_EXPORT' in build_defines): return - # Second step is to filter useless macro - resolved_defines = {} - for key in defines: + # Filter out useless macros from the output + cleaned_build_defines = {} + for key in build_defines: # Remove all boards now - if key.startswith("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.endswith("_NAME") and key != "CUSTOM_MACHINE_NAME": - continue + if key.startswith("BOARD_") and key != "BOARD_INFO_NAME": continue # Remove all keys ending by "_T_DECLARED" as it's a copy of extraneous system stuff - if key.endswith("_T_DECLARED"): - continue + if key.endswith("_T_DECLARED"): continue # Remove keys that are not in the #define list in the Configuration list - if key not in all_defines + [ 'DETAILED_BUILD_VERSION', '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 + if key not in conf_names + [ 'DETAILED_BUILD_VERSION', 'STRING_DISTRIBUTION_DATE' ]: continue + # Add to a new dictionary for simplicity + cleaned_build_defines[key] = build_defines[key] + + # And we only care about defines that (most likely) came from the config files + # Build a dictionary of dictionaries with keys: 'name', 'section', 'value' + # { 'file1': { 'option': { 'name':'option', 'section':..., 'value':... }, ... }, 'file2': { ... } } + real_config = {} for header in conf_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 conf_defines: + real_config[header] = {} + for key in cleaned_build_defines: if key in conf_defines[header]: - data[header][key] = resolved_defines[key] + if key[0:2] == '__': continue + val = cleaned_build_defines[key] + real_config[header][key] = { 'file':header, 'name': key, 'value': val, 'section': conf_defines[header][key]['section']} - # Every python needs this toy def tryint(key): - try: - return int(defines[key]) - except: - return 0 + try: return int(build_defines[key]) + except: return 0 + # Get the CONFIG_EXPORT value and do an extended dump if > 100 + # For example, CONFIG_EXPORT 102 will make a 'config.ini' with a [config:] group for each schema @section config_dump = tryint('CONFIG_EXPORT') + extended_dump = config_dump > 100 + if extended_dump: config_dump -= 100 # # Produce an INI file if CONFIG_EXPORT == 2 # if config_dump == 2: print("Generating config.ini ...") + + ini_fmt = '{0:40} = {1}' + ext_fmt = '{0:40} {1}' + ignore = ('CONFIGURATION_H_VERSION', 'CONFIGURATION_ADV_H_VERSION', 'CONFIG_EXPORT') + + if extended_dump: + # Extended export will dump config options by section + + # We'll use Schema class to get the sections + try: + conf_schema = schema.extract() + except Exception as exc: + print("Error: " + str(exc)) + exit(1) + + # Then group options by schema @section + sections = {} + for header in real_config: + for name in real_config[header]: + #print(f" name: {name}") + if name not in ignore: + ddict = real_config[header][name] + #print(f" real_config[{header}][{name}]:", ddict) + sect = ddict['section'] + if sect not in sections: sections[sect] = {} + sections[sect][name] = ddict + + # Get all sections as a list of strings, with spaces and dashes replaced by underscores + long_list = [ re.sub(r'[- ]+', '_', x).lower() for x in sections.keys() ] + # Make comma-separated lists of sections with 64 characters or less + sec_lines = [] + while len(long_list): + line = long_list.pop(0) + ', ' + while len(long_list) and len(line) + len(long_list[0]) < 64 - 1: + line += long_list.pop(0) + ', ' + sec_lines.append(line.strip()) + sec_lines[-1] = sec_lines[-1][:-1] # Remove the last comma + + else: + sec_lines = ['all'] + + # Build the ini_use_config item + sec_list = ini_fmt.format('ini_use_config', sec_lines[0]) + for line in sec_lines[1:]: sec_list += '\n' + ext_fmt.format('', line) + config_ini = build_path / 'config.ini' with config_ini.open('w') as outfile: - ignore = ('CONFIGURATION_H_VERSION', 'CONFIGURATION_ADV_H_VERSION', 'CONFIG_EXPORT') filegrp = { 'Configuration.h':'config:basic', 'Configuration_adv.h':'config:advanced' } - vers = defines["CONFIGURATION_H_VERSION"] + vers = build_defines["CONFIGURATION_H_VERSION"] dt_string = datetime.now().strftime("%Y-%m-%d at %H:%M:%S") - ini_fmt = '{0:40}{1}\n' + outfile.write( - '#\n' - + '# Marlin Firmware\n' - + '# config.ini - Options to apply before the build\n' - + '#\n' - + f'# Generated by Marlin build on {dt_string}\n' - + '#\n' - + '\n' - + '[config:base]\n' - + ini_fmt.format('ini_use_config', ' = all') - + ini_fmt.format('ini_config_vers', f' = {vers}') - ) - # Loop through the data array of arrays - for header in data: - if header.startswith('__'): - continue - outfile.write('\n[' + filegrp[header] + ']\n') - for key in sorted(data[header]): - if key not in ignore: - val = 'on' if data[header][key] == '' else data[header][key] - outfile.write(ini_fmt.format(key.lower(), ' = ' + val)) +f'''# +# Marlin Firmware +# config.ini - Options to apply before the build +# +# Generated by Marlin build on {dt_string} +# +[config:base] +# +# ini_use_config - A comma-separated list of actions to apply to the Configuration files. +# The actions will be applied in the listed order. +# - none +# Ignore this file and don't apply any configuration options +# +# - base +# Just apply the options in config:base to the configuration +# +# - minimal +# Just apply the options in config:minimal to the configuration +# +# - all +# Apply all 'config:*' sections in this file to the configuration +# +# - another.ini +# Load another INI file with a path relative to this config.ini file (i.e., within Marlin/) +# +# - https://me.myserver.com/path/to/configs +# Fetch configurations from any URL. +# +# - example/Creality/Ender-5 Plus @ bugfix-2.1.x +# Fetch example configuration files from the MarlinFirmware/Configurations repository +# https://raw.githubusercontent.com/MarlinFirmware/Configurations/bugfix-2.1.x/config/examples/Creality/Ender-5%20Plus/ +# +# - example/default @ release-2.0.9.7 +# Fetch default configuration files from the MarlinFirmware/Configurations repository +# https://raw.githubusercontent.com/MarlinFirmware/Configurations/release-2.0.9.7/config/default/ +# +# - [disable] +# Comment out all #defines in both Configuration.h and Configuration_adv.h. This is useful +# to start with a clean slate before applying any config: options, so only the options explicitly +# set in config.ini will be enabled in the configuration. +# +# - [flatten] (Not yet implemented) +# Produce a flattened set of Configuration.h and Configuration_adv.h files with only the enabled +# #defines and no comments. A clean look, but context-free. +# +{sec_list} +{ini_fmt.format('ini_config_vers', vers)} +''' ) + + if extended_dump: + + # Loop through the sections + for skey in sorted(sections): + #print(f" skey: {skey}") + sani = re.sub(r'[- ]+', '_', skey).lower() + outfile.write(f"\n[config:{sani}]\n") + opts = sections[skey] + for name in sorted(opts): + val = opts[name]['value'] + if val == '': val = 'on' + #print(f" {name} = {val}") + outfile.write(ini_fmt.format(name.lower(), val) + '\n') + + else: + + # Standard export just dumps config:basic and config:advanced sections + for header in real_config: + outfile.write(f'\n[{filegrp[header]}]\n') + for name in sorted(real_config[header]): + if name not in ignore: + val = real_config[header][name]['value'] + if val == '': val = 'on' + outfile.write(ini_fmt.format(name.lower(), val) + '\n') # - # Produce a schema.json file if CONFIG_EXPORT == 3 + # CONFIG_EXPORT 3 = schema.json, 4 = schema.yml # if config_dump >= 3: try: @@ -207,7 +325,7 @@ def tryint(key): if conf_schema: # - # Produce a schema.json file if CONFIG_EXPORT == 3 + # 3 = schema.json # if config_dump in (3, 13): print("Generating schema.json ...") @@ -217,7 +335,7 @@ def tryint(key): schema.dump_json(conf_schema, build_path / 'schema_grouped.json') # - # Produce a schema.yml file if CONFIG_EXPORT == 4 + # 4 = schema.yml # elif config_dump == 4: print("Generating schema.yml ...") @@ -231,33 +349,58 @@ def tryint(key): import yaml schema.dump_yaml(conf_schema, build_path / 'schema.yml') - # 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 - # # Produce a JSON file for CONFIGURATION_EMBEDDING or CONFIG_EXPORT == 1 + # Skip if an identical JSON file was already present. # - if config_dump == 1 or 'CONFIGURATION_EMBEDDING' in defines: + if not same_hash and (config_dump == 1 or 'CONFIGURATION_EMBEDDING' in build_defines): with marlin_json.open('w') as outfile: - json.dump(data, outfile, separators=(',', ':')) + + json_data = {} + if extended_dump: + print("Extended dump ...") + for header in real_config: + confs = real_config[header] + json_data[header] = {} + for name in confs: + c = confs[name] + s = c['section'] + if s not in json_data[header]: json_data[header][s] = {} + json_data[header][s][name] = c['value'] + else: + for header in real_config: + conf = real_config[header] + #print(f"real_config[{header}]", conf) + for name in conf: + json_data[name] = conf[name]['value'] + + json_data['__INITIAL_HASH'] = hashes + + # Append the source code version and date + json_data['VERSION'] = { + 'DETAILED_BUILD_VERSION': cleaned_build_defines['DETAILED_BUILD_VERSION'], + 'STRING_DISTRIBUTION_DATE': cleaned_build_defines['STRING_DISTRIBUTION_DATE'] + } + try: + curver = subprocess.check_output(["git", "describe", "--match=NeVeRmAtCh", "--always"]).strip() + json_data['VERSION']['GIT_REF'] = curver.decode() + except: + pass + + json.dump(json_data, outfile, separators=(',', ':')) # # The rest only applies to CONFIGURATION_EMBEDDING # - if not 'CONFIGURATION_EMBEDDING' in defines: + if not 'CONFIGURATION_EMBEDDING' in build_defines: + (build_path / 'mc.zip').unlink(missing_ok=True) return # Compress the JSON file as much as we can - compress_file(marlin_json, 'marlin_config.json', marlin_zip) + if not same_hash: + compress_file(marlin_json, 'marlin_config.json', marlin_zip) - # Generate a C source file for storing this array + # Generate a C source file containing the entire ZIP file as an array with open('Marlin/src/mczip.h','wb') as result_file: result_file.write( b'#ifndef NO_CONFIGURATION_EMBEDDING_WARNING\n' @@ -269,8 +412,11 @@ def tryint(key): for b in (build_path / 'mc.zip').open('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') + if count % 16 == 0: result_file.write(b'\n ') + if count % 16: result_file.write(b'\n') result_file.write(b'};\n') + +if __name__ == "__main__": + # Build required. From command line just explain usage. + print("Use schema.py to export JSON and YAML from the command-line.") + print("Build Marlin with CONFIG_EXPORT 2 to export 'config.ini'.") diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_PRO_V1_F429/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_PRO_V1_F429/variant.h index b8e4b9667e80..b51da1bda575 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_PRO_V1_F429/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_PRO_V1_F429/variant.h @@ -27,118 +27,118 @@ extern "C" { * Pins *----------------------------------------------------------------------------*/ -#define PA0 0 //D0 -#define PA1 1 //D1 -#define PA2 2 //D2 -#define PA3 3 //D3 -#define PA4 4 //D4 -#define PA5 5 //D5 -#define PA6 6 //D6 -#define PA7 7 //D7 -#define PA8 8 //D8 -#define PA9 9 //D9 -#define PA10 10 //D10 -#define PA11 11 //D11 -#define PA12 12 //D12 -#define PA13 13 //D13 -#define PA14 14 //D14 -#define PA15 15 //D15 -#define PB0 16 //D16 -#define PB1 17 //D17 -#define PB2 18 //D18 -#define PB3 19 //D19 -#define PB4 20 //D20 -#define PB5 21 //D21 -#define PB6 22 //D22 -#define PB7 23 //D23 -#define PB8 24 //D24 -#define PB9 25 //D25 -#define PB10 26 //D26 -#define PB11 27 //D27 -#define PB12 28 //D28 -#define PB13 29 //D29 -#define PB14 30 //D30 -#define PB15 31 //D31 -#define PC0 32 //D32 -#define PC1 33 //D33 -#define PC2 34 //D34 -#define PC3 35 //D35 -#define PC4 36 //D36 -#define PC5 37 //D37 -#define PC6 38 //D38 -#define PC7 39 //D39 -#define PC8 40 //D40 -#define PC9 41 //D41 -#define PC10 42 //D42 -#define PC11 43 //D43 -#define PC12 44 //D44 -#define PC13 45 //D45 -#define PC14 46 //D46 -#define PC15 47 //D47 -#define PD0 48 //D48 -#define PD1 49 //D49 -#define PD2 50 //D50 -#define PD3 51 //D51 -#define PD4 52 //D52 -#define PD5 53 //D53 -#define PD6 54 //D54 -#define PD7 55 //D55 -#define PD8 56 //D56 -#define PD9 57 //D57 -#define PD10 58 //D58 -#define PD11 59 //D59 -#define PD12 60 //D60 -#define PD13 61 //D61 -#define PD14 62 //D62 -#define PD15 63 //D63 -#define PE0 64 //D64 -#define PE1 65 //D65 -#define PE2 66 //D66 -#define PE3 67 //D67 -#define PE4 68 //D68 -#define PE5 69 //D69 -#define PE6 70 //D70 -#define PE7 71 //D71 -#define PE8 72 //D72 -#define PE9 73 //D73 -#define PE10 74 //D74 -#define PE11 75 //D75 -#define PE12 76 //D76 -#define PE13 77 //D77 -#define PE14 78 //D78 -#define PE15 79 //D79 -#define PF0 80 //D64 -#define PF1 81 //D65 -#define PF2 82 //D66 -#define PF3 83 //D67 -#define PF4 84 //D68 -#define PF5 85 //D69 -#define PF6 86 //D70 -#define PF7 87 //D71 -#define PF8 88 //D72 -#define PF9 89 //D73 -#define PF10 90 //D74 -#define PF11 91 //D75 -#define PF12 92 //D76 -#define PF13 93 //D77 -#define PF14 94 //D78 -#define PF15 95 //D79 -#define PG0 96 //D64 -#define PG1 97 //D65 -#define PG2 98 //D66 -#define PG3 99 //D67 -#define PG4 100 //D68 -#define PG5 101 //D69 -#define PG6 102 //D70 -#define PG7 103 //D71 -#define PG8 104 //D72 -#define PG9 105 //D73 -#define PG10 106 //D74 -#define PG11 107 //D75 -#define PG12 108 //D76 -#define PG13 109 //D77 -#define PG14 110 //D78 -#define PG15 111 //D79 +#define PA0 0 +#define PA1 1 +#define PA2 2 +#define PA3 3 +#define PA4 4 +#define PA5 5 +#define PA6 6 +#define PA7 7 +#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 16 +#define PB1 17 +#define PB2 18 +#define PB3 19 +#define PB4 20 +#define PB5 21 +#define PB6 22 +#define PB7 23 +#define PB8 24 +#define PB9 25 +#define PB10 26 +#define PB11 27 +#define PB12 28 +#define PB13 29 +#define PB14 30 +#define PB15 31 +#define PC0 32 +#define PC1 33 +#define PC2 34 +#define PC3 35 +#define PC4 36 +#define PC5 37 +#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 PD7 55 +#define PD8 56 +#define PD9 57 +#define PD10 58 +#define PD11 59 +#define PD12 60 +#define PD13 61 +#define PD14 62 +#define PD15 63 +#define PE0 64 +#define PE1 65 +#define PE2 66 +#define PE3 67 +#define PE4 68 +#define PE5 69 +#define PE6 70 +#define PE7 71 +#define PE8 72 +#define PE9 73 +#define PE10 74 +#define PE11 75 +#define PE12 76 +#define PE13 77 +#define PE14 78 +#define PE15 79 +#define PF0 80 +#define PF1 81 +#define PF2 82 +#define PF3 83 +#define PF4 84 +#define PF5 85 +#define PF6 86 +#define PF7 87 +#define PF8 88 +#define PF9 89 +#define PF10 90 +#define PF11 91 +#define PF12 92 +#define PF13 93 +#define PF14 94 +#define PF15 95 +#define PG0 96 +#define PG1 97 +#define PG2 98 +#define PG3 99 +#define PG4 100 +#define PG5 101 +#define PG6 102 +#define PG7 103 +#define PG8 104 +#define PG9 105 +#define PG10 106 +#define PG11 107 +#define PG12 108 +#define PG13 109 +#define PG14 110 +#define PG15 111 // This must be a literal with the same value as PEND #define NUM_DIGITAL_PINS 112 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h index 22b919697027..b07e9d7f05e5 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h @@ -27,118 +27,118 @@ extern "C" { * Pins *----------------------------------------------------------------------------*/ -#define PA0 0 //D0 -#define PA1 1 //D1 -#define PA2 2 //D2 -#define PA3 3 //D3 -#define PA4 4 //D4 -#define PA5 5 //D5 -#define PA6 6 //D6 -#define PA7 7 //D7 -#define PA8 8 //D8 -#define PA9 9 //D9 -#define PA10 10 //D10 -#define PA11 11 //D11 -#define PA12 12 //D12 -#define PA13 13 //D13 -#define PA14 14 //D14 -#define PA15 15 //D15 -#define PB0 16 //D16 -#define PB1 17 //D17 -#define PB2 18 //D18 -#define PB3 19 //D19 -#define PB4 20 //D20 -#define PB5 21 //D21 -#define PB6 22 //D22 -#define PB7 23 //D23 -#define PB8 24 //D24 -#define PB9 25 //D25 -#define PB10 26 //D26 -#define PB11 27 //D27 -#define PB12 28 //D28 -#define PB13 29 //D29 -#define PB14 30 //D30 -#define PB15 31 //D31 -#define PC0 32 //D32 -#define PC1 33 //D33 -#define PC2 34 //D34 -#define PC3 35 //D35 -#define PC4 36 //D36 -#define PC5 37 //D37 -#define PC6 38 //D38 -#define PC7 39 //D39 -#define PC8 40 //D40 -#define PC9 41 //D41 -#define PC10 42 //D42 -#define PC11 43 //D43 -#define PC12 44 //D44 -#define PC13 45 //D45 -#define PC14 46 //D46 -#define PC15 47 //D47 -#define PD0 48 //D48 -#define PD1 49 //D49 -#define PD2 50 //D50 -#define PD3 51 //D51 -#define PD4 52 //D52 -#define PD5 53 //D53 -#define PD6 54 //D54 -#define PD7 55 //D55 -#define PD8 56 //D56 -#define PD9 57 //D57 -#define PD10 58 //D58 -#define PD11 59 //D59 -#define PD12 60 //D60 -#define PD13 61 //D61 -#define PD14 62 //D62 -#define PD15 63 //D63 -#define PE0 64 //D64 -#define PE1 65 //D65 -#define PE2 66 //D66 -#define PE3 67 //D67 -#define PE4 68 //D68 -#define PE5 69 //D69 -#define PE6 70 //D70 -#define PE7 71 //D71 -#define PE8 72 //D72 -#define PE9 73 //D73 -#define PE10 74 //D74 -#define PE11 75 //D75 -#define PE12 76 //D76 -#define PE13 77 //D77 -#define PE14 78 //D78 -#define PE15 79 //D79 -#define PF0 80 //D64 -#define PF1 81 //D65 -#define PF2 82 //D66 -#define PF3 83 //D67 -#define PF4 84 //D68 -#define PF5 85 //D69 -#define PF6 86 //D70 -#define PF7 87 //D71 -#define PF8 88 //D72 -#define PF9 89 //D73 -#define PF10 90 //D74 -#define PF11 91 //D75 -#define PF12 92 //D76 -#define PF13 93 //D77 -#define PF14 94 //D78 -#define PF15 95 //D79 -#define PG0 96 //D64 -#define PG1 97 //D65 -#define PG2 98 //D66 -#define PG3 99 //D67 -#define PG4 100 //D68 -#define PG5 101 //D69 -#define PG6 102 //D70 -#define PG7 103 //D71 -#define PG8 104 //D72 -#define PG9 105 //D73 -#define PG10 106 //D74 -#define PG11 107 //D75 -#define PG12 108 //D76 -#define PG13 109 //D77 -#define PG14 110 //D78 -#define PG15 111 //D79 +#define PA0 0 +#define PA1 1 +#define PA2 2 +#define PA3 3 +#define PA4 4 +#define PA5 5 +#define PA6 6 +#define PA7 7 +#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 16 +#define PB1 17 +#define PB2 18 +#define PB3 19 +#define PB4 20 +#define PB5 21 +#define PB6 22 +#define PB7 23 +#define PB8 24 +#define PB9 25 +#define PB10 26 +#define PB11 27 +#define PB12 28 +#define PB13 29 +#define PB14 30 +#define PB15 31 +#define PC0 32 +#define PC1 33 +#define PC2 34 +#define PC3 35 +#define PC4 36 +#define PC5 37 +#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 PD7 55 +#define PD8 56 +#define PD9 57 +#define PD10 58 +#define PD11 59 +#define PD12 60 +#define PD13 61 +#define PD14 62 +#define PD15 63 +#define PE0 64 +#define PE1 65 +#define PE2 66 +#define PE3 67 +#define PE4 68 +#define PE5 69 +#define PE6 70 +#define PE7 71 +#define PE8 72 +#define PE9 73 +#define PE10 74 +#define PE11 75 +#define PE12 76 +#define PE13 77 +#define PE14 78 +#define PE15 79 +#define PF0 80 +#define PF1 81 +#define PF2 82 +#define PF3 83 +#define PF4 84 +#define PF5 85 +#define PF6 86 +#define PF7 87 +#define PF8 88 +#define PF9 89 +#define PF10 90 +#define PF11 91 +#define PF12 92 +#define PF13 93 +#define PF14 94 +#define PF15 95 +#define PG0 96 +#define PG1 97 +#define PG2 98 +#define PG3 99 +#define PG4 100 +#define PG5 101 +#define PG6 102 +#define PG7 103 +#define PG8 104 +#define PG9 105 +#define PG10 106 +#define PG11 107 +#define PG12 108 +#define PG13 109 +#define PG14 110 +#define PG15 111 // This must be a literal with the same value as PEND #define NUM_DIGITAL_PINS 112 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/variant.h index 722a29d00dd4..9c5c2530225d 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RC/variant.h @@ -23,9 +23,8 @@ extern "C" { #endif // __cplusplus - -// | DIGITAL | ANALOG | USART | TWI | SPI | SPECIAL | -// |---------|--------|-----------|----------|------------------------|-----------| + // | DIGITAL | ANALOG | USART | TWI | SPI | SPECIAL | + // |---------|--------|-----------|----------|------------------------|-----------| #define PA0 0 // | 0 | A0 | | | | | #define PA1 1 // | 1 | A1 | | | | | #define PA2 2 // | 2 | A2 | USART2_TX | | | | @@ -42,7 +41,7 @@ extern "C" { #define PA13 13 // | 13 | | | | | SWD_SWDIO | #define PA14 14 // | 14 | | | | | SWD_SWCLK | #define PA15 15 // | 15 | | | | SPI3_SS, (SPI1_SS) | | -// |---------|--------|-----------|----------|------------------------|-----------| + // |---------|--------|-----------|----------|------------------------|-----------| #define PB0 16 // | 16 | A8 | | | | | #define PB1 17 // | 17 | A9 | | | | | #define PB2 18 // | 18 | | | | | BOOT1 | @@ -58,7 +57,7 @@ extern "C" { #define PB13 28 // | 28 | | | | SPI2_SCK | | #define PB14 29 // | 29 | | | | SPI2_MISO | | #define PB15 30 // | 30 | | | | SPI2_MOSI | | -// |---------|--------|-----------|----------|------------------------|-----------| + // |---------|--------|-----------|----------|------------------------|-----------| #define PC0 31 // | 31 | A10 | | | | | #define PC1 32 // | 32 | A11 | | | | | #define PC2 33 // | 33 | A12 | | | SPI2_MISO | | @@ -75,12 +74,12 @@ extern "C" { #define PC13 44 // | 44 | | | | | | #define PC14 45 // | 45 | | | | | OSC32_IN | #define PC15 46 // | 46 | | | | | OSC32_OUT | -// |---------|--------|-----------|----------|------------------------|-----------| + // |---------|--------|-----------|----------|------------------------|-----------| #define PD2 47 // | 47 | | | | | | -// |---------|--------|-----------|----------|------------------------|-----------| + // |---------|--------|-----------|----------|------------------------|-----------| #define PH0 48 // | 48 | | | | | OSC_IN | #define PH1 49 // | 49 | | | | | OSC_OUT | -// |---------|--------|-----------|----------|------------------------|-----------| + // |---------|--------|-----------|----------|------------------------|-----------| // This must be a literal #define NUM_DIGITAL_PINS 50 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/PeripheralPins.c new file mode 100644 index 000000000000..418ef5aa7abc --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/PeripheralPins.c @@ -0,0 +1,252 @@ +/* + ******************************************************************************* + * Copyright (c) 2019, STMicroelectronics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************* + * Automatically generated from STM32F401R[(B-C)|(D-E)]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} +}; + +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} +}; + +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} +}; + +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} +}; + +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} +}; + +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} +}; + +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} +}; + +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[] = { +#ifndef ARDUINO_CoreBoard_F401RC + {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 +#endif + {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_CREALITY_STM32F401RE/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/PinNamesVar.h new file mode 100644 index 000000000000..f5db451e6f19 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/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_CREALITY_STM32F401RE/hal_conf_custom.h b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/hal_conf_custom.h new file mode 100644 index 000000000000..1dd047bb9005 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/hal_conf_custom.h @@ -0,0 +1,495 @@ +/** + ****************************************************************************** + * @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_CRC_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_IWDG_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +#define HAL_RTC_MODULE_ENABLED +#define HAL_SPI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_PCD_MODULE_ENABLED // Automatically added if any type of USB is enabled, as in Arduino IDE. (STM32 v3.10700.191028) + +//#define HAL_CAN_MODULE_ENABLED +//#define HAL_CAN_LEGACY_MODULE_ENABLED +//#define HAL_CEC_MODULE_ENABLED +//#define HAL_CRYP_MODULE_ENABLED +//#define HAL_DAC_MODULE_ENABLED +//#define HAL_DCMI_MODULE_ENABLED +//#define HAL_DMA2D_MODULE_ENABLED +//#define HAL_ETH_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_EXTI_MODULE_ENABLED +//#define HAL_SMBUS_MODULE_ENABLED +//#define HAL_I2S_MODULE_ENABLED +//#define HAL_LTDC_MODULE_ENABLED +//#define HAL_DSI_MODULE_ENABLED +//#define HAL_QSPI_MODULE_ENABLED +//#define HAL_RNG_MODULE_ENABLED +//#define HAL_SAI_MODULE_ENABLED +#define HAL_SD_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_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_CREALITY_STM32F401RE/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/ldscript.ld new file mode 100644 index 000000000000..881b72167ef1 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/ldscript.ld @@ -0,0 +1,186 @@ +/* +***************************************************************************** +** +** 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 +{ +FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET +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); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text ALIGN(4): + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.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(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} \ No newline at end of file diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/variant.cpp new file mode 100644 index 000000000000..d603ad6ef1ab --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/variant.cpp @@ -0,0 +1,238 @@ +/* + 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 + +// Digital PinName array +const PinName digitalPin[] = { + PA_0, // Digital pin 0 + PA_1, // Digital pin 1 + PA_2, // Digital pin 2 + PA_3, // Digital pin 3 + PA_4, // Digital pin 4 + PA_5, // Digital pin 5 + PA_6, // Digital pin 6 + PA_7, // Digital pin 7 + PA_8, // Digital pin 8 + PA_9, // Digital pin 9 + PA_10, // Digital pin 10 + PA_11, // Digital pin 11 + PA_12, // Digital pin 12 + PA_13, // Digital pin 13 + PA_14, // Digital pin 14 + PA_15, // Digital pin 15 + + PB_0, // Digital pin 16 + PB_1, // Digital pin 17 + PB_2, // Digital pin 18 + PB_3, // Digital pin 19 + PB_4, // Digital pin 20 + PB_5, // Digital pin 21 + PB_6, // Digital pin 22 + PB_7, // Digital pin 23 + PB_8, // Digital pin 24 + PB_9, // Digital pin 25 + PB_10, // Digital pin 26 + PB_12, // Digital pin 27 + PB_13, // Digital pin 28 + PB_14, // Digital pin 29 + PB_15, // Digital pin 30 + + PC_0, // Digital pin 31 + PC_1, // Digital pin 32 + PC_2, // Digital pin 33 + PC_3, // Digital pin 34 + PC_4, // Digital pin 35 + PC_5, // Digital pin 36 + PC_6, // Digital pin 37 + PC_7, // Digital pin 38 + PC_8, // Digital pin 39 + PC_9, // Digital pin 40 + PC_10, // Digital pin 41 + PC_11, // Digital pin 42 + PC_12, // Digital pin 43 + PC_13, // Digital pin 44 + PC_14, // Digital pin 45 + PC_15, // Digital pin 46 + + PD_2, // Digital pin 47 + + PH_0, // Digital pin 48, used by the external oscillator + PH_1 // Digital pin 49, used by the external oscillator +}; + +// 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 + 31, // A10, PC0 + 32, // A11, PC1 + 33, // A12, PC2 + 34, // A13, PC3 + 35, // A14, PC4 + 36 // A15, PC5 +}; + +#ifdef __cplusplus +} +#endif + +// ---------------------------------------------------------------------------- + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * @brief Configures the System clock source, PLL Multiplier and Divider factors, + * AHB/APBx prescalers and Flash settings + * @note This function should be called only once the RCC clock configuration + * is reset to the default reset state (done in SystemInit() function). + * @param None + * @retval None + */ + +/******************************************************************************/ +/* PLL (clocked by HSE) used as System clock source */ +/******************************************************************************/ +static uint8_t SetSysClock_PLL_HSE(uint8_t bypass) +{ + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_ClkInitTypeDef RCC_ClkInitStruct; + + /* 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_RCC_PWR_CLK_ENABLE(); + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2); + + // Enable HSE oscillator and activate PLL with HSE as source + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + if (bypass == 0) { + RCC_OscInitStruct.HSEState = RCC_HSE_ON; // External 8 MHz xtal on OSC_IN/OSC_OUT + } else { + RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; // External 8 MHz clock on OSC_IN + } + + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE / 1000000L; // Expects an 8 MHz external clock by default. Redefine HSE_VALUE if not + RCC_OscInitStruct.PLL.PLLN = 336; // VCO output clock = 336 MHz (1 MHz * 336) + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; // PLLCLK = 84 MHz (336 MHz / 4) + RCC_OscInitStruct.PLL.PLLQ = 7; // USB clock = 48 MHz (336 MHz / 7) --> OK for USB + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + return 0; // FAIL + } + + // 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; // 84 MHz + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; // 84 MHz + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; // 42 MHz + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; // 84 MHz + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) { + return 0; // FAIL + } + + /* Output clock on MCO1 pin(PA8) for debugging purpose */ + /* + if (bypass == 0) + HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_2); // 4 MHz + else + HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_1); // 8 MHz + */ + + return 1; // OK +} + +/******************************************************************************/ +/* PLL (clocked by HSI) used as System clock source */ +/******************************************************************************/ +uint8_t SetSysClock_PLL_HSI(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_ClkInitTypeDef RCC_ClkInitStruct; + + /* 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_RCC_PWR_CLK_ENABLE(); + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2); + + // Enable HSI oscillator and activate PLL with HSI as source + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSIState = RCC_HSI_ON; + RCC_OscInitStruct.HSEState = RCC_HSE_OFF; + RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI; + RCC_OscInitStruct.PLL.PLLM = 16; // VCO input clock = 1 MHz (16 MHz / 16) + RCC_OscInitStruct.PLL.PLLN = 336; // VCO output clock = 336 MHz (1 MHz * 336) + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; // PLLCLK = 84 MHz (336 MHz / 4) + RCC_OscInitStruct.PLL.PLLQ = 7; // USB clock = 48 MHz (336 MHz / 7) --> freq is ok but not precise enough + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + return 0; // FAIL + } + + /* 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; // 84 MHz + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; // 84 MHz + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; // 42 MHz + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; // 84 MHz + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) { + return 0; // FAIL + } + + /* Output clock on MCO1 pin(PA8) for debugging purpose */ + //HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSI, RCC_MCODIV_1); // 16 MHz + + return 1; // OK +} + +WEAK void SystemClock_Config(void) +{ + /* 1- If fail try to start with HSE and external xtal */ + if (SetSysClock_PLL_HSE(0) == 0) { + /* 2- Try to start with HSE and external clock */ + if (SetSysClock_PLL_HSE(1) == 0) { + /* 3- If fail start with HSI clock */ + if (SetSysClock_PLL_HSI() == 0) { + Error_Handler(); + } + } + } + /* Output clock on MCO2 pin(PC9) for debugging purpose */ + //HAL_RCC_MCOConfig(RCC_MCO2, RCC_MCO2SOURCE_SYSCLK, RCC_MCODIV_4); +} + +#ifdef __cplusplus +} +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/variant.h new file mode 100644 index 000000000000..dc73ccc51868 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_CREALITY_STM32F401RE/variant.h @@ -0,0 +1,150 @@ +/* + 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 + + // | DIGITAL | ANALOG | USART | TWI | SPI | SPECIAL | + // |---------|--------|-----------|----------|------------------------|-----------| +#define PA0 0 // | 0 | A0 | | | | | +#define PA1 1 // | 1 | A1 | | | | | +#define PA2 2 // | 2 | A2 | USART2_TX | | | | +#define PA3 3 // | 3 | A3 | USART2_RX | | | | +#define PA4 4 // | 4 | A4 | | | SPI1_SS, (SPI3_SS) | | +#define PA5 5 // | 5 | A5 | | | SPI1_SCK | | +#define PA6 6 // | 6 | A6 | | | SPI1_MISO | | +#define PA7 7 // | 7 | A7 | | | SPI1_MOSI | | +#define PA8 8 // | 8 | | | TWI3_SCL | | | +#define PA9 9 // | 9 | | USART1_TX | | | | +#define PA10 10 // | 10 | | USART1_RX | | | | +#define PA11 11 // | 11 | | USART6_TX | | | | +#define PA12 12 // | 12 | | USART6_RX | | | | +#define PA13 13 // | 13 | | | | | SWD_SWDIO | +#define PA14 14 // | 14 | | | | | SWD_SWCLK | +#define PA15 15 // | 15 | | | | SPI3_SS, (SPI1_SS) | | + // |---------|--------|-----------|----------|------------------------|-----------| +#define PB0 16 // | 16 | A8 | | | | | +#define PB1 17 // | 17 | A9 | | | | | +#define PB2 18 // | 18 | | | | | BOOT1 | +#define PB3 19 // | 19 | | | TWI2_SDA | SPI3_SCK, (SPI1_SCK) | | +#define PB4 20 // | 20 | | | TWI3_SDA | SPI3_MISO, (SPI1_MISO) | | +#define PB5 21 // | 21 | | | | SPI3_MOSI, (SPI1_MOSI) | | +#define PB6 22 // | 22 | | USART1_TX | TWI1_SCL | | | +#define PB7 23 // | 23 | | USART1_RX | TWI1_SDA | | | +#define PB8 24 // | 24 | | | TWI1_SCL | | | +#define PB9 25 // | 25 | | | TWI1_SDA | SPI2_SS | | +#define PB10 26 // | 26 | | | TWI2_SCL | SPI2_SCK | | +#define PB12 27 // | 27 | | | | SPI2_SS | | +#define PB13 28 // | 28 | | | | SPI2_SCK | | +#define PB14 29 // | 29 | | | | SPI2_MISO | | +#define PB15 30 // | 30 | | | | SPI2_MOSI | | + // |---------|--------|-----------|----------|------------------------|-----------| +#define PC0 31 // | 31 | A10 | | | | | +#define PC1 32 // | 32 | A11 | | | | | +#define PC2 33 // | 33 | A12 | | | SPI2_MISO | | +#define PC3 34 // | 34 | A13 | | | SPI2_MOSI | | +#define PC4 35 // | 35 | A14 | | | | | +#define PC5 36 // | 36 | A15 | | | | | +#define PC6 37 // | 37 | | USART6_TX | | | | +#define PC7 38 // | 38 | | USART6_RX | | | | +#define PC8 39 // | 39 | | | | | | +#define PC9 40 // | 40 | | | TWI3_SDA | | | +#define PC10 41 // | 41 | | | | SPI3_SCK | | +#define PC11 42 // | 42 | | | | SPI3_MISO | | +#define PC12 43 // | 43 | | | | SPI3_MOSI | | +#define PC13 44 // | 44 | | | | | | +#define PC14 45 // | 45 | | | | | OSC32_IN | +#define PC15 46 // | 46 | | | | | OSC32_OUT | + // |---------|--------|-----------|----------|------------------------|-----------| +#define PD2 47 // | 47 | | | | | | + // |---------|--------|-----------|----------|------------------------|-----------| +#define PH0 48 // | 48 | | | | | OSC_IN | +#define PH1 49 // | 49 | | | | | OSC_OUT | + // |---------|--------|-----------|----------|------------------------|-----------| + +// This must be a literal +#define NUM_DIGITAL_PINS 50 +#define NUM_ANALOG_INPUTS 16 + +// SPI definitions +#define PIN_SPI_SS PA4 +#define PIN_SPI_SS1 PA4 +#define PIN_SPI_MOSI PA7 +#define PIN_SPI_MISO PA6 +#define PIN_SPI_SCK PA5 + + +// Timer Definitions +#define TIMER_TONE TIM2 +#define TIMER_SERVO TIM11 +#define TIMER_SERIAL TIM5 + +// UART Definitions +//#define ENABLE_HWSERIAL1 done automatically by the #define SERIAL_UART_INSTANCE below +#define ENABLE_HWSERIAL2 + + +// Define here Serial instance number to map on Serial generic name (if not already used by SerialUSB) +#define SERIAL_UART_INSTANCE 1 //1 for Serial = Serial1 (USART1) + +// Default pin used for 'Serial' instance +// Mandatory for Firmata +#define PIN_SERIAL_RX PA10 +#define PIN_SERIAL_TX PA9 + +// Used when user instanciate a hardware Serial using its peripheral name. +// Example: HardwareSerial mySerial(USART3); +// will use PIN_SERIAL3_RX and PIN_SERIAL3_TX if defined. +#define PIN_SERIAL1_RX PA10 +#define PIN_SERIAL1_TX PA9 +#define PIN_SERIAL2_RX PA3 +#define PIN_SERIAL2_TX PA2 + +#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 Serial1 + #define SERIAL_PORT_HARDWARE_OPEN Serial2 +#endif + +#endif /* _VARIANT_ARDUINO_STM32_ */ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PeripheralPins.c old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PinNamesVar.h index d9e759f5d0cd..d9076b4dfb59 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PinNamesVar.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/PinNamesVar.h @@ -27,4 +27,4 @@ #ifdef USBCON USB_DM = PA_11, USB_DP = PA_12, -#endif \ No newline at end of file +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h index 4a0245e7e9d5..7452020652c4 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h @@ -26,8 +26,8 @@ extern "C" { // * = F103R8-B-C-D-E-F-G // ** = F103RC-D-E-F-G -// | DIGITAL | ANALOG | USART | TWI | SPI | SPECIAL | -// |---------|----------------|--------------------------|-----------|-----------------------|-----------| +// | DIGITAL | ANALOG | USART | TWI | SPI | SPECIAL | +// |---------|----------------|--------------------------|-----------|-----------------------|-----------| #define PA0 PIN_A0 // | 0 | A0 | | | | | #define PA1 PIN_A1 // | 1 | A1 | | | | | #define PA2 PIN_A2 // | 2 | A2 | USART2_TX | | | | @@ -36,53 +36,53 @@ extern "C" { #define PA5 PIN_A5 // | 5 | A5 | | | SPI1_SCK | | #define PA6 PIN_A6 // | 6 | A6 | | | SPI1_MISO | | #define PA7 PIN_A7 // | 7 | A7 | | | SPI1_MOSI | | -#define PA8 8 // | 8 | | | | | | -#define PA9 9 // | 9 | | USART1_TX | | | | -#define PA10 10 // | 10 | | USART1_RX | | | | -#define PA11 11 // | 11 | | | | | USB_DM | -#define PA12 12 // | 12 | | | | | USB_DP | -#define PA13 13 // | 13 | | | | | SWD_SWDIO | -#define PA14 14 // | 14 | | | | | SWD_SWCLK | -#define PA15 15 // | 15 | | | | SPI1_SS/SPI3_SS** | | -// |---------|----------------|--------------------------|-----------|-----------------------|-----------| +#define PA8 8 // | 8 | | | | | | +#define PA9 9 // | 9 | | USART1_TX | | | | +#define PA10 10 // | 10 | | USART1_RX | | | | +#define PA11 11 // | 11 | | | | | USB_DM | +#define PA12 12 // | 12 | | | | | USB_DP | +#define PA13 13 // | 13 | | | | | SWD_SWDIO | +#define PA14 14 // | 14 | | | | | SWD_SWCLK | +#define PA15 15 // | 15 | | | | SPI1_SS/SPI3_SS** | | +// |---------|----------------|--------------------------|-----------|-----------------------|-----------| #define PB0 PIN_A8 // | 16 | A8 | | | | | #define PB1 PIN_A9 // | 17 | A9 | | | | | -#define PB2 18 // | 18 | | | | | BOOT1 | -#define PB3 19 // | 19 | | | | SPI1_SCK/SPI3_SCK** | | -#define PB4 20 // | 20 | | | | SPI1_MISO/SPI3_MISO** | | -#define PB5 21 // | 21 | | | | SPI1_MOSI/SPI3_MOSI** | | -#define PB6 22 // | 22 | | USART1_TX | TWI1_SCL | | | -#define PB7 23 // | 23 | | USART1_RX | TWI1_SDA | | | -#define PB8 24 // | 24 | | | TWI1_SCL | | | -#define PB9 25 // | 25 | | | TWI1_SDA | | | -#define PB10 26 // | 26 | | USART3_TX* | TWI2_SCL* | | | -#define PB11 27 // | 27 | | USART3_RX* | TWI2_SDA* | | | -#define PB12 28 // | 28 | | | | SPI2_SS* | | -#define PB13 29 // | 29 | | | | SPI2_SCK* | | -#define PB14 30 // | 30 | | | | SPI2_MISO* | | -#define PB15 31 // | 31 | | | | SPI2_MOSI* | | -// |---------|----------------|--------------------------|-----------|-----------------------|-----------| +#define PB2 18 // | 18 | | | | | BOOT1 | +#define PB3 19 // | 19 | | | | SPI1_SCK/SPI3_SCK** | | +#define PB4 20 // | 20 | | | | SPI1_MISO/SPI3_MISO** | | +#define PB5 21 // | 21 | | | | SPI1_MOSI/SPI3_MOSI** | | +#define PB6 22 // | 22 | | USART1_TX | TWI1_SCL | | | +#define PB7 23 // | 23 | | USART1_RX | TWI1_SDA | | | +#define PB8 24 // | 24 | | | TWI1_SCL | | | +#define PB9 25 // | 25 | | | TWI1_SDA | | | +#define PB10 26 // | 26 | | USART3_TX* | TWI2_SCL* | | | +#define PB11 27 // | 27 | | USART3_RX* | TWI2_SDA* | | | +#define PB12 28 // | 28 | | | | SPI2_SS* | | +#define PB13 29 // | 29 | | | | SPI2_SCK* | | +#define PB14 30 // | 30 | | | | SPI2_MISO* | | +#define PB15 31 // | 31 | | | | SPI2_MOSI* | | +// |---------|----------------|--------------------------|-----------|-----------------------|-----------| #define PC0 PIN_A10 // | 32 | A10 | | | | | #define PC1 PIN_A11 // | 33 | A11 | | | | | #define PC2 PIN_A12 // | 34 | A12 | | | | | #define PC3 PIN_A13 // | 35 | A13 | | | | | #define PC4 PIN_A14 // | 36 | A14 | | | | | #define PC5 PIN_A15 // | 37 | A15 | | | | | -#define PC6 38 // | 38 | | | | | | -#define PC7 39 // | 39 | | | | | | -#define PC8 40 // | 40 | | | | | | -#define PC9 41 // | 41 | | | | | | -#define PC10 42 // | 42 | | USART3_TX*/UART4_TX** | | | | -#define PC11 43 // | 43 | | USART3_RX*/UART4_RX** | | | | -#define PC12 44 // | 44 | | UART5_TX** | | | | -#define PC13 45 // | 45 | | | | | | -#define PC14 46 // | 46 | | | | | OSC32_IN | -#define PC15 47 // | 47 | | | | | OSC32_OUT | -// |---------|----------------|--------------------------|-----------|-----------------------|-----------| -#define PD0 48 // | 48 | | | | | OSC_IN | -#define PD1 49 // | 48 | | | | | OSC_OUT | -#define PD2 50 // | 50 | | UART5_RX** | | | | -// |---------|----------------|--------------------------|-----------|-----------------------|-----------| +#define PC6 38 // | 38 | | | | | | +#define PC7 39 // | 39 | | | | | | +#define PC8 40 // | 40 | | | | | | +#define PC9 41 // | 41 | | | | | | +#define PC10 42 // | 42 | | USART3_TX*/UART4_TX** | | | | +#define PC11 43 // | 43 | | USART3_RX*/UART4_RX** | | | | +#define PC12 44 // | 44 | | UART5_TX** | | | | +#define PC13 45 // | 45 | | | | | | +#define PC14 46 // | 46 | | | | | OSC32_IN | +#define PC15 47 // | 47 | | | | | OSC32_OUT | +// |---------|----------------|--------------------------|-----------|-----------------------|-----------| +#define PD0 48 // | 48 | | | | | OSC_IN | +#define PD1 49 // | 48 | | | | | OSC_OUT | +#define PD2 50 // | 50 | | UART5_RX** | | | | +// |---------|----------------|--------------------------|-----------|-----------------------|-----------| // This must be a literal #define NUM_DIGITAL_PINS 51 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/PeripheralPins.c index d0905853a9a9..de796f4ef535 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/PeripheralPins.c @@ -413,7 +413,7 @@ const PinMap PinMap_USB_OTG_HS[] = { */ {NC, NP, 0} }; - +#endif #ifdef HAL_SD_MODULE_ENABLED WEAK const PinMap PinMap_SD[] = { @@ -430,4 +430,3 @@ WEAK const PinMap PinMap_SD[] = { {NC, NP, 0} }; #endif -#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/variant.h index b8e4b9667e80..b51da1bda575 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F407ZE/variant.h @@ -27,118 +27,118 @@ extern "C" { * Pins *----------------------------------------------------------------------------*/ -#define PA0 0 //D0 -#define PA1 1 //D1 -#define PA2 2 //D2 -#define PA3 3 //D3 -#define PA4 4 //D4 -#define PA5 5 //D5 -#define PA6 6 //D6 -#define PA7 7 //D7 -#define PA8 8 //D8 -#define PA9 9 //D9 -#define PA10 10 //D10 -#define PA11 11 //D11 -#define PA12 12 //D12 -#define PA13 13 //D13 -#define PA14 14 //D14 -#define PA15 15 //D15 -#define PB0 16 //D16 -#define PB1 17 //D17 -#define PB2 18 //D18 -#define PB3 19 //D19 -#define PB4 20 //D20 -#define PB5 21 //D21 -#define PB6 22 //D22 -#define PB7 23 //D23 -#define PB8 24 //D24 -#define PB9 25 //D25 -#define PB10 26 //D26 -#define PB11 27 //D27 -#define PB12 28 //D28 -#define PB13 29 //D29 -#define PB14 30 //D30 -#define PB15 31 //D31 -#define PC0 32 //D32 -#define PC1 33 //D33 -#define PC2 34 //D34 -#define PC3 35 //D35 -#define PC4 36 //D36 -#define PC5 37 //D37 -#define PC6 38 //D38 -#define PC7 39 //D39 -#define PC8 40 //D40 -#define PC9 41 //D41 -#define PC10 42 //D42 -#define PC11 43 //D43 -#define PC12 44 //D44 -#define PC13 45 //D45 -#define PC14 46 //D46 -#define PC15 47 //D47 -#define PD0 48 //D48 -#define PD1 49 //D49 -#define PD2 50 //D50 -#define PD3 51 //D51 -#define PD4 52 //D52 -#define PD5 53 //D53 -#define PD6 54 //D54 -#define PD7 55 //D55 -#define PD8 56 //D56 -#define PD9 57 //D57 -#define PD10 58 //D58 -#define PD11 59 //D59 -#define PD12 60 //D60 -#define PD13 61 //D61 -#define PD14 62 //D62 -#define PD15 63 //D63 -#define PE0 64 //D64 -#define PE1 65 //D65 -#define PE2 66 //D66 -#define PE3 67 //D67 -#define PE4 68 //D68 -#define PE5 69 //D69 -#define PE6 70 //D70 -#define PE7 71 //D71 -#define PE8 72 //D72 -#define PE9 73 //D73 -#define PE10 74 //D74 -#define PE11 75 //D75 -#define PE12 76 //D76 -#define PE13 77 //D77 -#define PE14 78 //D78 -#define PE15 79 //D79 -#define PF0 80 //D64 -#define PF1 81 //D65 -#define PF2 82 //D66 -#define PF3 83 //D67 -#define PF4 84 //D68 -#define PF5 85 //D69 -#define PF6 86 //D70 -#define PF7 87 //D71 -#define PF8 88 //D72 -#define PF9 89 //D73 -#define PF10 90 //D74 -#define PF11 91 //D75 -#define PF12 92 //D76 -#define PF13 93 //D77 -#define PF14 94 //D78 -#define PF15 95 //D79 -#define PG0 96 //D64 -#define PG1 97 //D65 -#define PG2 98 //D66 -#define PG3 99 //D67 -#define PG4 100 //D68 -#define PG5 101 //D69 -#define PG6 102 //D70 -#define PG7 103 //D71 -#define PG8 104 //D72 -#define PG9 105 //D73 -#define PG10 106 //D74 -#define PG11 107 //D75 -#define PG12 108 //D76 -#define PG13 109 //D77 -#define PG14 110 //D78 -#define PG15 111 //D79 +#define PA0 0 +#define PA1 1 +#define PA2 2 +#define PA3 3 +#define PA4 4 +#define PA5 5 +#define PA6 6 +#define PA7 7 +#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 16 +#define PB1 17 +#define PB2 18 +#define PB3 19 +#define PB4 20 +#define PB5 21 +#define PB6 22 +#define PB7 23 +#define PB8 24 +#define PB9 25 +#define PB10 26 +#define PB11 27 +#define PB12 28 +#define PB13 29 +#define PB14 30 +#define PB15 31 +#define PC0 32 +#define PC1 33 +#define PC2 34 +#define PC3 35 +#define PC4 36 +#define PC5 37 +#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 PD7 55 +#define PD8 56 +#define PD9 57 +#define PD10 58 +#define PD11 59 +#define PD12 60 +#define PD13 61 +#define PD14 62 +#define PD15 63 +#define PE0 64 +#define PE1 65 +#define PE2 66 +#define PE3 67 +#define PE4 68 +#define PE5 69 +#define PE6 70 +#define PE7 71 +#define PE8 72 +#define PE9 73 +#define PE10 74 +#define PE11 75 +#define PE12 76 +#define PE13 77 +#define PE14 78 +#define PE15 79 +#define PF0 80 +#define PF1 81 +#define PF2 82 +#define PF3 83 +#define PF4 84 +#define PF5 85 +#define PF6 86 +#define PF7 87 +#define PF8 88 +#define PF9 89 +#define PF10 90 +#define PF11 91 +#define PF12 92 +#define PF13 93 +#define PF14 94 +#define PF15 95 +#define PG0 96 +#define PG1 97 +#define PG2 98 +#define PG3 99 +#define PG4 100 +#define PG5 101 +#define PG6 102 +#define PG7 103 +#define PG8 104 +#define PG9 105 +#define PG10 106 +#define PG11 107 +#define PG12 108 +#define PG13 109 +#define PG14 110 +#define PG15 111 // This must be a literal with the same value as PEND #define NUM_DIGITAL_PINS 112 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/variant.h index ca3664daa165..c629be7359bb 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_CHEETAH_V20/variant.h @@ -23,9 +23,8 @@ extern "C" { #endif // __cplusplus - -// | DIGITAL | ANALOG | USART | TWI | SPI | SPECIAL | -// |---------|--------|-----------|----------|------------------------|-----------| + // | DIGITAL | ANALOG | USART | TWI | SPI | SPECIAL | + // |---------|--------|-----------|----------|------------------------|-----------| #define PA0 A0 // | 0 | A0 | | | | | #define PA1 A1 // | 1 | A1 | | | | | #define PA2 A2 // | 2 | A2 | USART2_TX | | | | @@ -42,7 +41,7 @@ extern "C" { #define PA13 13 // | 13 | | | | | SWD_SWDIO | #define PA14 14 // | 14 | | | | | SWD_SWCLK | #define PA15 15 // | 15 | | | | SPI3_SS, (SPI1_SS) | | -// |---------|--------|-----------|----------|------------------------|-----------| + // |---------|--------|-----------|----------|------------------------|-----------| #define PB0 A8 // | 16 | A8 | | | | | #define PB1 A9 // | 17 | A9 | | | | | #define PB2 18 // | 18 | | | | | BOOT1 | @@ -58,7 +57,7 @@ extern "C" { #define PB13 28 // | 28 | | | | SPI2_SCK | | #define PB14 29 // | 29 | | | | SPI2_MISO | | #define PB15 30 // | 30 | | | | SPI2_MOSI | | -// |---------|--------|-----------|----------|------------------------|-----------| + // |---------|--------|-----------|----------|------------------------|-----------| #define PC0 A10 // | 31 | A10 | | | | | #define PC1 A11 // | 32 | A11 | | | | | #define PC2 A12 // | 33 | A12 | | | SPI2_MISO | | @@ -75,12 +74,12 @@ extern "C" { #define PC13 44 // | 44 | | | | | | #define PC14 45 // | 45 | | | | | OSC32_IN | #define PC15 46 // | 46 | | | | | OSC32_OUT | -// |---------|--------|-----------|----------|------------------------|-----------| + // |---------|--------|-----------|----------|------------------------|-----------| #define PD2 47 // | 47 | | | | | | -// |---------|--------|-----------|----------|------------------------|-----------| + // |---------|--------|-----------|----------|------------------------|-----------| #define PH0 48 // | 48 | | | | | OSC_IN | #define PH1 49 // | 49 | | | | | OSC_OUT | -// |---------|--------|-----------|----------|------------------------|-----------| + // |---------|--------|-----------|----------|------------------------|-----------| // This must be a literal #define NUM_DIGITAL_PINS 50 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/variant.h index 4f77dc688f35..f64bbacc4566 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_S6/variant.h @@ -27,86 +27,86 @@ extern "C" { * Pins *----------------------------------------------------------------------------*/ -#define PA0 0 //D0 -#define PA1 1 //D1 -#define PA2 2 //D2 -#define PA3 3 //D3 -#define PA4 4 //D4 -#define PA5 5 //D5 -#define PA6 6 //D6 -#define PA7 7 //D7 -#define PA8 8 //D8 -#define PA9 9 //D9 -#define PA10 10 //D10 -#define PA11 11 //D11 -#define PA12 12 //D12 -#define PA13 13 //D13 -#define PA14 14 //D14 -#define PA15 15 //D15 -#define PB0 16 //D16 -#define PB1 17 //D17 -#define PB2 18 //D18 -#define PB3 19 //D19 -#define PB4 20 //D20 -#define PB5 21 //D21 -#define PB6 22 //D22 -#define PB7 23 //D23 -#define PB8 24 //D24 -#define PB9 25 //D25 -#define PB10 26 //D26 -#define PB11 27 //D27 -#define PB12 28 //D28 -#define PB13 29 //D29 -#define PB14 30 //D30 -#define PB15 31 //D31 -#define PC0 32 //D32 -#define PC1 33 //D33 -#define PC2 34 //D34 -#define PC3 35 //D35 -#define PC4 36 //D36 -#define PC5 37 //D37 -#define PC6 38 //D38 -#define PC7 39 //D39 -#define PC8 40 //D40 -#define PC9 41 //D41 -#define PC10 42 //D42 -#define PC11 43 //D43 -#define PC12 44 //D44 -#define PC13 45 //D45 -#define PC14 46 //D46 -#define PC15 47 //D47 -#define PD0 48 //D48 -#define PD1 49 //D49 -#define PD2 50 //D50 -#define PD3 51 //D51 -#define PD4 52 //D52 -#define PD5 53 //D53 -#define PD6 54 //D54 -#define PD7 55 //D55 -#define PD8 56 //D56 -#define PD9 57 //D57 -#define PD10 58 //D58 -#define PD11 59 //D59 -#define PD12 60 //D60 -#define PD13 61 //D61 -#define PD14 62 //D62 -#define PD15 63 //D63 -#define PE0 64 //D64 -#define PE1 65 //D65 -#define PE2 66 //D66 -#define PE3 67 //D67 -#define PE4 68 //D68 -#define PE5 69 //D69 -#define PE6 70 //D70 -#define PE7 71 //D71 -#define PE8 72 //D72 -#define PE9 73 //D73 -#define PE10 74 //D74 -#define PE11 75 //D75 -#define PE12 76 //D76 -#define PE13 77 //D77 -#define PE14 78 //D78 -#define PE15 79 //D79 +#define PA0 0 +#define PA1 1 +#define PA2 2 +#define PA3 3 +#define PA4 4 +#define PA5 5 +#define PA6 6 +#define PA7 7 +#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 16 +#define PB1 17 +#define PB2 18 +#define PB3 19 +#define PB4 20 +#define PB5 21 +#define PB6 22 +#define PB7 23 +#define PB8 24 +#define PB9 25 +#define PB10 26 +#define PB11 27 +#define PB12 28 +#define PB13 29 +#define PB14 30 +#define PB15 31 +#define PC0 32 +#define PC1 33 +#define PC2 34 +#define PC3 35 +#define PC4 36 +#define PC5 37 +#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 PD7 55 +#define PD8 56 +#define PD9 57 +#define PD10 58 +#define PD11 59 +#define PD12 60 +#define PD13 61 +#define PD14 62 +#define PD15 63 +#define PE0 64 +#define PE1 65 +#define PE2 66 +#define PE3 67 +#define PE4 68 +#define PE5 69 +#define PE6 70 +#define PE7 71 +#define PE8 72 +#define PE9 73 +#define PE10 74 +#define PE11 75 +#define PE12 76 +#define PE13 77 +#define PE14 78 +#define PE15 79 // This must be a literal with the same value as PEND #define NUM_DIGITAL_PINS 87 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/PeripheralPins.c index 4411065d21d8..f8ec8381467f 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_FYSETC_SPIDER_KING407/PeripheralPins.c @@ -191,7 +191,7 @@ WEAK const PinMap PinMap_PWM[] = { {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 FAN2_PIN //{PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 //{PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 - {PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N FAN_PIN + {PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N FAN0_PIN {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 FAN1_PIN {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N HEATER_BED_PIN //{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Vx/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/PeripheralPins.c similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Vx/PeripheralPins.c rename to buildroot/share/PlatformIO/variants/MARLIN_H723VG/PeripheralPins.c diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Vx/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/PinNamesVar.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Vx/PinNamesVar.h rename to buildroot/share/PlatformIO/variants/MARLIN_H723VG/PinNamesVar.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Vx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/ldscript.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Vx/ldscript.ld rename to buildroot/share/PlatformIO/variants/MARLIN_H723VG/ldscript.ld diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Vx/variant_MARLIN_STM32H723VX.cpp b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Vx/variant_MARLIN_STM32H723VX.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.cpp diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Vx/variant_MARLIN_STM32H723VX.h b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.h similarity index 99% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Vx/variant_MARLIN_STM32H723VX.h rename to buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.h index 8b67905680a9..c3e5c78ec51f 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_H723Vx/variant_MARLIN_STM32H723VX.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.h @@ -161,6 +161,7 @@ #define NUM_DIGITAL_PINS 82 #define NUM_DUALPAD_PINS 2 #define NUM_ANALOG_INPUTS 16 +#define NUM_ANALOG_FIRST PA0 // On-board LED pin number #ifndef LED_BUILTIN diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Zx/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_H723ZE/PeripheralPins.c similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Zx/PeripheralPins.c rename to buildroot/share/PlatformIO/variants/MARLIN_H723ZE/PeripheralPins.c diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Zx/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_H723ZE/PinNamesVar.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Zx/PinNamesVar.h rename to buildroot/share/PlatformIO/variants/MARLIN_H723ZE/PinNamesVar.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Zx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_H723ZE/ldscript.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Zx/ldscript.ld rename to buildroot/share/PlatformIO/variants/MARLIN_H723ZE/ldscript.ld diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Zx/variant_MARLIN_STM32H723ZX.cpp b/buildroot/share/PlatformIO/variants/MARLIN_H723ZE/variant_MARLIN_STM32H723ZE.cpp similarity index 98% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Zx/variant_MARLIN_STM32H723ZX.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_H723ZE/variant_MARLIN_STM32H723ZE.cpp index 4506cf5ce6b5..a99a3cb609aa 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_H723Zx/variant_MARLIN_STM32H723ZX.cpp +++ b/buildroot/share/PlatformIO/variants/MARLIN_H723ZE/variant_MARLIN_STM32H723ZE.cpp @@ -128,7 +128,9 @@ const PinName digitalPin[] = { PH_0, // D110 PH_1, // D111 PC_2_C, // D112/A26 - PC_3_C // D113/A27 + PC_3_C, // D113/A27 + PC_2, // D114/A28 + PC_3 // D115/A29 }; // Analog (Ax) pin number array @@ -160,7 +162,9 @@ const uint32_t analogInputPin[] = { 91, // A24, PF13 92, // A25, PF14 112, // A26, PC2_C - 113 // A27, PC3_C + 113, // A27, PC3_C + 114, // A28, PC2 + 115 // A29, PC3 }; void MPU_Config(void) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Zx/variant_MARLIN_STM32H723ZX.h b/buildroot/share/PlatformIO/variants/MARLIN_H723ZE/variant_MARLIN_STM32H723ZE.h similarity index 98% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Zx/variant_MARLIN_STM32H723ZX.h rename to buildroot/share/PlatformIO/variants/MARLIN_H723ZE/variant_MARLIN_STM32H723ZE.h index d443f5c1fd3d..c9c631412a04 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_H723Zx/variant_MARLIN_STM32H723ZX.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_H723ZE/variant_MARLIN_STM32H723ZE.h @@ -129,6 +129,8 @@ #define PH1 111 #define PC2_C PIN_A26 #define PC3_C PIN_A27 +#define PC2 PC2_C +#define PC3 PC3_C // Alternate pins number #define PA0_ALT1 (PA0 | ALT1) @@ -197,9 +199,10 @@ #define PF9_ALT2 (PF9 | ALT2) #define PG13_ALT1 (PG13 | ALT1) -#define NUM_DIGITAL_PINS 114 +#define NUM_DIGITAL_PINS 116 #define NUM_DUALPAD_PINS 2 -#define NUM_ANALOG_INPUTS 28 +#define NUM_ANALOG_INPUTS 30 +#define NUM_ANALOG_FIRST PA0 // On-board LED pin number #ifndef LED_BUILTIN diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_H743VI/PeripheralPins.c similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H743Vx/PeripheralPins.c rename to buildroot/share/PlatformIO/variants/MARLIN_H743VI/PeripheralPins.c diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_H743VI/PinNamesVar.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H743Vx/PinNamesVar.h rename to buildroot/share/PlatformIO/variants/MARLIN_H743VI/PinNamesVar.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_H743VI/ldscript.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H743Vx/ldscript.ld rename to buildroot/share/PlatformIO/variants/MARLIN_H743VI/ldscript.ld diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/variant_MARLIN_STM32H743VX.cpp b/buildroot/share/PlatformIO/variants/MARLIN_H743VI/variant_MARLIN_STM32H743VI.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H743Vx/variant_MARLIN_STM32H743VX.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_H743VI/variant_MARLIN_STM32H743VI.cpp diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/variant_MARLIN_STM32H743VX.h b/buildroot/share/PlatformIO/variants/MARLIN_H743VI/variant_MARLIN_STM32H743VI.h similarity index 99% rename from buildroot/share/PlatformIO/variants/MARLIN_H743Vx/variant_MARLIN_STM32H743VX.h rename to buildroot/share/PlatformIO/variants/MARLIN_H743VI/variant_MARLIN_STM32H743VI.h index c4635c4b1f64..5c0492ac3a62 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_H743Vx/variant_MARLIN_STM32H743VX.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_H743VI/variant_MARLIN_STM32H743VI.h @@ -160,6 +160,7 @@ #define NUM_DIGITAL_PINS 82 #define NUM_DUALPAD_PINS 2 #define NUM_ANALOG_INPUTS 16 +#define NUM_ANALOG_FIRST PA0 // On-board LED pin number #ifndef LED_BUILTIN diff --git a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_V2/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_V2/PeripheralPins.c index 03d75bbfa823..edefd00f7ab0 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_V2/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_V2/PeripheralPins.c @@ -161,7 +161,7 @@ WEAK const PinMap PinMap_PWM[] = { //{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N //{PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 - //{PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N LCD_PINS_ENABLE + //{PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N LCD_PINS_EN //{PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N //{PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2 @@ -292,7 +292,7 @@ WEAK const PinMap PinMap_USB_OTG_HS[] = { //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID CS (LCD) //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS LCD_PINS_D4 //{PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM MISO (LCD) - //{PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP LCD_PINS_ENABLE + //{PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP LCD_PINS_EN #else //{PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 Z_STEP //{PA_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_CK SPI-SCK diff --git a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_V2/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_V2/variant.h index 5232a1eaf2e4..3b4d43054ddf 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_V2/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_V2/variant.h @@ -27,8 +27,8 @@ extern "C" { * Pins (STM32F405RG and STM32F415RG) *----------------------------------------------------------------------------*/ -// | DIGITAL | ANALOG IN | ANALOG OUT | UART/USART | TWI | SPI | SPECIAL | -// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +// | DIGITAL | ANALOG IN | ANALOG OUT | UART/USART | TWI | SPI | SPECIAL | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| #define PA0 PIN_A0 // | 0 | A0 (ADC1) | | UART4_TX | | | | #define PA1 PIN_A1 // | 1 | A1 (ADC1) | | UART4_RX | | | | #define PA2 PIN_A2 // | 2 | A2 (ADC1) | | USART2_TX | | | | @@ -37,54 +37,54 @@ extern "C" { #define PA5 PIN_A5 // | 5 | A5 (ADC1) | DAC_OUT2 | | | SPI1_SCK | | #define PA6 PIN_A6 // | 6 | A6 (ADC1) | | | | SPI1_MISO | | #define PA7 PIN_A7 // | 7 | A7 (ADC1) | | | | SPI1_MOSI | | -#define PA8 8 // | 8 | | | | TWI3_SCL | | | -#define PA9 9 // | 9 | | | USART1_TX | | SPI2_SCK | | -#define PA10 10 // | 10 | | | USART1_RX | | | | -#define PA11 11 // | 11 | | | | | | | -#define PA12 12 // | 12 | | | | | | | -#define PA13 13 // | 13 | | | | | | SWD_SWDIO | -#define PA14 14 // | 14 | | | | | | SWD_SWCLK | -#define PA15 15 // | 15 | | | | | SPI3_SS, (SPI1_SS) | | -// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +#define PA8 8 // | 8 | | | | TWI3_SCL | | | +#define PA9 9 // | 9 | | | USART1_TX | | SPI2_SCK | | +#define PA10 10 // | 10 | | | USART1_RX | | | | +#define PA11 11 // | 11 | | | | | | | +#define PA12 12 // | 12 | | | | | | | +#define PA13 13 // | 13 | | | | | | SWD_SWDIO | +#define PA14 14 // | 14 | | | | | | SWD_SWCLK | +#define PA15 15 // | 15 | | | | | SPI3_SS, (SPI1_SS) | | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| #define PB0 PIN_A8 // | 16 | A8 (ADC1) | | | | | | #define PB1 PIN_A9 // | 17 | A9 (ADC1) | | | | | | -#define PB2 18 // | 18 | | | | | | BOOT1 | -#define PB3 19 // | 19 | | | | | SPI3_SCK, (SPI1_SCK) | | -#define PB4 20 // | 20 | | | | | SPI3_MISO, (SPI1_MISO) | | -#define PB5 21 // | 21 | | | | | SPI3_MOSI, (SPI1_MOSI) | | -#define PB6 22 // | 22 | | | USART1_TX | TWI1_SCL | | | -#define PB7 23 // | 23 | | | USART1_RX | TWI1_SDA | | | -#define PB8 24 // | 24 | | | | TWI1_SCL | | | -#define PB9 25 // | 25 | | | | TWI1_SDA | SPI2_SS | | -#define PB10 26 // | 26 | | | USART3_TX | TWI2_SCL | SPI2_SCK | | -#define PB11 27 // | 27 | | | USART3_RX | TWI2_SDA | | | -#define PB12 28 // | 28 | | | | | SPI2_SS | | -#define PB13 29 // | 29 | | | | | SPI2_SCK | | -#define PB14 30 // | 30 | | | | | SPI2_MISO | | -#define PB15 31 // | 31 | | | | | SPI2_MOSI | | -// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +#define PB2 18 // | 18 | | | | | | BOOT1 | +#define PB3 19 // | 19 | | | | | SPI3_SCK, (SPI1_SCK) | | +#define PB4 20 // | 20 | | | | | SPI3_MISO, (SPI1_MISO) | | +#define PB5 21 // | 21 | | | | | SPI3_MOSI, (SPI1_MOSI) | | +#define PB6 22 // | 22 | | | USART1_TX | TWI1_SCL | | | +#define PB7 23 // | 23 | | | USART1_RX | TWI1_SDA | | | +#define PB8 24 // | 24 | | | | TWI1_SCL | | | +#define PB9 25 // | 25 | | | | TWI1_SDA | SPI2_SS | | +#define PB10 26 // | 26 | | | USART3_TX | TWI2_SCL | SPI2_SCK | | +#define PB11 27 // | 27 | | | USART3_RX | TWI2_SDA | | | +#define PB12 28 // | 28 | | | | | SPI2_SS | | +#define PB13 29 // | 29 | | | | | SPI2_SCK | | +#define PB14 30 // | 30 | | | | | SPI2_MISO | | +#define PB15 31 // | 31 | | | | | SPI2_MOSI | | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| #define PC0 PIN_A10 // | 32 | A10 (ADC1) | | | | | | #define PC1 PIN_A11 // | 33 | A11 (ADC1) | | | | | | #define PC2 PIN_A12 // | 34 | A12 (ADC1) | | | | SPI2_MISO | | #define PC3 PIN_A13 // | 35 | A13 (ADC1) | | | | SPI2_MOSI | | #define PC4 PIN_A14 // | 36 | A14 (ADC1) | | | | | | #define PC5 PIN_A15 // | 37 | A15 (ADC1) | | | | | | -#define PC6 38 // | 38 | | | USART6_TX | | | | -#define PC7 39 // | 39 | | | USART3_RX | | SPI2_SCK | | -#define PC8 40 // | 40 | | | | | | | -#define PC9 41 // | 41 | | | | TWI3_SDA | | | -#define PC10 42 // | 42 | | | USART3_TX, (UART4_TX) | | SPI3_SCK | | -#define PC11 43 // | 43 | | | USART3_RX, (UART4_RX) | | SPI3_MISO | | -#define PC12 44 // | 44 | | | UART5_TX | | SPI3_MOSI | | -#define PC13 45 // | 45 | | | | | | | -#define PC14 46 // | 46 | | | | | | OSC32_IN | -#define PC15 47 // | 47 | | | | | | OSC32_OUT | -// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| -#define PD2 48 // | 48 | | | UART5_RX | | | | -// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| -#define PH0 49 // | 49 | | | | | | OSC_IN | -#define PH1 50 // | 50 | | | | | | OSC_OUT | -// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +#define PC6 38 // | 38 | | | USART6_TX | | | | +#define PC7 39 // | 39 | | | USART3_RX | | SPI2_SCK | | +#define PC8 40 // | 40 | | | | | | | +#define PC9 41 // | 41 | | | | TWI3_SDA | | | +#define PC10 42 // | 42 | | | USART3_TX, (UART4_TX) | | SPI3_SCK | | +#define PC11 43 // | 43 | | | USART3_RX, (UART4_RX) | | SPI3_MISO | | +#define PC12 44 // | 44 | | | UART5_TX | | SPI3_MOSI | | +#define PC13 45 // | 45 | | | | | | | +#define PC14 46 // | 46 | | | | | | OSC32_IN | +#define PC15 47 // | 47 | | | | | | OSC32_OUT | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +#define PD2 48 // | 48 | | | UART5_RX | | | | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| +#define PH0 49 // | 49 | | | | | | OSC_IN | +#define PH1 50 // | 50 | | | | | | OSC_OUT | +// |---------|------------|------------|-----------------------|----------------------|-----------------------------------|-----------| /// This must be a literal #define NUM_DIGITAL_PINS 51 diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/board/board.h b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/board/board.h index 80261d30274d..863c8041c9c2 100644 --- a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/board/board.h +++ b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/board/board.h @@ -100,12 +100,12 @@ /* * SDIO Pins */ -#define BOARD_SDIO_D0 PC8 -#define BOARD_SDIO_D1 PC9 -#define BOARD_SDIO_D2 PC10 -#define BOARD_SDIO_D3 PC11 -#define BOARD_SDIO_CLK PC12 -#define BOARD_SDIO_CMD PD2 +#define BOARD_SDIO_D0 PC8 +#define BOARD_SDIO_D1 PC9 +#define BOARD_SDIO_D2 PC10 +#define BOARD_SDIO_D3 PC11 +#define BOARD_SDIO_CLK PC12 +#define BOARD_SDIO_CMD PD2 /* Pin aliases: these give the GPIO port/bit for each pin as an * enum. These are optional, but recommended. They make it easier to @@ -119,117 +119,5 @@ PE0,PE1,PE2,PE3,PE4,PE5,PE6,PE7,PE8,PE9,PE10,PE11,PE12,PE13,PE14,PE15, PF0,PF1,PF2,PF3,PF4,PF5,PF6,PF7,PF8,PF9,PF10,PF11,PF12,PF13,PF14,PF15, PG0,PG1,PG2,PG3,PG4,PG5,PG6,PG7,PG8,PG9,PG10,PG11,PG12,PG13,PG14,PG15 };/* Note PB2 is skipped as this is Boot1 and is not going to be much use as its likely to be pulled permanently low */ -/* -#define PA0 0 -#define PA1 1 -#define PA2 2 -#define PA3 3 -#define PA4 4 -#define PA5 5 -#define PA6 6 -#define PA7 7 -#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 16 -#define PB1 17 -#define PB2 18 -#define PB3 19 -#define PB4 20 -#define PB5 21 -#define PB6 22 -#define PB7 23 -#define PB8 24 -#define PB9 25 -#define PB10 26 -#define PB11 27 -#define PB12 28 -#define PB13 29 -#define PB14 30 -#define PB15 31 -#define PC0 32 -#define PC1 33 -#define PC2 34 -#define PC3 35 -#define PC4 36 -#define PC5 37 -#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 PD7 55 -#define PD8 56 -#define PD9 57 -#define PD10 58 -#define PD11 59 -#define PD12 60 -#define PD13 61 -#define PD14 62 -#define PD15 63 -#define PE0 64 -#define PE1 65 -#define PE2 66 -#define PE3 67 -#define PE4 68 -#define PE5 69 -#define PE6 70 -#define PE7 71 -#define PE8 72 -#define PE9 73 -#define PE10 74 -#define PE11 75 -#define PE12 76 -#define PE13 77 -#define PE14 78 -#define PE15 79 -#define PF0 80 -#define PF1 81 -#define PF2 82 -#define PF3 83 -#define PF4 84 -#define PF5 85 -#define PF6 86 -#define PF7 87 -#define PF8 88 -#define PF9 89 -#define PF10 90 -#define PF11 91 -#define PF12 92 -#define PF13 93 -#define PF14 94 -#define PF15 95 -#define PG0 96 -#define PG1 97 -#define PG2 98 -#define PG3 99 -#define PG4 100 -#define PG5 101 -#define PG6 102 -#define PG7 103 -#define PG8 104 -#define PG9 105 -#define PG10 106 -#define PG11 107 -#define PG12 108 -#define PG13 109 -#define PG14 110 -#define PG15 111 */ -#endif + +#endif // _BOARDS_GENERIC_STM32F103Z_H_ diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/board/board.h b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/board/board.h index 6ffa2447460d..24458fe79ab2 100644 --- a/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/board/board.h +++ b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/board/board.h @@ -100,12 +100,12 @@ /* * SDIO Pins */ -#define BOARD_SDIO_D0 PC8 -#define BOARD_SDIO_D1 PC9 -#define BOARD_SDIO_D2 PC10 -#define BOARD_SDIO_D3 PC11 -#define BOARD_SDIO_CLK PC12 -#define BOARD_SDIO_CMD PD2 +#define BOARD_SDIO_D0 PC8 +#define BOARD_SDIO_D1 PC9 +#define BOARD_SDIO_D2 PC10 +#define BOARD_SDIO_D3 PC11 +#define BOARD_SDIO_CLK PC12 +#define BOARD_SDIO_CMD PD2 /* Pin aliases: these give the GPIO port/bit for each pin as an * enum. These are optional, but recommended. They make it easier to diff --git a/buildroot/share/cmake/CMakeLists.txt b/buildroot/share/cmake/CMakeLists.txt index 1ed9091e01d6..09b5b6f1bff1 100644 --- a/buildroot/share/cmake/CMakeLists.txt +++ b/buildroot/share/cmake/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.8) +cmake_minimum_required(VERSION 3.5) #====================================================================# # Usage under Linux: # # # @@ -24,21 +24,67 @@ set(SCRIPT_BRANCH 1.0.2) #Set to wanted marlin-cmake release tag or branch if(NOT EXISTS ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake) - file(DOWNLOAD https://github.com/tohara/marlin-cmake/archive/${SCRIPT_BRANCH}.tar.gz - ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake-src.tar.gz SHOW_PROGRESS) + file(DOWNLOAD https://github.com/tohara/marlin-cmake/archive/${SCRIPT_BRANCH}.tar.gz + ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake-src.tar.gz SHOW_PROGRESS) - execute_process(COMMAND ${CMAKE_COMMAND} -E tar -xvf ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake-src.tar.gz WORKING_DIRECTORY ${CMAKE_CURRENT_LIST_DIR}) + execute_process(COMMAND ${CMAKE_COMMAND} -E tar -xvf ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake-src.tar.gz WORKING_DIRECTORY ${CMAKE_CURRENT_LIST_DIR}) - file(RENAME ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake-${SCRIPT_BRANCH} ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake) - file(REMOVE ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake-src.tar.gz) + file(RENAME ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake-${SCRIPT_BRANCH} ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake) + file(REMOVE ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake-src.tar.gz) +endif() + +if(NOT EXISTS ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/modules/Arduino_SDK.cmake) + file(DOWNLOAD https://raw.githubusercontent.com/tohara/marlin-cmake/master/modules/Arduino_SDK.cmake + ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/modules/Arduino_SDK.cmake SHOW_PROGRESS) +endif() + +if(NOT EXISTS ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/modules/marlin_cmake_functions.cmake) + file(DOWNLOAD https://raw.githubusercontent.com/tohara/marlin-cmake/master/modules/marlin_cmake_functions.cmake + ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/modules/marlin_cmake_functions.cmake SHOW_PROGRESS) +endif() + +if(NOT EXISTS ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/Platform/Arduino.cmake) + file(DOWNLOAD https://raw.githubusercontent.com/tohara/marlin-cmake/master/Platform/Arduino.cmake + ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/Platform/Arduino.cmake SHOW_PROGRESS) +endif() +if(NOT EXISTS ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/settings/marlin_boards.txt) + file(DOWNLOAD https://raw.githubusercontent.com/tohara/marlin-cmake/master/settings/marlin_boards.txt + ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/settings/marlin_boards.txt SHOW_PROGRESS) endif() -if(WIN32 AND NOT EXISTS ${CMAKE_BINARY_DIR}/make.exe) - file(COPY ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/resources/make.exe DESTINATION ${CMAKE_BINARY_DIR}/) +if(NOT EXISTS ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/toolchain/ArduinoToolchain.cmake) + file(DOWNLOAD https://raw.githubusercontent.com/tohara/marlin-cmake/master/toolchain/ArduinoToolchain.cmake + ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/toolchain/ArduinoToolchain.cmake SHOW_PROGRESS) endif() +if(WIN32) + if(NOT EXISTS ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/resources/make.exe) + file(DOWNLOAD https://raw.githubusercontent.com/tohara/marlin-cmake/master/resources/make.exe + ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/resources/make.exe SHOW_PROGRESS) + endif() +endif(WIN32) + +if(NOT EXISTS ${CMAKE_CURRENT_LIST_DIR}/arduino-1.8.19) + + file(DOWNLOAD https://downloads.arduino.cc/arduino-1.8.19-windows.zip + ${CMAKE_CURRENT_LIST_DIR}/arduino-1.8.19-windows.zip SHOW_PROGRESS) + + execute_process(COMMAND ${CMAKE_COMMAND} -E tar -xvzf ${CMAKE_CURRENT_LIST_DIR}/arduino-1.8.19-windows.zip WORKING_DIRECTORY ${CMAKE_CURRENT_LIST_DIR}) + + file(REMOVE ${CMAKE_CURRENT_LIST_DIR}/arduino-1.8.19-windows.zip) + +endif() + +# Print CMake version +message("-- Running CMake version: " ${CMAKE_VERSION}) + +# Replace the CMake Ver. in the Arduino.cmake +file(READ "${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/Platform/Arduino.cmake" ORIGINAL_FILE_CONTENTS) +string(REGEX REPLACE "cmake_minimum_required\\(VERSION[^\n]*\n" "cmake_minimum_required(VERSION 3.5)\n" NEW_FILE_CONTENTS "${ORIGINAL_FILE_CONTENTS}") +file(WRITE "${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/Platform/Arduino.cmake" "${NEW_FILE_CONTENTS}") + set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/modules) #====================================================================# @@ -46,9 +92,10 @@ set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}/marlin-cma # It can also be set from command line. eg.: # # cmake .. -DARDUINO_SDK_PATH="/path/to/arduino-1.x.x" # #====================================================================# -#set(ARDUINO_SDK_PATH ${CMAKE_CURRENT_LIST_DIR}/arduino-1.6.8) +set(ARDUINO_SDK_PATH ${CMAKE_CURRENT_LIST_DIR}/arduino-1.8.19) #set(ARDUINO_SDK_PATH /Applications/Arduino.app/Contents/Java) #set(ARDUINO_SDK_PATH $HOME/ArduinoAddons/Arduino_1.6.x) + #====================================================================# # Set included cmake files # #====================================================================# @@ -62,6 +109,19 @@ set(CMAKE_TOOLCHAIN_FILE ${CMAKE_CURRENT_LIST_DIR}/marlin-cmake/toolchain/Arduin #====================================================================# # Setup Project # +# # +# If you receive this error: # +# 'Unknown CMake command "_cmake_record_install_prefix".' # +# # +# Go to the file in your CMake directory. # +# # +# For Windows: cmake\Modules\Platform\WindowsPaths.cmake # +# For Linux: cmake/Modules/Platform/UnixPaths.cmake # +# # +# Comment out "_cmake_record_install_prefix()" # +# - OR - # +# Add "include(CMakeSystemSpecificInformation)" above the line. # +# # #====================================================================# project(Marlin C CXX) @@ -79,7 +139,6 @@ project(Marlin C CXX) print_board_list() print_programmer_list() - #====================================================================# # Get motherboard settings from Configuration.h # # setup_motherboard(TARGET Marlin_src_folder) # @@ -105,9 +164,9 @@ set(${PROJECT_NAME}_SRCS "${SOURCES};../../../Marlin/Marlin.ino") # cmake .. -DUPLOAD_PORT=/dev/ttyACM0 # #====================================================================# if(UPLOAD_PORT) - set(${PROJECT_NAME}_PORT ${UPLOAD_PORT}) + set(${PROJECT_NAME}_PORT ${UPLOAD_PORT}) else() - set(${PROJECT_NAME}_PORT /dev/ttyACM0) + set(${PROJECT_NAME}_PORT /dev/ttyACM0) endif() #====================================================================# diff --git a/buildroot/share/dwin/bin/DWIN_ICO.py b/buildroot/share/dwin/bin/DWIN_ICO.py index 3ddc734022ee..436a98701de0 100644 --- a/buildroot/share/dwin/bin/DWIN_ICO.py +++ b/buildroot/share/dwin/bin/DWIN_ICO.py @@ -113,8 +113,7 @@ def _splitEntryData(self, infile, outDir): # Seek file position, read length bytes, and write to new output file. print('%02d: offset: 0x%06x len: 0x%04x width: %d height: %d' % (count, entry.offset, entry.length, entry.width, entry.height)) - outfilename = os.path.join(outDir, - '%03d-%s.jpg' % (count, _iconNames[count])) + outfilename = os.path.join(outDir, '%03d-ICON_%s.jpg' % (count, _iconNames7[count])) with open(outfilename, 'wb') as outfile: infile.seek(entry.offset) blob = infile.read(entry.length) @@ -246,97 +245,97 @@ def serialize(self): 0, 0, 0, 0, 0) return rawdata -_iconNames = { - 0 : 'ICON_LOGO', - 1 : 'ICON_Print_0', - 2 : 'ICON_Print_1', - 3 : 'ICON_Prepare_0', - 4 : 'ICON_Prepare_1', - 5 : 'ICON_Control_0', - 6 : 'ICON_Control_1', - 7 : 'ICON_Leveling_0', - 8 : 'ICON_Leveling_1', - 9 : 'ICON_HotendTemp', - 10 : 'ICON_BedTemp', - 11 : 'ICON_Speed', - 12 : 'ICON_Zoffset', - 13 : 'ICON_Back', - 14 : 'ICON_File', - 15 : 'ICON_PrintTime', - 16 : 'ICON_RemainTime', - 17 : 'ICON_Setup_0', - 18 : 'ICON_Setup_1', - 19 : 'ICON_Pause_0', - 20 : 'ICON_Pause_1', - 21 : 'ICON_Continue_0', - 22 : 'ICON_Continue_1', - 23 : 'ICON_Stop_0', - 24 : 'ICON_Stop_1', - 25 : 'ICON_Bar', - 26 : 'ICON_More', - 27 : 'ICON_Axis', - 28 : 'ICON_CloseMotor', - 29 : 'ICON_Homing', - 30 : 'ICON_SetHome', - 31 : 'ICON_PLAPreheat', - 32 : 'ICON_ABSPreheat', - 33 : 'ICON_Cool', - 34 : 'ICON_Language', - 35 : 'ICON_MoveX', - 36 : 'ICON_MoveY', - 37 : 'ICON_MoveZ', - 38 : 'ICON_Extruder', - # no 39 - 40 : 'ICON_Temperature', - 41 : 'ICON_Motion', - 42 : 'ICON_WriteEEPROM', - 43 : 'ICON_ReadEEPROM', - 44 : 'ICON_ResumeEEPROM', - 45 : 'ICON_Info', - 46 : 'ICON_SetEndTemp', - 47 : 'ICON_SetBedTemp', - 48 : 'ICON_FanSpeed', - 49 : 'ICON_SetPLAPreheat', - 50 : 'ICON_SetABSPreheat', - 51 : 'ICON_MaxSpeed', - 52 : 'ICON_MaxAccelerated', - 53 : 'ICON_MaxJerk', - 54 : 'ICON_Step', - 55 : 'ICON_PrintSize', - 56 : 'ICON_Version', - 57 : 'ICON_Contact', - 58 : 'ICON_StockConfiguraton', - 59 : 'ICON_MaxSpeedX', - 60 : 'ICON_MaxSpeedY', - 61 : 'ICON_MaxSpeedZ', - 62 : 'ICON_MaxSpeedE', - 63 : 'ICON_MaxAccX', - 64 : 'ICON_MaxAccY', - 65 : 'ICON_MaxAccZ', - 66 : 'ICON_MaxAccE', - 67 : 'ICON_MaxSpeedJerkX', - 68 : 'ICON_MaxSpeedJerkY', - 69 : 'ICON_MaxSpeedJerkZ', - 70 : 'ICON_MaxSpeedJerkE', - 71 : 'ICON_StepX', - 72 : 'ICON_StepY', - 73 : 'ICON_StepZ', - 74 : 'ICON_StepE', - 75 : 'ICON_Setspeed', - 76 : 'ICON_SetZOffset', - 77 : 'ICON_Rectangle', - 78 : 'ICON_BLTouch', - 79 : 'ICON_TempTooLow', - 80 : 'ICON_AutoLeveling', - 81 : 'ICON_TempTooHigh', - 82 : 'ICON_NoTips_C', - 83 : 'ICON_NoTips_E', - 84 : 'ICON_Continue_C', - 85 : 'ICON_Continue_E', - 86 : 'ICON_Cancel_C', - 87 : 'ICON_Cancel_E', - 88 : 'ICON_Confirm_C', - 89 : 'ICON_Confirm_E', - 90 : 'ICON_Info_0', - 91 : 'ICON_Info_1' - } +_iconNames7 = { + 0 : "LOGO_Creality", + 1 : "Print_0", + 2 : "Print_1", + 3 : "Prepare_0", + 4 : "Prepare_1", + 5 : "Control_0", + 6 : "Control_1", + 7 : "Leveling_0", + 8 : "Leveling_1", + 9 : "HotendTemp", + 10 : "BedTemp", + 11 : "Speed", + 12 : "Zoffset", + 13 : "Back", + 14 : "File", + 15 : "PrintTime", + 16 : "RemainTime", + 17 : "Setup_0", + 18 : "Setup_1", + 19 : "Pause_0", + 20 : "Pause_1", + 21 : "Continue_0", + 22 : "Continue_1", + 23 : "Stop_0", + 24 : "Stop_1", + 25 : "Bar", + 26 : "More", + 27 : "Axis", + 28 : "CloseMotor", + 29 : "Homing", + 30 : "SetHome", + 31 : "PLAPreheat", + 32 : "ABSPreheat", + 33 : "Cool", + 34 : "Language", + 35 : "MoveX", + 36 : "MoveY", + 37 : "MoveZ", + 38 : "Extruder", + # Skip 39 + 40 : "Temperature", + 41 : "Motion", + 42 : "WriteEEPROM", + 43 : "ReadEEPROM", + 44 : "ResetEEPROM", + 45 : "Info", + 46 : "SetEndTemp", + 47 : "SetBedTemp", + 48 : "FanSpeed", + 49 : "SetPLAPreheat", + 50 : "SetABSPreheat", + 51 : "MaxSpeed", + 52 : "MaxAccelerated", + 53 : "MaxJerk", + 54 : "Step", + 55 : "PrintSize", + 56 : "Version", + 57 : "Contact", + 58 : "StockConfiguraton", + 59 : "MaxSpeedX", + 60 : "MaxSpeedY", + 61 : "MaxSpeedZ", + 62 : "MaxSpeedE", + 63 : "MaxAccX", + 64 : "MaxAccY", + 65 : "MaxAccZ", + 66 : "MaxAccE", + 67 : "MaxSpeedJerkX", + 68 : "MaxSpeedJerkY", + 69 : "MaxSpeedJerkZ", + 70 : "MaxSpeedJerkE", + 71 : "StepX", + 72 : "StepY", + 73 : "StepZ", + 74 : "StepE", + 75 : "Setspeed", + 76 : "SetZOffset", + 77 : "Rectangle", + 78 : "BLTouch", + 79 : "TempTooLow", + 80 : "AutoLeveling", + 81 : "TempTooHigh", + 82 : "NoTips_C", + 83 : "NoTips_E", + 84 : "Continue_C", + 85 : "Continue_E", + 86 : "Cancel_C", + 87 : "Cancel_E", + 88 : "Confirm_C", + 89 : "Confirm_E", + 90 : "Info_0", + 91 : "Info_1" +} diff --git a/buildroot/share/dwin/icons-2/000-ICON_BootLogo.jpg b/buildroot/share/dwin/icons-3/000-ICON_BootLogo.jpg similarity index 100% rename from buildroot/share/dwin/icons-2/000-ICON_BootLogo.jpg rename to buildroot/share/dwin/icons-3/000-ICON_BootLogo.jpg diff --git a/buildroot/share/dwin/icons-2/001-ICON_OpenSourceFirmware.jpg b/buildroot/share/dwin/icons-3/001-ICON_OpenSourceFirmware.jpg similarity index 100% rename from buildroot/share/dwin/icons-2/001-ICON_OpenSourceFirmware.jpg rename to buildroot/share/dwin/icons-3/001-ICON_OpenSourceFirmware.jpg diff --git a/buildroot/share/dwin/icons-2/002-ICON_GitHub.jpg b/buildroot/share/dwin/icons-3/002-ICON_GitHub.jpg similarity index 100% rename from buildroot/share/dwin/icons-2/002-ICON_GitHub.jpg rename to buildroot/share/dwin/icons-3/002-ICON_GitHub.jpg diff --git a/buildroot/share/dwin/icons-2/003-ICON_Website.jpg b/buildroot/share/dwin/icons-3/003-ICON_Website.jpg similarity index 100% rename from buildroot/share/dwin/icons-2/003-ICON_Website.jpg rename to buildroot/share/dwin/icons-3/003-ICON_Website.jpg diff --git a/buildroot/share/dwin/icons-2/004-ICON_Copyright.jpg b/buildroot/share/dwin/icons-3/004-ICON_Copyright.jpg similarity index 100% rename from buildroot/share/dwin/icons-2/004-ICON_Copyright.jpg rename to buildroot/share/dwin/icons-3/004-ICON_Copyright.jpg diff --git a/buildroot/share/dwin/icons-3/000-ICON_LOGO_Marlin.jpg b/buildroot/share/dwin/icons-4/000-ICON_LOGO_Marlin.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/000-ICON_LOGO_Marlin.jpg rename to buildroot/share/dwin/icons-4/000-ICON_LOGO_Marlin.jpg diff --git a/buildroot/share/dwin/icons-3/001-ICON_HotendOff.jpg b/buildroot/share/dwin/icons-4/001-ICON_HotendOff.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/001-ICON_HotendOff.jpg rename to buildroot/share/dwin/icons-4/001-ICON_HotendOff.jpg diff --git a/buildroot/share/dwin/icons-3/002-ICON_HotendOn.jpg b/buildroot/share/dwin/icons-4/002-ICON_HotendOn.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/002-ICON_HotendOn.jpg rename to buildroot/share/dwin/icons-4/002-ICON_HotendOn.jpg diff --git a/buildroot/share/dwin/icons-3/003-ICON_BedOff.jpg b/buildroot/share/dwin/icons-4/003-ICON_BedOff.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/003-ICON_BedOff.jpg rename to buildroot/share/dwin/icons-4/003-ICON_BedOff.jpg diff --git a/buildroot/share/dwin/icons-3/004-ICON_BedOn.jpg b/buildroot/share/dwin/icons-4/004-ICON_BedOn.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/004-ICON_BedOn.jpg rename to buildroot/share/dwin/icons-4/004-ICON_BedOn.jpg diff --git a/buildroot/share/dwin/icons-3/005-ICON_Fan0.jpg b/buildroot/share/dwin/icons-4/005-ICON_Fan0.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/005-ICON_Fan0.jpg rename to buildroot/share/dwin/icons-4/005-ICON_Fan0.jpg diff --git a/buildroot/share/dwin/icons-3/006-ICON_Fan1.jpg b/buildroot/share/dwin/icons-4/006-ICON_Fan1.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/006-ICON_Fan1.jpg rename to buildroot/share/dwin/icons-4/006-ICON_Fan1.jpg diff --git a/buildroot/share/dwin/icons-3/007-ICON_Fan2.jpg b/buildroot/share/dwin/icons-4/007-ICON_Fan2.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/007-ICON_Fan2.jpg rename to buildroot/share/dwin/icons-4/007-ICON_Fan2.jpg diff --git a/buildroot/share/dwin/icons-3/008-ICON_Fan3.jpg b/buildroot/share/dwin/icons-4/008-ICON_Fan3.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/008-ICON_Fan3.jpg rename to buildroot/share/dwin/icons-4/008-ICON_Fan3.jpg diff --git a/buildroot/share/dwin/icons-3/009-ICON_Halted.jpg b/buildroot/share/dwin/icons-4/009-ICON_Halted.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/009-ICON_Halted.jpg rename to buildroot/share/dwin/icons-4/009-ICON_Halted.jpg diff --git a/buildroot/share/dwin/icons-3/010-ICON_Question.jpg b/buildroot/share/dwin/icons-4/010-ICON_Question.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/010-ICON_Question.jpg rename to buildroot/share/dwin/icons-4/010-ICON_Question.jpg diff --git a/buildroot/share/dwin/icons-3/011-ICON_Alert.jpg b/buildroot/share/dwin/icons-4/011-ICON_Alert.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/011-ICON_Alert.jpg rename to buildroot/share/dwin/icons-4/011-ICON_Alert.jpg diff --git a/buildroot/share/dwin/icons-3/012-ICON_RotateCW.jpg b/buildroot/share/dwin/icons-4/012-ICON_RotateCW.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/012-ICON_RotateCW.jpg rename to buildroot/share/dwin/icons-4/012-ICON_RotateCW.jpg diff --git a/buildroot/share/dwin/icons-3/013-ICON_RotateCCW.jpg b/buildroot/share/dwin/icons-4/013-ICON_RotateCCW.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/013-ICON_RotateCCW.jpg rename to buildroot/share/dwin/icons-4/013-ICON_RotateCCW.jpg diff --git a/buildroot/share/dwin/icons-3/014-ICON_UpArrow.jpg b/buildroot/share/dwin/icons-4/014-ICON_UpArrow.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/014-ICON_UpArrow.jpg rename to buildroot/share/dwin/icons-4/014-ICON_UpArrow.jpg diff --git a/buildroot/share/dwin/icons-3/015-ICON_DownArrow.jpg b/buildroot/share/dwin/icons-4/015-ICON_DownArrow.jpg similarity index 100% rename from buildroot/share/dwin/icons-3/015-ICON_DownArrow.jpg rename to buildroot/share/dwin/icons-4/015-ICON_DownArrow.jpg diff --git a/buildroot/share/dwin/icons-6/000-ICON_LOGO_Creality.jpg b/buildroot/share/dwin/icons-7/000-ICON_LOGO_Creality.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/000-ICON_LOGO_Creality.jpg rename to buildroot/share/dwin/icons-7/000-ICON_LOGO_Creality.jpg diff --git a/buildroot/share/dwin/icons-6/001-ICON_Print_0.jpg b/buildroot/share/dwin/icons-7/001-ICON_Print_0.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/001-ICON_Print_0.jpg rename to buildroot/share/dwin/icons-7/001-ICON_Print_0.jpg diff --git a/buildroot/share/dwin/icons-6/002-ICON_Print_1.jpg b/buildroot/share/dwin/icons-7/002-ICON_Print_1.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/002-ICON_Print_1.jpg rename to buildroot/share/dwin/icons-7/002-ICON_Print_1.jpg diff --git a/buildroot/share/dwin/icons-6/003-ICON_Prepare_0.jpg b/buildroot/share/dwin/icons-7/003-ICON_Prepare_0.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/003-ICON_Prepare_0.jpg rename to buildroot/share/dwin/icons-7/003-ICON_Prepare_0.jpg diff --git a/buildroot/share/dwin/icons-6/004-ICON_Prepare_1.jpg b/buildroot/share/dwin/icons-7/004-ICON_Prepare_1.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/004-ICON_Prepare_1.jpg rename to buildroot/share/dwin/icons-7/004-ICON_Prepare_1.jpg diff --git a/buildroot/share/dwin/icons-6/005-ICON_Control_0.jpg b/buildroot/share/dwin/icons-7/005-ICON_Control_0.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/005-ICON_Control_0.jpg rename to buildroot/share/dwin/icons-7/005-ICON_Control_0.jpg diff --git a/buildroot/share/dwin/icons-6/006-ICON_Control_1.jpg b/buildroot/share/dwin/icons-7/006-ICON_Control_1.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/006-ICON_Control_1.jpg rename to buildroot/share/dwin/icons-7/006-ICON_Control_1.jpg diff --git a/buildroot/share/dwin/icons-6/007-ICON_Leveling_0.jpg b/buildroot/share/dwin/icons-7/007-ICON_Leveling_0.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/007-ICON_Leveling_0.jpg rename to buildroot/share/dwin/icons-7/007-ICON_Leveling_0.jpg diff --git a/buildroot/share/dwin/icons-6/008-ICON_Leveling_1.jpg b/buildroot/share/dwin/icons-7/008-ICON_Leveling_1.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/008-ICON_Leveling_1.jpg rename to buildroot/share/dwin/icons-7/008-ICON_Leveling_1.jpg diff --git a/buildroot/share/dwin/icons-6/009-ICON_HotendTemp.jpg b/buildroot/share/dwin/icons-7/009-ICON_HotendTemp.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/009-ICON_HotendTemp.jpg rename to buildroot/share/dwin/icons-7/009-ICON_HotendTemp.jpg diff --git a/buildroot/share/dwin/icons-6/010-ICON_BedTemp.jpg b/buildroot/share/dwin/icons-7/010-ICON_BedTemp.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/010-ICON_BedTemp.jpg rename to buildroot/share/dwin/icons-7/010-ICON_BedTemp.jpg diff --git a/buildroot/share/dwin/icons-6/011-ICON_Speed.jpg b/buildroot/share/dwin/icons-7/011-ICON_Speed.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/011-ICON_Speed.jpg rename to buildroot/share/dwin/icons-7/011-ICON_Speed.jpg diff --git a/buildroot/share/dwin/icons-6/012-ICON_Zoffset.jpg b/buildroot/share/dwin/icons-7/012-ICON_Zoffset.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/012-ICON_Zoffset.jpg rename to buildroot/share/dwin/icons-7/012-ICON_Zoffset.jpg diff --git a/buildroot/share/dwin/icons-6/013-ICON_Back.jpg b/buildroot/share/dwin/icons-7/013-ICON_Back.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/013-ICON_Back.jpg rename to buildroot/share/dwin/icons-7/013-ICON_Back.jpg diff --git a/buildroot/share/dwin/icons-6/014-ICON_File.jpg b/buildroot/share/dwin/icons-7/014-ICON_File.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/014-ICON_File.jpg rename to buildroot/share/dwin/icons-7/014-ICON_File.jpg diff --git a/buildroot/share/dwin/icons-6/015-ICON_PrintTime.jpg b/buildroot/share/dwin/icons-7/015-ICON_PrintTime.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/015-ICON_PrintTime.jpg rename to buildroot/share/dwin/icons-7/015-ICON_PrintTime.jpg diff --git a/buildroot/share/dwin/icons-6/016-ICON_RemainTime.jpg b/buildroot/share/dwin/icons-7/016-ICON_RemainTime.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/016-ICON_RemainTime.jpg rename to buildroot/share/dwin/icons-7/016-ICON_RemainTime.jpg diff --git a/buildroot/share/dwin/icons-6/017-ICON_Setup_0.jpg b/buildroot/share/dwin/icons-7/017-ICON_Setup_0.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/017-ICON_Setup_0.jpg rename to buildroot/share/dwin/icons-7/017-ICON_Setup_0.jpg diff --git a/buildroot/share/dwin/icons-6/018-ICON_Setup_1.jpg b/buildroot/share/dwin/icons-7/018-ICON_Setup_1.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/018-ICON_Setup_1.jpg rename to buildroot/share/dwin/icons-7/018-ICON_Setup_1.jpg diff --git a/buildroot/share/dwin/icons-6/019-ICON_Pause_0.jpg b/buildroot/share/dwin/icons-7/019-ICON_Pause_0.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/019-ICON_Pause_0.jpg rename to buildroot/share/dwin/icons-7/019-ICON_Pause_0.jpg diff --git a/buildroot/share/dwin/icons-6/020-ICON_Pause_1.jpg b/buildroot/share/dwin/icons-7/020-ICON_Pause_1.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/020-ICON_Pause_1.jpg rename to buildroot/share/dwin/icons-7/020-ICON_Pause_1.jpg diff --git a/buildroot/share/dwin/icons-6/021-ICON_Continue_0.jpg b/buildroot/share/dwin/icons-7/021-ICON_Continue_0.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/021-ICON_Continue_0.jpg rename to buildroot/share/dwin/icons-7/021-ICON_Continue_0.jpg diff --git a/buildroot/share/dwin/icons-6/022-ICON_Continue_1.jpg b/buildroot/share/dwin/icons-7/022-ICON_Continue_1.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/022-ICON_Continue_1.jpg rename to buildroot/share/dwin/icons-7/022-ICON_Continue_1.jpg diff --git a/buildroot/share/dwin/icons-6/023-ICON_Stop_0.jpg b/buildroot/share/dwin/icons-7/023-ICON_Stop_0.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/023-ICON_Stop_0.jpg rename to buildroot/share/dwin/icons-7/023-ICON_Stop_0.jpg diff --git a/buildroot/share/dwin/icons-6/024-ICON_Stop_1.jpg b/buildroot/share/dwin/icons-7/024-ICON_Stop_1.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/024-ICON_Stop_1.jpg rename to buildroot/share/dwin/icons-7/024-ICON_Stop_1.jpg diff --git a/buildroot/share/dwin/icons-6/025-ICON_Bar.jpg b/buildroot/share/dwin/icons-7/025-ICON_Bar.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/025-ICON_Bar.jpg rename to buildroot/share/dwin/icons-7/025-ICON_Bar.jpg diff --git a/buildroot/share/dwin/icons-6/026-ICON_More.jpg b/buildroot/share/dwin/icons-7/026-ICON_More.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/026-ICON_More.jpg rename to buildroot/share/dwin/icons-7/026-ICON_More.jpg diff --git a/buildroot/share/dwin/icons-6/027-ICON_Axis.jpg b/buildroot/share/dwin/icons-7/027-ICON_Axis.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/027-ICON_Axis.jpg rename to buildroot/share/dwin/icons-7/027-ICON_Axis.jpg diff --git a/buildroot/share/dwin/icons-6/028-ICON_CloseMotor.jpg b/buildroot/share/dwin/icons-7/028-ICON_CloseMotor.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/028-ICON_CloseMotor.jpg rename to buildroot/share/dwin/icons-7/028-ICON_CloseMotor.jpg diff --git a/buildroot/share/dwin/icons-6/029-ICON_Homing.jpg b/buildroot/share/dwin/icons-7/029-ICON_Homing.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/029-ICON_Homing.jpg rename to buildroot/share/dwin/icons-7/029-ICON_Homing.jpg diff --git a/buildroot/share/dwin/icons-6/030-ICON_SetHome.jpg b/buildroot/share/dwin/icons-7/030-ICON_SetHome.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/030-ICON_SetHome.jpg rename to buildroot/share/dwin/icons-7/030-ICON_SetHome.jpg diff --git a/buildroot/share/dwin/icons-6/031-ICON_PLAPreheat.jpg b/buildroot/share/dwin/icons-7/031-ICON_PLAPreheat.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/031-ICON_PLAPreheat.jpg rename to buildroot/share/dwin/icons-7/031-ICON_PLAPreheat.jpg diff --git a/buildroot/share/dwin/icons-6/032-ICON_ABSPreheat.jpg b/buildroot/share/dwin/icons-7/032-ICON_ABSPreheat.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/032-ICON_ABSPreheat.jpg rename to buildroot/share/dwin/icons-7/032-ICON_ABSPreheat.jpg diff --git a/buildroot/share/dwin/icons-6/033-ICON_Cool.jpg b/buildroot/share/dwin/icons-7/033-ICON_Cool.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/033-ICON_Cool.jpg rename to buildroot/share/dwin/icons-7/033-ICON_Cool.jpg diff --git a/buildroot/share/dwin/icons-6/034-ICON_Language.jpg b/buildroot/share/dwin/icons-7/034-ICON_Language.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/034-ICON_Language.jpg rename to buildroot/share/dwin/icons-7/034-ICON_Language.jpg diff --git a/buildroot/share/dwin/icons-6/035-ICON_MoveX.jpg b/buildroot/share/dwin/icons-7/035-ICON_MoveX.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/035-ICON_MoveX.jpg rename to buildroot/share/dwin/icons-7/035-ICON_MoveX.jpg diff --git a/buildroot/share/dwin/icons-6/036-ICON_MoveY.jpg b/buildroot/share/dwin/icons-7/036-ICON_MoveY.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/036-ICON_MoveY.jpg rename to buildroot/share/dwin/icons-7/036-ICON_MoveY.jpg diff --git a/buildroot/share/dwin/icons-6/037-ICON_MoveZ.jpg b/buildroot/share/dwin/icons-7/037-ICON_MoveZ.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/037-ICON_MoveZ.jpg rename to buildroot/share/dwin/icons-7/037-ICON_MoveZ.jpg diff --git a/buildroot/share/dwin/icons-6/038-ICON_Extruder.jpg b/buildroot/share/dwin/icons-7/038-ICON_Extruder.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/038-ICON_Extruder.jpg rename to buildroot/share/dwin/icons-7/038-ICON_Extruder.jpg diff --git a/buildroot/share/dwin/icons-6/040-ICON_Temperature.jpg b/buildroot/share/dwin/icons-7/040-ICON_Temperature.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/040-ICON_Temperature.jpg rename to buildroot/share/dwin/icons-7/040-ICON_Temperature.jpg diff --git a/buildroot/share/dwin/icons-6/041-ICON_Motion.jpg b/buildroot/share/dwin/icons-7/041-ICON_Motion.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/041-ICON_Motion.jpg rename to buildroot/share/dwin/icons-7/041-ICON_Motion.jpg diff --git a/buildroot/share/dwin/icons-6/042-ICON_WriteEEPROM.jpg b/buildroot/share/dwin/icons-7/042-ICON_WriteEEPROM.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/042-ICON_WriteEEPROM.jpg rename to buildroot/share/dwin/icons-7/042-ICON_WriteEEPROM.jpg diff --git a/buildroot/share/dwin/icons-6/043-ICON_ReadEEPROM.jpg b/buildroot/share/dwin/icons-7/043-ICON_ReadEEPROM.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/043-ICON_ReadEEPROM.jpg rename to buildroot/share/dwin/icons-7/043-ICON_ReadEEPROM.jpg diff --git a/buildroot/share/dwin/icons-6/044-ICON_ResumeEEPROM.jpg b/buildroot/share/dwin/icons-7/044-ICON_ResetEEPROM.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/044-ICON_ResumeEEPROM.jpg rename to buildroot/share/dwin/icons-7/044-ICON_ResetEEPROM.jpg diff --git a/buildroot/share/dwin/icons-6/045-ICON_Info.jpg b/buildroot/share/dwin/icons-7/045-ICON_Info.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/045-ICON_Info.jpg rename to buildroot/share/dwin/icons-7/045-ICON_Info.jpg diff --git a/buildroot/share/dwin/icons-6/046-ICON_SetEndTemp.jpg b/buildroot/share/dwin/icons-7/046-ICON_SetEndTemp.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/046-ICON_SetEndTemp.jpg rename to buildroot/share/dwin/icons-7/046-ICON_SetEndTemp.jpg diff --git a/buildroot/share/dwin/icons-6/047-ICON_SetBedTemp.jpg b/buildroot/share/dwin/icons-7/047-ICON_SetBedTemp.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/047-ICON_SetBedTemp.jpg rename to buildroot/share/dwin/icons-7/047-ICON_SetBedTemp.jpg diff --git a/buildroot/share/dwin/icons-6/048-ICON_FanSpeed.jpg b/buildroot/share/dwin/icons-7/048-ICON_FanSpeed.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/048-ICON_FanSpeed.jpg rename to buildroot/share/dwin/icons-7/048-ICON_FanSpeed.jpg diff --git a/buildroot/share/dwin/icons-6/049-ICON_SetPLAPreheat.jpg b/buildroot/share/dwin/icons-7/049-ICON_SetPLAPreheat.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/049-ICON_SetPLAPreheat.jpg rename to buildroot/share/dwin/icons-7/049-ICON_SetPLAPreheat.jpg diff --git a/buildroot/share/dwin/icons-6/050-ICON_SetABSPreheat.jpg b/buildroot/share/dwin/icons-7/050-ICON_SetABSPreheat.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/050-ICON_SetABSPreheat.jpg rename to buildroot/share/dwin/icons-7/050-ICON_SetABSPreheat.jpg diff --git a/buildroot/share/dwin/icons-6/051-ICON_MaxSpeed.jpg b/buildroot/share/dwin/icons-7/051-ICON_MaxSpeed.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/051-ICON_MaxSpeed.jpg rename to buildroot/share/dwin/icons-7/051-ICON_MaxSpeed.jpg diff --git a/buildroot/share/dwin/icons-6/052-ICON_MaxAccelerated.jpg b/buildroot/share/dwin/icons-7/052-ICON_MaxAccelerated.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/052-ICON_MaxAccelerated.jpg rename to buildroot/share/dwin/icons-7/052-ICON_MaxAccelerated.jpg diff --git a/buildroot/share/dwin/icons-6/053-ICON_MaxJerk.jpg b/buildroot/share/dwin/icons-7/053-ICON_MaxJerk.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/053-ICON_MaxJerk.jpg rename to buildroot/share/dwin/icons-7/053-ICON_MaxJerk.jpg diff --git a/buildroot/share/dwin/icons-6/054-ICON_Step.jpg b/buildroot/share/dwin/icons-7/054-ICON_Step.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/054-ICON_Step.jpg rename to buildroot/share/dwin/icons-7/054-ICON_Step.jpg diff --git a/buildroot/share/dwin/icons-6/055-ICON_PrintSize.jpg b/buildroot/share/dwin/icons-7/055-ICON_PrintSize.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/055-ICON_PrintSize.jpg rename to buildroot/share/dwin/icons-7/055-ICON_PrintSize.jpg diff --git a/buildroot/share/dwin/icons-6/056-ICON_Version.jpg b/buildroot/share/dwin/icons-7/056-ICON_Version.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/056-ICON_Version.jpg rename to buildroot/share/dwin/icons-7/056-ICON_Version.jpg diff --git a/buildroot/share/dwin/icons-6/057-ICON_Contact.jpg b/buildroot/share/dwin/icons-7/057-ICON_Contact.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/057-ICON_Contact.jpg rename to buildroot/share/dwin/icons-7/057-ICON_Contact.jpg diff --git a/buildroot/share/dwin/icons-6/058-ICON_StockConfiguraton.jpg b/buildroot/share/dwin/icons-7/058-ICON_StockConfiguraton.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/058-ICON_StockConfiguraton.jpg rename to buildroot/share/dwin/icons-7/058-ICON_StockConfiguraton.jpg diff --git a/buildroot/share/dwin/icons-6/059-ICON_MaxSpeedX.jpg b/buildroot/share/dwin/icons-7/059-ICON_MaxSpeedX.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/059-ICON_MaxSpeedX.jpg rename to buildroot/share/dwin/icons-7/059-ICON_MaxSpeedX.jpg diff --git a/buildroot/share/dwin/icons-6/060-ICON_MaxSpeedY.jpg b/buildroot/share/dwin/icons-7/060-ICON_MaxSpeedY.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/060-ICON_MaxSpeedY.jpg rename to buildroot/share/dwin/icons-7/060-ICON_MaxSpeedY.jpg diff --git a/buildroot/share/dwin/icons-6/061-ICON_MaxSpeedZ.jpg b/buildroot/share/dwin/icons-7/061-ICON_MaxSpeedZ.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/061-ICON_MaxSpeedZ.jpg rename to buildroot/share/dwin/icons-7/061-ICON_MaxSpeedZ.jpg diff --git a/buildroot/share/dwin/icons-6/062-ICON_MaxSpeedE.jpg b/buildroot/share/dwin/icons-7/062-ICON_MaxSpeedE.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/062-ICON_MaxSpeedE.jpg rename to buildroot/share/dwin/icons-7/062-ICON_MaxSpeedE.jpg diff --git a/buildroot/share/dwin/icons-6/063-ICON_MaxAccX.jpg b/buildroot/share/dwin/icons-7/063-ICON_MaxAccX.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/063-ICON_MaxAccX.jpg rename to buildroot/share/dwin/icons-7/063-ICON_MaxAccX.jpg diff --git a/buildroot/share/dwin/icons-6/064-ICON_MaxAccY.jpg b/buildroot/share/dwin/icons-7/064-ICON_MaxAccY.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/064-ICON_MaxAccY.jpg rename to buildroot/share/dwin/icons-7/064-ICON_MaxAccY.jpg diff --git a/buildroot/share/dwin/icons-6/065-ICON_MaxAccZ.jpg b/buildroot/share/dwin/icons-7/065-ICON_MaxAccZ.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/065-ICON_MaxAccZ.jpg rename to buildroot/share/dwin/icons-7/065-ICON_MaxAccZ.jpg diff --git a/buildroot/share/dwin/icons-6/066-ICON_MaxAccE.jpg b/buildroot/share/dwin/icons-7/066-ICON_MaxAccE.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/066-ICON_MaxAccE.jpg rename to buildroot/share/dwin/icons-7/066-ICON_MaxAccE.jpg diff --git a/buildroot/share/dwin/icons-6/067-ICON_MaxSpeedJerkX.jpg b/buildroot/share/dwin/icons-7/067-ICON_MaxSpeedJerkX.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/067-ICON_MaxSpeedJerkX.jpg rename to buildroot/share/dwin/icons-7/067-ICON_MaxSpeedJerkX.jpg diff --git a/buildroot/share/dwin/icons-6/068-ICON_MaxSpeedJerkY.jpg b/buildroot/share/dwin/icons-7/068-ICON_MaxSpeedJerkY.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/068-ICON_MaxSpeedJerkY.jpg rename to buildroot/share/dwin/icons-7/068-ICON_MaxSpeedJerkY.jpg diff --git a/buildroot/share/dwin/icons-6/069-ICON_MaxSpeedJerkZ.jpg b/buildroot/share/dwin/icons-7/069-ICON_MaxSpeedJerkZ.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/069-ICON_MaxSpeedJerkZ.jpg rename to buildroot/share/dwin/icons-7/069-ICON_MaxSpeedJerkZ.jpg diff --git a/buildroot/share/dwin/icons-6/070-ICON_MaxSpeedJerkE.jpg b/buildroot/share/dwin/icons-7/070-ICON_MaxSpeedJerkE.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/070-ICON_MaxSpeedJerkE.jpg rename to buildroot/share/dwin/icons-7/070-ICON_MaxSpeedJerkE.jpg diff --git a/buildroot/share/dwin/icons-6/071-ICON_StepX.jpg b/buildroot/share/dwin/icons-7/071-ICON_StepX.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/071-ICON_StepX.jpg rename to buildroot/share/dwin/icons-7/071-ICON_StepX.jpg diff --git a/buildroot/share/dwin/icons-6/072-ICON_StepY.jpg b/buildroot/share/dwin/icons-7/072-ICON_StepY.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/072-ICON_StepY.jpg rename to buildroot/share/dwin/icons-7/072-ICON_StepY.jpg diff --git a/buildroot/share/dwin/icons-6/073-ICON_StepZ.jpg b/buildroot/share/dwin/icons-7/073-ICON_StepZ.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/073-ICON_StepZ.jpg rename to buildroot/share/dwin/icons-7/073-ICON_StepZ.jpg diff --git a/buildroot/share/dwin/icons-6/074-ICON_StepE.jpg b/buildroot/share/dwin/icons-7/074-ICON_StepE.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/074-ICON_StepE.jpg rename to buildroot/share/dwin/icons-7/074-ICON_StepE.jpg diff --git a/buildroot/share/dwin/icons-6/075-ICON_Setspeed.jpg b/buildroot/share/dwin/icons-7/075-ICON_Setspeed.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/075-ICON_Setspeed.jpg rename to buildroot/share/dwin/icons-7/075-ICON_Setspeed.jpg diff --git a/buildroot/share/dwin/icons-6/076-ICON_SetZOffset.jpg b/buildroot/share/dwin/icons-7/076-ICON_SetZOffset.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/076-ICON_SetZOffset.jpg rename to buildroot/share/dwin/icons-7/076-ICON_SetZOffset.jpg diff --git a/buildroot/share/dwin/icons-6/077-ICON_Rectangle.jpg b/buildroot/share/dwin/icons-7/077-ICON_Rectangle.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/077-ICON_Rectangle.jpg rename to buildroot/share/dwin/icons-7/077-ICON_Rectangle.jpg diff --git a/buildroot/share/dwin/icons-6/078-ICON_BLTouch.jpg b/buildroot/share/dwin/icons-7/078-ICON_BLTouch.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/078-ICON_BLTouch.jpg rename to buildroot/share/dwin/icons-7/078-ICON_BLTouch.jpg diff --git a/buildroot/share/dwin/icons-6/079-ICON_TempTooLow.jpg b/buildroot/share/dwin/icons-7/079-ICON_TempTooLow.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/079-ICON_TempTooLow.jpg rename to buildroot/share/dwin/icons-7/079-ICON_TempTooLow.jpg diff --git a/buildroot/share/dwin/icons-6/080-ICON_AutoLeveling.jpg b/buildroot/share/dwin/icons-7/080-ICON_AutoLeveling.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/080-ICON_AutoLeveling.jpg rename to buildroot/share/dwin/icons-7/080-ICON_AutoLeveling.jpg diff --git a/buildroot/share/dwin/icons-6/081-ICON_TempTooHigh.jpg b/buildroot/share/dwin/icons-7/081-ICON_TempTooHigh.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/081-ICON_TempTooHigh.jpg rename to buildroot/share/dwin/icons-7/081-ICON_TempTooHigh.jpg diff --git a/buildroot/share/dwin/icons-6/082-ICON_NoTips_C.jpg b/buildroot/share/dwin/icons-7/082-ICON_NoTips_C.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/082-ICON_NoTips_C.jpg rename to buildroot/share/dwin/icons-7/082-ICON_NoTips_C.jpg diff --git a/buildroot/share/dwin/icons-6/083-ICON_NoTips_E.jpg b/buildroot/share/dwin/icons-7/083-ICON_NoTips_E.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/083-ICON_NoTips_E.jpg rename to buildroot/share/dwin/icons-7/083-ICON_NoTips_E.jpg diff --git a/buildroot/share/dwin/icons-6/084-ICON_Continue_C.jpg b/buildroot/share/dwin/icons-7/084-ICON_Continue_C.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/084-ICON_Continue_C.jpg rename to buildroot/share/dwin/icons-7/084-ICON_Continue_C.jpg diff --git a/buildroot/share/dwin/icons-6/085-ICON_Continue_E.jpg b/buildroot/share/dwin/icons-7/085-ICON_Continue_E.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/085-ICON_Continue_E.jpg rename to buildroot/share/dwin/icons-7/085-ICON_Continue_E.jpg diff --git a/buildroot/share/dwin/icons-6/086-ICON_Cancel_C.jpg b/buildroot/share/dwin/icons-7/086-ICON_Cancel_C.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/086-ICON_Cancel_C.jpg rename to buildroot/share/dwin/icons-7/086-ICON_Cancel_C.jpg diff --git a/buildroot/share/dwin/icons-6/087-ICON_Cancel_E.jpg b/buildroot/share/dwin/icons-7/087-ICON_Cancel_E.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/087-ICON_Cancel_E.jpg rename to buildroot/share/dwin/icons-7/087-ICON_Cancel_E.jpg diff --git a/buildroot/share/dwin/icons-6/088-ICON_Confirm_C.jpg b/buildroot/share/dwin/icons-7/088-ICON_Confirm_C.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/088-ICON_Confirm_C.jpg rename to buildroot/share/dwin/icons-7/088-ICON_Confirm_C.jpg diff --git a/buildroot/share/dwin/icons-6/089-ICON_Confirm_E.jpg b/buildroot/share/dwin/icons-7/089-ICON_Confirm_E.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/089-ICON_Confirm_E.jpg rename to buildroot/share/dwin/icons-7/089-ICON_Confirm_E.jpg diff --git a/buildroot/share/dwin/icons-6/090-ICON_Info_0.jpg b/buildroot/share/dwin/icons-7/090-ICON_Info_0.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/090-ICON_Info_0.jpg rename to buildroot/share/dwin/icons-7/090-ICON_Info_0.jpg diff --git a/buildroot/share/dwin/icons-6/091-ICON_Info_1.jpg b/buildroot/share/dwin/icons-7/091-ICON_Info_1.jpg similarity index 100% rename from buildroot/share/dwin/icons-6/091-ICON_Info_1.jpg rename to buildroot/share/dwin/icons-7/091-ICON_Info_1.jpg diff --git a/buildroot/share/dwin/make_jpgs.sh b/buildroot/share/dwin/make_jpgs.sh index 0acace7388df..c114757a0622 100755 --- a/buildroot/share/dwin/make_jpgs.sh +++ b/buildroot/share/dwin/make_jpgs.sh @@ -1,31 +1,31 @@ #!/usr/bin/env bash -mkdir -p icons-3 +mkdir -p icons-4 -convert -size 48x36 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/hotend_off.svg ./icons-3/001-ICON_HotendOff.jpg -convert -size 48x36 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/hotend_on.svg ./icons-3/002-ICON_HotendOn.jpg +convert -size 48x36 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/hotend_off.svg ./icons-4/001-ICON_HotendOff.jpg +convert -size 48x36 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/hotend_on.svg ./icons-4/002-ICON_HotendOn.jpg -convert -size 48x36 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/bed_off.svg ./icons-3/003-ICON_BedOff.jpg -convert -size 48x36 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/bed_on.svg ./icons-3/004-ICON_BedOn.jpg +convert -size 48x36 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/bed_off.svg ./icons-4/003-ICON_BedOff.jpg +convert -size 48x36 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/bed_on.svg ./icons-4/004-ICON_BedOn.jpg -convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/fan.svg ./icons-3/005-ICON_Fan0.jpg -convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 -distort SRT 22.5 ./icons-svg/fan.svg ./icons-3/006-ICON_Fan1.jpg -convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 -distort SRT 45 ./icons-svg/fan.svg ./icons-3/007-ICON_Fan2.jpg -convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 -distort SRT 67.5 ./icons-svg/fan.svg ./icons-3/008-ICON_Fan3.jpg +convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/fan.svg ./icons-4/005-ICON_Fan0.jpg +convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 -distort SRT 22.5 ./icons-svg/fan.svg ./icons-4/006-ICON_Fan1.jpg +convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 -distort SRT 45 ./icons-svg/fan.svg ./icons-4/007-ICON_Fan2.jpg +convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 -distort SRT 67.5 ./icons-svg/fan.svg ./icons-4/008-ICON_Fan3.jpg -convert -size 96x96 -background "#333e44" -quality 100 -sampling-factor 4:4:4 ./icons-svg/halted.svg ./icons-3/009-ICON_Halted.jpg -convert -size 96x96 -background "#333e44" -quality 100 -sampling-factor 4:4:4 ./icons-svg/question.svg ./icons-3/010-ICON_Question.jpg -convert -size 96x96 -background "#333e44" -quality 100 -sampling-factor 4:4:4 ./icons-svg/alert.svg ./icons-3/011-ICON_Alert.jpg +convert -size 96x96 -background "#333e44" -quality 100 -sampling-factor 4:4:4 ./icons-svg/halted.svg ./icons-4/009-ICON_Halted.jpg +convert -size 96x96 -background "#333e44" -quality 100 -sampling-factor 4:4:4 ./icons-svg/question.svg ./icons-4/010-ICON_Question.jpg +convert -size 96x96 -background "#333e44" -quality 100 -sampling-factor 4:4:4 ./icons-svg/alert.svg ./icons-4/011-ICON_Alert.jpg -convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/rotate_cw.svg ./icons-3/012-ICON_RotateCW.jpg -convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/rotate_ccw.svg ./icons-3/013-ICON_RotateCCW.jpg -convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/up_arrow.svg ./icons-3/014-ICON_UpArrow.jpg -convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/down_arrow.svg ./icons-3/015-ICON_DownArrow.jpg +convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/rotate_cw.svg ./icons-4/012-ICON_RotateCW.jpg +convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/rotate_ccw.svg ./icons-4/013-ICON_RotateCCW.jpg +convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/up_arrow.svg ./icons-4/014-ICON_UpArrow.jpg +convert -size 48x48 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/down_arrow.svg ./icons-4/015-ICON_DownArrow.jpg -convert -size 48x8 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/bedline.svg ./icons-3/016-ICON_Bedline.jpg +convert -size 48x8 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/bedline.svg ./icons-4/016-ICON_Bedline.jpg -convert -size 48x36 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/bed_leveled_off.svg ./icons-3/017-ICON_BedLeveledOff.jpg -convert -size 48x36 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/bed_leveled_on.svg ./icons-3/018-ICON_BedLeveledOn.jpg +convert -size 48x36 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/bed_leveled_off.svg ./icons-4/017-ICON_BedLeveledOff.jpg +convert -size 48x36 -background "#080808" -quality 100 -sampling-factor 4:4:4 ./icons-svg/bed_leveled_on.svg ./icons-4/018-ICON_BedLeveledOn.jpg -rm 3.ICO -./bin/makeIco.py icons-3 3.ICO +rm -f 4.ICO +./bin/makeIco.py icons-4 4.ICO diff --git a/buildroot/share/extras/header.h b/buildroot/share/extras/file_header.h similarity index 92% rename from buildroot/share/extras/header.h rename to buildroot/share/extras/file_header.h index e40471dface9..0c868aebb36f 100644 --- a/buildroot/share/extras/header.h +++ b/buildroot/share/extras/file_header.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm diff --git a/buildroot/share/extras/func_header.h b/buildroot/share/extras/func_header.h new file mode 100644 index 000000000000..bc1eff10d573 --- /dev/null +++ b/buildroot/share/extras/func_header.h @@ -0,0 +1,5 @@ +/** + * $(function) : Description pending + * + * $(javaparam) + */ diff --git a/buildroot/share/extras/uncrustify.cfg b/buildroot/share/extras/uncrustify.cfg index 82044f8c7b9a..73ccadc5e37e 100644 --- a/buildroot/share/extras/uncrustify.cfg +++ b/buildroot/share/extras/uncrustify.cfg @@ -1,84 +1,3643 @@ # # Uncrustify Configuration File -# File Created With UncrustifyX 0.4.3 (252) -# -align_assign_span = 1 -cmt_cpp_to_c = false -cmt_indent_multi = false -cmt_insert_file_header = "./header.h" -cmt_reflow_mode = 1 -cmt_sp_after_star_cont = 1 -cmt_sp_before_star_cont = 1 -cmt_star_cont = true -eat_blanks_after_open_brace = false -eat_blanks_before_close_brace = false -indent_align_assign = false -indent_case_brace = 0 -indent_columns = 2 -indent_cpp_lambda_body = false -indent_func_call_param = true -indent_func_def_param = true -indent_switch_case = 2 -indent_with_tabs = 0 -input_tab_size = 2 -mod_add_long_ifdef_else_comment = 40 -mod_add_long_ifdef_endif_comment = 40 -mod_full_brace_do = false -mod_full_brace_for = false -mod_full_brace_if = false -mod_full_brace_if_chain = 1 -mod_full_brace_while = false -mod_remove_extra_semicolon = true -newlines = lf -nl_after_brace_close = true -nl_after_brace_open = true -nl_assign_leave_one_liners = true -nl_brace_else = add -nl_class_leave_one_liners = true -nl_create_for_one_liner = true -nl_create_if_one_liner = false -nl_create_while_one_liner = true -nl_else_brace = remove -nl_end_of_file = add -nl_enum_brace = remove -nl_enum_leave_one_liners = true -nl_fdef_brace = remove -nl_for_brace = remove -nl_func_leave_one_liners = true -nl_getset_leave_one_liners = true -nl_if_brace = remove -nl_if_leave_one_liners = true -nl_multi_line_sparen_close = add -nl_squeeze_ifdef = false -nl_struct_brace = remove -nl_switch_brace = remove -nl_union_brace = remove -pp_define_at_level = true -pp_if_indent_code = true -pp_indent = add -pp_indent_at_level = true -pp_indent_count = 2 -pp_indent_if = 0 -sp_after_comma = add -sp_after_semi = add -sp_after_sparen = add -sp_arith = add -sp_assign = add -sp_assign_default = remove -sp_before_comma = remove -sp_before_sparen = add -sp_bool = add -sp_brace_else = add -sp_cmt_cpp_start = add -sp_compare = add -sp_cond_colon = add -sp_cond_question = add -sp_else_brace = add -sp_endif_cmt = true -sp_fparen_brace = add -sp_func_call_paren = remove -sp_func_proto_paren = remove -sp_inside_sparen = remove -sp_inside_square = remove -sp_paren_brace = add -sp_paren_paren = remove +# Created with Uncrustify 0.77.1_f +# + +# +# General options +# + +# The type of line endings. +# +# Default: auto +newlines = lf # lf/crlf/cr/auto + +# The original size of tabs in the input. +# +# Default: 8 +input_tab_size = 2 # unsigned number + +# The size of tabs in the output (only used if align_with_tabs=true). +# +# Default: 8 +output_tab_size = 8 # unsigned number + +# The ASCII value of the string escape char, usually 92 (\) or (Pawn) 94 (^). +# +# Default: 92 +string_escape_char = 92 # unsigned number + +# Alternate string escape char (usually only used for Pawn). +# Only works right before the quote char. +string_escape_char2 = 0 # unsigned number + +# Replace tab characters found in string literals with the escape sequence \t +# instead. +string_replace_tab_chars = false # true/false + +# Allow interpreting '>=' and '>>=' as part of a template in code like +# 'void f(list>=val);'. If true, 'assert(x<0 && y>=3)' will be broken. +# Improvements to template detection may make this option obsolete. +tok_split_gte = false # true/false + +# Disable formatting of NL_CONT ('\\n') ended lines (e.g. multi-line macros). +disable_processing_nl_cont = false # true/false + +# Specify the marker used in comments to disable processing of part of the +# file. +# +# Default: *INDENT-OFF* +disable_processing_cmt = " *INDENT-OFF*" # string + +# Specify the marker used in comments to (re)enable processing in a file. +# +# Default: *INDENT-ON* +enable_processing_cmt = " *INDENT-ON*" # string + +# Enable parsing of digraphs. +enable_digraphs = false # true/false + +# Option to allow both disable_processing_cmt and enable_processing_cmt +# strings, if specified, to be interpreted as ECMAScript regular expressions. +# If true, a regex search will be performed within comments according to the +# specified patterns in order to disable/enable processing. +processing_cmt_as_regex = false # true/false + +# Add or remove the UTF-8 BOM (recommend 'remove'). +utf8_bom = ignore # ignore/add/remove/force/not_defined + +# If the file contains bytes with values between 128 and 255, but is not +# UTF-8, then output as UTF-8. +utf8_byte = false # true/false + +# Force the output encoding to UTF-8. +utf8_force = false # true/false + +# +# Spacing options +# + +# Add or remove space around non-assignment symbolic operators ('+', '/', '%', +# '<<', and so forth). +sp_arith = add # ignore/add/remove/force/not_defined + +# Add or remove space around arithmetic operators '+' and '-'. +# +# Overrides sp_arith. +sp_arith_additive = ignore # ignore/add/remove/force/not_defined + +# Add or remove space around assignment operator '=', '+=', etc. +sp_assign = add # ignore/add/remove/force/not_defined + +# Add or remove space around '=' in C++11 lambda capture specifications. +# +# Overrides sp_assign. +sp_cpp_lambda_assign = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after the capture specification of a C++11 lambda when +# an argument list is present, as in '[] (int x){ ... }'. +sp_cpp_lambda_square_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after the capture specification of a C++11 lambda with +# no argument list is present, as in '[] { ... }'. +sp_cpp_lambda_square_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after the opening parenthesis and before the closing +# parenthesis of a argument list of a C++11 lambda, as in +# '[]( int x ){ ... }'. +sp_cpp_lambda_argument_list = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after the argument list of a C++11 lambda, as in +# '[](int x) { ... }'. +sp_cpp_lambda_paren_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between a lambda body and its call operator of an +# immediately invoked lambda, as in '[]( ... ){ ... } ( ... )'. +sp_cpp_lambda_fparen = ignore # ignore/add/remove/force/not_defined + +# Add or remove space around assignment operator '=' in a prototype. +# +# If set to ignore, use sp_assign. +sp_assign_default = remove # ignore/add/remove/force/not_defined + +# Add or remove space before assignment operator '=', '+=', etc. +# +# Overrides sp_assign. +sp_before_assign = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after assignment operator '=', '+=', etc. +# +# Overrides sp_assign. +sp_after_assign = ignore # ignore/add/remove/force/not_defined + +# Add or remove space in 'enum {'. +# +# Default: add +sp_enum_brace = add # ignore/add/remove/force/not_defined + +# Add or remove space in 'NS_ENUM ('. +sp_enum_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space around assignment '=' in enum. +sp_enum_assign = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before assignment '=' in enum. +# +# Overrides sp_enum_assign. +sp_enum_before_assign = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after assignment '=' in enum. +# +# Overrides sp_enum_assign. +sp_enum_after_assign = ignore # ignore/add/remove/force/not_defined + +# Add or remove space around assignment ':' in enum. +sp_enum_colon = ignore # ignore/add/remove/force/not_defined + +# Add or remove space around preprocessor '##' concatenation operator. +# +# Default: add +sp_pp_concat = add # ignore/add/remove/force/not_defined + +# Add or remove space after preprocessor '#' stringify operator. +# Also affects the '#@' charizing operator. +sp_pp_stringify = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before preprocessor '#' stringify operator +# as in '#define x(y) L#y'. +sp_before_pp_stringify = ignore # ignore/add/remove/force/not_defined + +# Add or remove space around boolean operators '&&' and '||'. +sp_bool = add # ignore/add/remove/force/not_defined + +# Add or remove space around compare operator '<', '>', '==', etc. +sp_compare = add # ignore/add/remove/force/not_defined + +# Add or remove space inside '(' and ')'. +sp_inside_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between nested parentheses, i.e. '((' vs. ') )'. +sp_paren_paren = remove # ignore/add/remove/force/not_defined + +# Add or remove space between back-to-back parentheses, i.e. ')(' vs. ') ('. +sp_cparen_oparen = ignore # ignore/add/remove/force/not_defined + +# Whether to balance spaces inside nested parentheses. +sp_balance_nested_parens = false # true/false + +# Add or remove space between ')' and '{'. +sp_paren_brace = add # ignore/add/remove/force/not_defined + +# Add or remove space between nested braces, i.e. '{{' vs. '{ {'. +sp_brace_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before pointer star '*'. +sp_before_ptr_star = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before pointer star '*' that isn't followed by a +# variable name. If set to ignore, sp_before_ptr_star is used instead. +sp_before_unnamed_ptr_star = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between a qualifier and a pointer star '*' that isn't +# followed by a variable name, as in '(char const *)'. If set to ignore, +# sp_before_ptr_star is used instead. +sp_qualifier_unnamed_ptr_star = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between pointer stars '*', as in 'int ***a;'. +sp_between_ptr_star = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after pointer star '*', if followed by a word. +# +# Overrides sp_type_func. +sp_after_ptr_star = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after pointer caret '^', if followed by a word. +sp_after_ptr_block_caret = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after pointer star '*', if followed by a qualifier. +sp_after_ptr_star_qualifier = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after a pointer star '*', if followed by a function +# prototype or function definition. +# +# Overrides sp_after_ptr_star and sp_type_func. +sp_after_ptr_star_func = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after a pointer star '*' in the trailing return of a +# function prototype or function definition. +sp_after_ptr_star_trailing = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between the pointer star '*' and the name of the variable +# in a function pointer definition. +sp_ptr_star_func_var = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between the pointer star '*' and the name of the type +# in a function pointer type definition. +sp_ptr_star_func_type = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after a pointer star '*', if followed by an open +# parenthesis, as in 'void* (*)()'. +sp_ptr_star_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before a pointer star '*', if followed by a function +# prototype or function definition. If set to ignore, sp_before_ptr_star is +# used instead. +sp_before_ptr_star_func = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between a qualifier and a pointer star '*' followed by +# the name of the function in a function prototype or definition, as in +# 'char const *foo()`. If set to ignore, sp_before_ptr_star is used instead. +sp_qualifier_ptr_star_func = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before a pointer star '*' in the trailing return of a +# function prototype or function definition. +sp_before_ptr_star_trailing = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between a qualifier and a pointer star '*' in the +# trailing return of a function prototype or function definition, as in +# 'auto foo() -> char const *'. +sp_qualifier_ptr_star_trailing = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before a reference sign '&'. +sp_before_byref = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before a reference sign '&' that isn't followed by a +# variable name. If set to ignore, sp_before_byref is used instead. +sp_before_unnamed_byref = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after reference sign '&', if followed by a word. +# +# Overrides sp_type_func. +sp_after_byref = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after a reference sign '&', if followed by a function +# prototype or function definition. +# +# Overrides sp_after_byref and sp_type_func. +sp_after_byref_func = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before a reference sign '&', if followed by a function +# prototype or function definition. +sp_before_byref_func = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after a reference sign '&', if followed by an open +# parenthesis, as in 'char& (*)()'. +sp_byref_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between type and word. In cases where total removal of +# whitespace would be a syntax error, a value of 'remove' is treated the same +# as 'force'. +# +# This also affects some other instances of space following a type that are +# not covered by other options; for example, between the return type and +# parenthesis of a function type template argument, between the type and +# parenthesis of an array parameter, or between 'decltype(...)' and the +# following word. +# +# Default: force +sp_after_type = force # ignore/add/remove/force/not_defined + +# Add or remove space between 'decltype(...)' and word, +# brace or function call. +sp_after_decltype = ignore # ignore/add/remove/force/not_defined + +# (D) Add or remove space before the parenthesis in the D constructs +# 'template Foo(' and 'class Foo('. +sp_before_template_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'template' and '<'. +# If set to ignore, sp_before_angle is used. +sp_template_angle = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before '<'. +sp_before_angle = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside '<' and '>'. +sp_inside_angle = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside '<>'. +sp_inside_angle_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between '>' and ':'. +sp_angle_colon = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after '>'. +sp_after_angle = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between '>' and '(' as found in 'new List(foo);'. +sp_angle_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between '>' and '()' as found in 'new List();'. +sp_angle_paren_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between '>' and a word as in 'List m;' or +# 'template static ...'. +sp_angle_word = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between '>' and '>' in '>>' (template stuff). +# +# Default: add +sp_angle_shift = add # ignore/add/remove/force/not_defined + +# (C++11) Permit removal of the space between '>>' in 'foo >'. Note +# that sp_angle_shift cannot remove the space without this option. +sp_permit_cpp11_shift = false # true/false + +# Add or remove space before '(' of control statements ('if', 'for', 'switch', +# 'while', etc.). +sp_before_sparen = add # ignore/add/remove/force/not_defined + +# Add or remove space inside '(' and ')' of control statements other than +# 'for'. +sp_inside_sparen = remove # ignore/add/remove/force/not_defined + +# Add or remove space after '(' of control statements other than 'for'. +# +# Overrides sp_inside_sparen. +sp_inside_sparen_open = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before ')' of control statements other than 'for'. +# +# Overrides sp_inside_sparen. +sp_inside_sparen_close = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside '(' and ')' of 'for' statements. +sp_inside_for = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after '(' of 'for' statements. +# +# Overrides sp_inside_for. +sp_inside_for_open = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before ')' of 'for' statements. +# +# Overrides sp_inside_for. +sp_inside_for_close = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between '((' or '))' of control statements. +sp_sparen_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after ')' of control statements. +sp_after_sparen = add # ignore/add/remove/force/not_defined + +# Add or remove space between ')' and '{' of control statements. +sp_sparen_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'do' and '{'. +sp_do_brace_open = force # ignore/add/remove/force/not_defined + +# Add or remove space between '}' and 'while'. +sp_brace_close_while = force # ignore/add/remove/force/not_defined + +# Add or remove space between 'while' and '('. Overrides sp_before_sparen. +sp_while_paren_open = force # ignore/add/remove/force/not_defined + +# (D) Add or remove space between 'invariant' and '('. +sp_invariant_paren = ignore # ignore/add/remove/force/not_defined + +# (D) Add or remove space after the ')' in 'invariant (C) c'. +sp_after_invariant_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before empty statement ';' on 'if', 'for' and 'while'. +sp_special_semi = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before ';'. +# +# Default: remove +sp_before_semi = remove # ignore/add/remove/force/not_defined + +# Add or remove space before ';' in non-empty 'for' statements. +sp_before_semi_for = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before a semicolon of an empty left part of a for +# statement, as in 'for ( ; ; )'. +sp_before_semi_for_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between the semicolons of an empty middle part of a for +# statement, as in 'for ( ; ; )'. +sp_between_semi_for_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after ';', except when followed by a comment. +# +# Default: add +sp_after_semi = add # ignore/add/remove/force/not_defined + +# Add or remove space after ';' in non-empty 'for' statements. +# +# Default: force +sp_after_semi_for = force # ignore/add/remove/force/not_defined + +# Add or remove space after the final semicolon of an empty part of a for +# statement, as in 'for ( ; ; )'. +sp_after_semi_for_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before '[' (except '[]'). +sp_before_square = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before '[' for a variable definition. +# +# Default: remove +sp_before_vardef_square = remove # ignore/add/remove/force/not_defined + +# Add or remove space before '[' for asm block. +sp_before_square_asm_block = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before '[]'. +sp_before_squares = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before C++17 structured bindings. +sp_cpp_before_struct_binding = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside a non-empty '[' and ']'. +sp_inside_square = remove # ignore/add/remove/force/not_defined + +# Add or remove space inside '[]'. +sp_inside_square_empty = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space inside a non-empty Objective-C boxed array '@[' and +# ']'. If set to ignore, sp_inside_square is used. +sp_inside_square_oc_array = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after ',', i.e. 'a,b' vs. 'a, b'. +sp_after_comma = add # ignore/add/remove/force/not_defined + +# Add or remove space before ',', i.e. 'a,b' vs. 'a ,b'. +# +# Default: remove +sp_before_comma = remove # ignore/add/remove/force/not_defined + +# (C#, Vala) Add or remove space between ',' and ']' in multidimensional array type +# like 'int[,,]'. +sp_after_mdatype_commas = ignore # ignore/add/remove/force/not_defined + +# (C#, Vala) Add or remove space between '[' and ',' in multidimensional array type +# like 'int[,,]'. +sp_before_mdatype_commas = ignore # ignore/add/remove/force/not_defined + +# (C#, Vala) Add or remove space between ',' in multidimensional array type +# like 'int[,,]'. +sp_between_mdatype_commas = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between an open parenthesis and comma, +# i.e. '(,' vs. '( ,'. +# +# Default: force +sp_paren_comma = force # ignore/add/remove/force/not_defined + +# Add or remove space between a type and ':'. +sp_type_colon = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after the variadic '...' when preceded by a +# non-punctuator. +# The value REMOVE will be overridden with FORCE +sp_after_ellipsis = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before the variadic '...' when preceded by a +# non-punctuator. +# The value REMOVE will be overridden with FORCE +sp_before_ellipsis = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between a type and '...'. +sp_type_ellipsis = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between a '*' and '...'. +sp_ptr_type_ellipsis = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between ')' and '...'. +sp_paren_ellipsis = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between '&&' and '...'. +sp_byref_ellipsis = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between ')' and a qualifier such as 'const'. +sp_paren_qualifier = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between ')' and 'noexcept'. +sp_paren_noexcept = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after class ':'. +sp_after_class_colon = add # ignore/add/remove/force/not_defined + +# Add or remove space before class ':'. +sp_before_class_colon = add # ignore/add/remove/force/not_defined + +# Add or remove space after class constructor ':'. +# +# Default: add +sp_after_constr_colon = add # ignore/add/remove/force/not_defined + +# Add or remove space before class constructor ':'. +# +# Default: add +sp_before_constr_colon = add # ignore/add/remove/force/not_defined + +# Add or remove space before case ':'. +# +# Default: remove +sp_before_case_colon = remove # ignore/add/remove/force/not_defined + +# Add or remove space between 'operator' and operator sign. +sp_after_operator = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between the operator symbol and the open parenthesis, as +# in 'operator ++('. +sp_after_operator_sym = ignore # ignore/add/remove/force/not_defined + +# Overrides sp_after_operator_sym when the operator has no arguments, as in +# 'operator *()'. +sp_after_operator_sym_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after C/D cast, i.e. 'cast(int)a' vs. 'cast(int) a' or +# '(int)a' vs. '(int) a'. +sp_after_cast = ignore # ignore/add/remove/force/not_defined + +# Add or remove spaces inside cast parentheses. +sp_inside_paren_cast = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between the type and open parenthesis in a C++ cast, +# i.e. 'int(exp)' vs. 'int (exp)'. +sp_cpp_cast_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'sizeof' and '('. +sp_sizeof_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'sizeof' and '...'. +sp_sizeof_ellipsis = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'sizeof...' and '('. +sp_sizeof_ellipsis_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between '...' and a parameter pack. +sp_ellipsis_parameter_pack = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between a parameter pack and '...'. +sp_parameter_pack_ellipsis = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'decltype' and '('. +sp_decltype_paren = ignore # ignore/add/remove/force/not_defined + +# (Pawn) Add or remove space after the tag keyword. +sp_after_tag = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside enum '{' and '}'. +sp_inside_braces_enum = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside struct/union '{' and '}'. +sp_inside_braces_struct = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space inside Objective-C boxed dictionary '{' and '}' +sp_inside_braces_oc_dict = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after open brace in an unnamed temporary +# direct-list-initialization +# if statement is a brace_init_lst +# works only if sp_brace_brace is set to ignore. +sp_after_type_brace_init_lst_open = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before close brace in an unnamed temporary +# direct-list-initialization +# if statement is a brace_init_lst +# works only if sp_brace_brace is set to ignore. +sp_before_type_brace_init_lst_close = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside an unnamed temporary direct-list-initialization +# if statement is a brace_init_lst +# works only if sp_brace_brace is set to ignore +# works only if sp_before_type_brace_init_lst_close is set to ignore. +sp_inside_type_brace_init_lst = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside '{' and '}'. +sp_inside_braces = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside '{}'. +sp_inside_braces_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove space around trailing return operator '->'. +sp_trailing_return = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between return type and function name. A minimum of 1 +# is forced except for pointer return types. +sp_type_func = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between type and open brace of an unnamed temporary +# direct-list-initialization. +sp_type_brace_init_lst = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between function name and '(' on function declaration. +sp_func_proto_paren = remove # ignore/add/remove/force/not_defined + +# Add or remove space between function name and '()' on function declaration +# without parameters. +sp_func_proto_paren_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between function name and '(' with a typedef specifier. +sp_func_type_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between alias name and '(' of a non-pointer function type typedef. +sp_func_def_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between function name and '()' on function definition +# without parameters. +sp_func_def_paren_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside empty function '()'. +# Overrides sp_after_angle unless use_sp_after_angle_always is set to true. +sp_inside_fparens = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside function '(' and ')'. +sp_inside_fparen = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside user functor '(' and ')'. +sp_func_call_user_inside_rparen = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside empty functor '()'. +# Overrides sp_after_angle unless use_sp_after_angle_always is set to true. +sp_inside_rparens = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside functor '(' and ')'. +sp_inside_rparen = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside the first parentheses in a function type, as in +# 'void (*x)(...)'. +sp_inside_tparen = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between the ')' and '(' in a function type, as in +# 'void (*x)(...)'. +sp_after_tparen_close = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between ']' and '(' when part of a function call. +sp_square_fparen = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between ')' and '{' of function. +sp_fparen_brace = force # ignore/add/remove/force/not_defined + +# Add or remove space between ')' and '{' of a function call in object +# initialization. +# +# Overrides sp_fparen_brace. +sp_fparen_brace_initializer = ignore # ignore/add/remove/force/not_defined + +# (Java) Add or remove space between ')' and '{{' of double brace initializer. +sp_fparen_dbrace = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between function name and '(' on function calls. +sp_func_call_paren = remove # ignore/add/remove/force/not_defined + +# Add or remove space between function name and '()' on function calls without +# parameters. If set to ignore (the default), sp_func_call_paren is used. +sp_func_call_paren_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between the user function name and '(' on function +# calls. You need to set a keyword to be a user function in the config file, +# like: +# set func_call_user tr _ i18n +sp_func_call_user_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside user function '(' and ')'. +sp_func_call_user_inside_fparen = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between nested parentheses with user functions, +# i.e. '((' vs. '( ('. +sp_func_call_user_paren_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between a constructor/destructor and the open +# parenthesis. +sp_func_class_paren = remove # ignore/add/remove/force/not_defined + +# Add or remove space between a constructor without parameters or destructor +# and '()'. +sp_func_class_paren_empty = remove # ignore/add/remove/force/not_defined + +# Add or remove space after 'return'. +# +# Default: force +sp_return = force # ignore/add/remove/force/not_defined + +# Add or remove space between 'return' and '('. +sp_return_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'return' and '{'. +sp_return_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between '__attribute__' and '('. +sp_attribute_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'defined' and '(' in '#if defined (FOO)'. +sp_defined_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'throw' and '(' in 'throw (something)'. +sp_throw_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'throw' and anything other than '(' as in +# '@throw [...];'. +sp_after_throw = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'catch' and '(' in 'catch (something) { }'. +# If set to ignore, sp_before_sparen is used. +sp_catch_paren = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space between '@catch' and '(' +# in '@catch (something) { }'. If set to ignore, sp_catch_paren is used. +sp_oc_catch_paren = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space before Objective-C protocol list +# as in '@protocol Protocol' or '@interface MyClass : NSObject'. +sp_before_oc_proto_list = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space between class name and '(' +# in '@interface className(categoryName):BaseClass' +sp_oc_classname_paren = ignore # ignore/add/remove/force/not_defined + +# (D) Add or remove space between 'version' and '(' +# in 'version (something) { }'. If set to ignore, sp_before_sparen is used. +sp_version_paren = ignore # ignore/add/remove/force/not_defined + +# (D) Add or remove space between 'scope' and '(' +# in 'scope (something) { }'. If set to ignore, sp_before_sparen is used. +sp_scope_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'super' and '(' in 'super (something)'. +# +# Default: remove +sp_super_paren = remove # ignore/add/remove/force/not_defined + +# Add or remove space between 'this' and '(' in 'this (something)'. +# +# Default: remove +sp_this_paren = remove # ignore/add/remove/force/not_defined + +# Add or remove space between a macro name and its definition. +sp_macro = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between a macro function ')' and its definition. +sp_macro_func = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'else' and '{' if on the same line. +sp_else_brace = add # ignore/add/remove/force/not_defined + +# Add or remove space between '}' and 'else' if on the same line. +sp_brace_else = force # ignore/add/remove/force/not_defined + +# Add or remove space between '}' and the name of a typedef on the same line. +sp_brace_typedef = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before the '{' of a 'catch' statement, if the '{' and +# 'catch' are on the same line, as in 'catch (decl) {'. +sp_catch_brace = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space before the '{' of a '@catch' statement, if the '{' +# and '@catch' are on the same line, as in '@catch (decl) {'. +# If set to ignore, sp_catch_brace is used. +sp_oc_catch_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between '}' and 'catch' if on the same line. +sp_brace_catch = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space between '}' and '@catch' if on the same line. +# If set to ignore, sp_brace_catch is used. +sp_oc_brace_catch = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'finally' and '{' if on the same line. +sp_finally_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between '}' and 'finally' if on the same line. +sp_brace_finally = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'try' and '{' if on the same line. +sp_try_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between get/set and '{' if on the same line. +sp_getset_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between a variable and '{' for C++ uniform +# initialization. +sp_word_brace_init_lst = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between a variable and '{' for a namespace. +# +# Default: add +sp_word_brace_ns = add # ignore/add/remove/force/not_defined + +# Add or remove space before the '::' operator. +sp_before_dc = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after the '::' operator. +sp_after_dc = ignore # ignore/add/remove/force/not_defined + +# (D) Add or remove around the D named array initializer ':' operator. +sp_d_array_colon = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after the '!' (not) unary operator. +# +# Default: remove +sp_not = remove # ignore/add/remove/force/not_defined + +# Add or remove space between two '!' (not) unary operators. +# If set to ignore, sp_not will be used. +sp_not_not = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after the '~' (invert) unary operator. +# +# Default: remove +sp_inv = remove # ignore/add/remove/force/not_defined + +# Add or remove space after the '&' (address-of) unary operator. This does not +# affect the spacing after a '&' that is part of a type. +# +# Default: remove +sp_addr = remove # ignore/add/remove/force/not_defined + +# Add or remove space around the '.' or '->' operators. +# +# Default: remove +sp_member = remove # ignore/add/remove/force/not_defined + +# Add or remove space after the '*' (dereference) unary operator. This does +# not affect the spacing after a '*' that is part of a type. +# +# Default: remove +sp_deref = remove # ignore/add/remove/force/not_defined + +# Add or remove space after '+' or '-', as in 'x = -5' or 'y = +7'. +# +# Default: remove +sp_sign = remove # ignore/add/remove/force/not_defined + +# Add or remove space between '++' and '--' the word to which it is being +# applied, as in '(--x)' or 'y++;'. +# +# Default: remove +sp_incdec = remove # ignore/add/remove/force/not_defined + +# Add or remove space before a backslash-newline at the end of a line. +# +# Default: add +sp_before_nl_cont = add # ignore/add/remove/force/not_defined + +# (OC) Add or remove space after the scope '+' or '-', as in '-(void) foo;' +# or '+(int) bar;'. +sp_after_oc_scope = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space after the colon in message specs, +# i.e. '-(int) f:(int) x;' vs. '-(int) f: (int) x;'. +sp_after_oc_colon = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space before the colon in message specs, +# i.e. '-(int) f: (int) x;' vs. '-(int) f : (int) x;'. +sp_before_oc_colon = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space after the colon in immutable dictionary expression +# 'NSDictionary *test = @{@"foo" :@"bar"};'. +sp_after_oc_dict_colon = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space before the colon in immutable dictionary expression +# 'NSDictionary *test = @{@"foo" :@"bar"};'. +sp_before_oc_dict_colon = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space after the colon in message specs, +# i.e. '[object setValue:1];' vs. '[object setValue: 1];'. +sp_after_send_oc_colon = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space before the colon in message specs, +# i.e. '[object setValue:1];' vs. '[object setValue :1];'. +sp_before_send_oc_colon = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space after the (type) in message specs, +# i.e. '-(int)f: (int) x;' vs. '-(int)f: (int)x;'. +sp_after_oc_type = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space after the first (type) in message specs, +# i.e. '-(int) f:(int)x;' vs. '-(int)f:(int)x;'. +sp_after_oc_return_type = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space between '@selector' and '(', +# i.e. '@selector(msgName)' vs. '@selector (msgName)'. +# Also applies to '@protocol()' constructs. +sp_after_oc_at_sel = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space between '@selector(x)' and the following word, +# i.e. '@selector(foo) a:' vs. '@selector(foo)a:'. +sp_after_oc_at_sel_parens = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space inside '@selector' parentheses, +# i.e. '@selector(foo)' vs. '@selector( foo )'. +# Also applies to '@protocol()' constructs. +sp_inside_oc_at_sel_parens = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space before a block pointer caret, +# i.e. '^int (int arg){...}' vs. ' ^int (int arg){...}'. +sp_before_oc_block_caret = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space after a block pointer caret, +# i.e. '^int (int arg){...}' vs. '^ int (int arg){...}'. +sp_after_oc_block_caret = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space between the receiver and selector in a message, +# as in '[receiver selector ...]'. +sp_after_oc_msg_receiver = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space after '@property'. +sp_after_oc_property = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove space between '@synchronized' and the open parenthesis, +# i.e. '@synchronized(foo)' vs. '@synchronized (foo)'. +sp_after_oc_synchronized = ignore # ignore/add/remove/force/not_defined + +# Add or remove space around the ':' in 'b ? t : f'. +sp_cond_colon = add # ignore/add/remove/force/not_defined + +# Add or remove space before the ':' in 'b ? t : f'. +# +# Overrides sp_cond_colon. +sp_cond_colon_before = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after the ':' in 'b ? t : f'. +# +# Overrides sp_cond_colon. +sp_cond_colon_after = ignore # ignore/add/remove/force/not_defined + +# Add or remove space around the '?' in 'b ? t : f'. +sp_cond_question = add # ignore/add/remove/force/not_defined + +# Add or remove space before the '?' in 'b ? t : f'. +# +# Overrides sp_cond_question. +sp_cond_question_before = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after the '?' in 'b ? t : f'. +# +# Overrides sp_cond_question. +sp_cond_question_after = ignore # ignore/add/remove/force/not_defined + +# In the abbreviated ternary form '(a ?: b)', add or remove space between '?' +# and ':'. +# +# Overrides all other sp_cond_* options. +sp_cond_ternary_short = ignore # ignore/add/remove/force/not_defined + +# Fix the spacing between 'case' and the label. Only 'ignore' and 'force' make +# sense here. +sp_case_label = ignore # ignore/add/remove/force/not_defined + +# (D) Add or remove space around the D '..' operator. +sp_range = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after ':' in a Java/C++11 range-based 'for', +# as in 'for (Type var : expr)'. +sp_after_for_colon = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before ':' in a Java/C++11 range-based 'for', +# as in 'for (Type var : expr)'. +sp_before_for_colon = ignore # ignore/add/remove/force/not_defined + +# (D) Add or remove space between 'extern' and '(' as in 'extern (C)'. +sp_extern_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after the opening of a C++ comment, as in '// A'. +sp_cmt_cpp_start = add # ignore/add/remove/force/not_defined + +# remove space after the '//' and the pvs command '-V1234', +# only works with sp_cmt_cpp_start set to add or force. +sp_cmt_cpp_pvs = false # true/false + +# remove space after the '//' and the command 'lint', +# only works with sp_cmt_cpp_start set to add or force. +sp_cmt_cpp_lint = false # true/false + +# Add or remove space in a C++ region marker comment, as in '// BEGIN'. +# A region marker is defined as a comment which is not preceded by other text +# (i.e. the comment is the first non-whitespace on the line), and which starts +# with either 'BEGIN' or 'END'. +# +# Overrides sp_cmt_cpp_start. +sp_cmt_cpp_region = ignore # ignore/add/remove/force/not_defined + +# If true, space added with sp_cmt_cpp_start will be added after Doxygen +# sequences like '///', '///<', '//!' and '//!<'. +sp_cmt_cpp_doxygen = true # true/false + +# If true, space added with sp_cmt_cpp_start will be added after Qt translator +# or meta-data comments like '//:', '//=', and '//~'. +sp_cmt_cpp_qttr = false # true/false + +# Add or remove space between #else or #endif and a trailing comment. +sp_endif_cmt = add # ignore/add/remove/force/not_defined + +# Add or remove space after 'new', 'delete' and 'delete[]'. +sp_after_new = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between 'new' and '(' in 'new()'. +sp_between_new_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space between ')' and type in 'new(foo) BAR'. +sp_after_newop_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space inside parentheses of the new operator +# as in 'new(foo) BAR'. +sp_inside_newop_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after the open parenthesis of the new operator, +# as in 'new(foo) BAR'. +# +# Overrides sp_inside_newop_paren. +sp_inside_newop_paren_open = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before the close parenthesis of the new operator, +# as in 'new(foo) BAR'. +# +# Overrides sp_inside_newop_paren. +sp_inside_newop_paren_close = ignore # ignore/add/remove/force/not_defined + +# Add or remove space before a trailing comment. +sp_before_tr_cmt = ignore # ignore/add/remove/force/not_defined + +# Number of spaces before a trailing comment. +sp_num_before_tr_cmt = 0 # unsigned number + +# Add or remove space before an embedded comment. +# +# Default: force +sp_before_emb_cmt = force # ignore/add/remove/force/not_defined + +# Number of spaces before an embedded comment. +# +# Default: 1 +sp_num_before_emb_cmt = 1 # unsigned number + +# Add or remove space after an embedded comment. +# +# Default: force +sp_after_emb_cmt = force # ignore/add/remove/force/not_defined + +# Number of spaces after an embedded comment. +# +# Default: 1 +sp_num_after_emb_cmt = 1 # unsigned number + +# (Java) Add or remove space between an annotation and the open parenthesis. +sp_annotation_paren = ignore # ignore/add/remove/force/not_defined + +# If true, vbrace tokens are dropped to the previous token and skipped. +sp_skip_vbrace_tokens = false # true/false + +# Add or remove space after 'noexcept'. +sp_after_noexcept = ignore # ignore/add/remove/force/not_defined + +# Add or remove space after '_'. +sp_vala_after_translation = ignore # ignore/add/remove/force/not_defined + +# If true, a is inserted after #define. +force_tab_after_define = false # true/false + +# +# Indenting options +# + +# The number of columns to indent per level. Usually 2, 3, 4, or 8. +# +# Default: 8 +indent_columns = 2 # unsigned number + +# Whether to ignore indent for the first continuation line. Subsequent +# continuation lines will still be indented to match the first. +indent_ignore_first_continue = false # true/false + +# The continuation indent. If non-zero, this overrides the indent of '(', '[' +# and '=' continuation indents. Negative values are OK; negative value is +# absolute and not increased for each '(' or '[' level. +# +# For FreeBSD, this is set to 4. +# Requires indent_ignore_first_continue=false. +indent_continue = 0 # number + +# The continuation indent, only for class header line(s). If non-zero, this +# overrides the indent of 'class' continuation indents. +# Requires indent_ignore_first_continue=false. +indent_continue_class_head = 0 # unsigned number + +# Whether to indent empty lines (i.e. lines which contain only spaces before +# the newline character). +indent_single_newlines = false # true/false + +# The continuation indent for func_*_param if they are true. If non-zero, this +# overrides the indent. +indent_param = 0 # unsigned number + +# How to use tabs when indenting code. +# +# 0: Spaces only +# 1: Indent with tabs to brace level, align with spaces (default) +# 2: Indent and align with tabs, using spaces when not on a tabstop +# +# Default: 1 +indent_with_tabs = 0 # unsigned number + +# Whether to indent comments that are not at a brace level with tabs on a +# tabstop. Requires indent_with_tabs=2. If false, will use spaces. +indent_cmt_with_tabs = false # true/false + +# Whether to indent strings broken by '\' so that they line up. +indent_align_string = false # true/false + +# The number of spaces to indent multi-line XML strings. +# Requires indent_align_string=true. +indent_xml_string = 0 # unsigned number + +# Spaces to indent '{' from level. +indent_brace = 0 # unsigned number + +# Whether braces are indented to the body level. +indent_braces = false # true/false + +# Whether to disable indenting function braces if indent_braces=true. +indent_braces_no_func = false # true/false + +# Whether to disable indenting class braces if indent_braces=true. +indent_braces_no_class = false # true/false + +# Whether to disable indenting struct braces if indent_braces=true. +indent_braces_no_struct = false # true/false + +# Whether to indent based on the size of the brace parent, +# i.e. 'if' => 3 spaces, 'for' => 4 spaces, etc. +indent_brace_parent = false # true/false + +# Whether to indent based on the open parenthesis instead of the open brace +# in '({\n'. +indent_paren_open_brace = false # true/false + +# (C#) Whether to indent the brace of a C# delegate by another level. +indent_cs_delegate_brace = false # true/false + +# (C#) Whether to indent a C# delegate (to handle delegates with no brace) by +# another level. +indent_cs_delegate_body = false # true/false + +# Whether to indent the body of a 'namespace'. +indent_namespace = false # true/false + +# Whether to indent only the first namespace, and not any nested namespaces. +# Requires indent_namespace=true. +indent_namespace_single_indent = false # true/false + +# The number of spaces to indent a namespace block. +# If set to zero, use the value indent_columns +indent_namespace_level = 0 # unsigned number + +# If the body of the namespace is longer than this number, it won't be +# indented. Requires indent_namespace=true. 0 means no limit. +indent_namespace_limit = 0 # unsigned number + +# Whether to indent only in inner namespaces (nested in other namespaces). +# Requires indent_namespace=true. +indent_namespace_inner_only = false # true/false + +# Whether the 'extern "C"' body is indented. +indent_extern = false # true/false + +# Whether the 'class' body is indented. +indent_class = true # true/false + +# Whether to ignore indent for the leading base class colon. +indent_ignore_before_class_colon = false # true/false + +# Additional indent before the leading base class colon. +# Negative values decrease indent down to the first column. +# Requires indent_ignore_before_class_colon=false and a newline break before +# the colon (see pos_class_colon and nl_class_colon) +indent_before_class_colon = 0 # number + +# Whether to indent the stuff after a leading base class colon. +indent_class_colon = false # true/false + +# Whether to indent based on a class colon instead of the stuff after the +# colon. Requires indent_class_colon=true. +indent_class_on_colon = false # true/false + +# Whether to ignore indent for a leading class initializer colon. +indent_ignore_before_constr_colon = false # true/false + +# Whether to indent the stuff after a leading class initializer colon. +indent_constr_colon = false # true/false + +# Virtual indent from the ':' for leading member initializers. +# +# Default: 2 +indent_ctor_init_leading = 2 # unsigned number + +# Virtual indent from the ':' for following member initializers. +# +# Default: 2 +indent_ctor_init_following = 2 # unsigned number + +# Additional indent for constructor initializer list. +# Negative values decrease indent down to the first column. +indent_ctor_init = 0 # number + +# Whether to indent 'if' following 'else' as a new block under the 'else'. +# If false, 'else\nif' is treated as 'else if' for indenting purposes. +indent_else_if = false # true/false + +# Amount to indent variable declarations after a open brace. +# +# <0: Relative +# >=0: Absolute +indent_var_def_blk = 0 # number + +# Whether to indent continued variable declarations instead of aligning. +indent_var_def_cont = false # true/false + +# How to indent continued shift expressions ('<<' and '>>'). +# Set align_left_shift=false when using this. +# 0: Align shift operators instead of indenting them (default) +# 1: Indent by one level +# -1: Preserve original indentation +indent_shift = 0 # number + +# Whether to force indentation of function definitions to start in column 1. +indent_func_def_force_col1 = false # true/false + +# Whether to indent continued function call parameters one indent level, +# rather than aligning parameters under the open parenthesis. +indent_func_call_param = true # true/false + +# Whether to indent continued function definition parameters one indent level, +# rather than aligning parameters under the open parenthesis. +indent_func_def_param = true # true/false + +# for function definitions, only if indent_func_def_param is false +# Allows to align params when appropriate and indent them when not +# behave as if it was true if paren position is more than this value +# if paren position is more than the option value +indent_func_def_param_paren_pos_threshold = 0 # unsigned number + +# Whether to indent continued function call prototype one indent level, +# rather than aligning parameters under the open parenthesis. +indent_func_proto_param = false # true/false + +# Whether to indent continued function call declaration one indent level, +# rather than aligning parameters under the open parenthesis. +indent_func_class_param = false # true/false + +# Whether to indent continued class variable constructors one indent level, +# rather than aligning parameters under the open parenthesis. +indent_func_ctor_var_param = false # true/false + +# Whether to indent continued template parameter list one indent level, +# rather than aligning parameters under the open parenthesis. +indent_template_param = false # true/false + +# Double the indent for indent_func_xxx_param options. +# Use both values of the options indent_columns and indent_param. +indent_func_param_double = false # true/false + +# Indentation column for standalone 'const' qualifier on a function +# prototype. +indent_func_const = 0 # unsigned number + +# Indentation column for standalone 'throw' qualifier on a function +# prototype. +indent_func_throw = 0 # unsigned number + +# How to indent within a macro followed by a brace on the same line +# This allows reducing the indent in macros that have (for example) +# `do { ... } while (0)` blocks bracketing them. +# +# true: add an indent for the brace on the same line as the macro +# false: do not add an indent for the brace on the same line as the macro +# +# Default: true +indent_macro_brace = true # true/false + +# The number of spaces to indent a continued '->' or '.'. +# Usually set to 0, 1, or indent_columns. +indent_member = 0 # unsigned number + +# Whether lines broken at '.' or '->' should be indented by a single indent. +# The indent_member option will not be effective if this is set to true. +indent_member_single = false # true/false + +# Spaces to indent single line ('//') comments on lines before code. +indent_single_line_comments_before = 0 # unsigned number + +# Spaces to indent single line ('//') comments on lines after code. +indent_single_line_comments_after = 0 # unsigned number + +# When opening a paren for a control statement (if, for, while, etc), increase +# the indent level by this value. Negative values decrease the indent level. +indent_sparen_extra = 0 # number + +# Whether to indent trailing single line ('//') comments relative to the code +# instead of trying to keep the same absolute column. +indent_relative_single_line_comments = false # true/false + +# Spaces to indent 'case' from 'switch'. Usually 0 or indent_columns. +# It might be wise to choose the same value for the option indent_case_brace. +indent_switch_case = 2 # unsigned number + +# Spaces to indent the body of a 'switch' before any 'case'. +# Usually the same as indent_columns or indent_switch_case. +indent_switch_body = 0 # unsigned number + +# Whether to ignore indent for '{' following 'case'. +indent_ignore_case_brace = false # true/false + +# Spaces to indent '{' from 'case'. By default, the brace will appear under +# the 'c' in case. Usually set to 0 or indent_columns. Negative values are OK. +# It might be wise to choose the same value for the option indent_switch_case. +indent_case_brace = 0 # number + +# indent 'break' with 'case' from 'switch'. +indent_switch_break_with_case = false # true/false + +# Whether to indent preprocessor statements inside of switch statements. +# +# Default: true +indent_switch_pp = true # true/false + +# Spaces to shift the 'case' line, without affecting any other lines. +# Usually 0. +indent_case_shift = 0 # unsigned number + +# Whether to align comments before 'case' with the 'case'. +# +# Default: true +indent_case_comment = true # true/false + +# Whether to indent comments not found in first column. +# +# Default: true +indent_comment = true # true/false + +# Whether to indent comments found in first column. +indent_col1_comment = true # true/false + +# Whether to indent multi string literal in first column. +indent_col1_multi_string_literal = false # true/false + +# Align comments on adjacent lines that are this many columns apart or less. +# +# Default: 3 +indent_comment_align_thresh = 3 # unsigned number + +# Whether to ignore indent for goto labels. +indent_ignore_label = false # true/false + +# How to indent goto labels. Requires indent_ignore_label=false. +# +# >0: Absolute column where 1 is the leftmost column +# <=0: Subtract from brace indent +# +# Default: 1 +indent_label = 1 # number + +# How to indent access specifiers that are followed by a +# colon. +# +# >0: Absolute column where 1 is the leftmost column +# <=0: Subtract from brace indent +# +# Default: 1 +indent_access_spec = 1 # number + +# Whether to indent the code after an access specifier by one level. +# If true, this option forces 'indent_access_spec=0'. +indent_access_spec_body = false # true/false + +# If an open parenthesis is followed by a newline, whether to indent the next +# line so that it lines up after the open parenthesis (not recommended). +indent_paren_nl = false # true/false + +# How to indent a close parenthesis after a newline. +# +# 0: Indent to body level (default) +# 1: Align under the open parenthesis +# 2: Indent to the brace level +# -1: Preserve original indentation +indent_paren_close = 0 # number + +# Whether to indent the open parenthesis of a function definition, +# if the parenthesis is on its own line. +indent_paren_after_func_def = false # true/false + +# Whether to indent the open parenthesis of a function declaration, +# if the parenthesis is on its own line. +indent_paren_after_func_decl = false # true/false + +# Whether to indent the open parenthesis of a function call, +# if the parenthesis is on its own line. +indent_paren_after_func_call = false # true/false + +# How to indent a comma when inside braces. +# 0: Indent by one level (default) +# 1: Align under the open brace +# -1: Preserve original indentation +indent_comma_brace = 0 # number + +# How to indent a comma when inside parentheses. +# 0: Indent by one level (default) +# 1: Align under the open parenthesis +# -1: Preserve original indentation +indent_comma_paren = 0 # number + +# How to indent a Boolean operator when inside parentheses. +# 0: Indent by one level (default) +# 1: Align under the open parenthesis +# -1: Preserve original indentation +indent_bool_paren = 0 # number + +# Whether to ignore the indentation of a Boolean operator when outside +# parentheses. +indent_ignore_bool = false # true/false + +# Whether to ignore the indentation of an arithmetic operator. +indent_ignore_arith = false # true/false + +# Whether to indent a semicolon when inside a for parenthesis. +# If true, aligns under the open for parenthesis. +indent_semicolon_for_paren = false # true/false + +# Whether to ignore the indentation of a semicolon outside of a 'for' +# statement. +indent_ignore_semicolon = false # true/false + +# Whether to align the first expression to following ones +# if indent_bool_paren=1. +indent_first_bool_expr = false # true/false + +# Whether to align the first expression to following ones +# if indent_semicolon_for_paren=true. +indent_first_for_expr = false # true/false + +# If an open square is followed by a newline, whether to indent the next line +# so that it lines up after the open square (not recommended). +indent_square_nl = false # true/false + +# (ESQL/C) Whether to preserve the relative indent of 'EXEC SQL' bodies. +indent_preserve_sql = false # true/false + +# Whether to ignore the indentation of an assignment operator. +indent_ignore_assign = false # true/false + +# Whether to align continued statements at the '='. If false or if the '=' is +# followed by a newline, the next line is indent one tab. +# +# Default: true +indent_align_assign = false # true/false + +# If true, the indentation of the chunks after a '=' sequence will be set at +# LHS token indentation column before '='. +indent_off_after_assign = false # true/false + +# Whether to align continued statements at the '('. If false or the '(' is +# followed by a newline, the next line indent is one tab. +# +# Default: true +indent_align_paren = true # true/false + +# (OC) Whether to indent Objective-C code inside message selectors. +indent_oc_inside_msg_sel = false # true/false + +# (OC) Whether to indent Objective-C blocks at brace level instead of usual +# rules. +indent_oc_block = false # true/false + +# (OC) Indent for Objective-C blocks in a message relative to the parameter +# name. +# +# =0: Use indent_oc_block rules +# >0: Use specified number of spaces to indent +indent_oc_block_msg = 0 # unsigned number + +# (OC) Minimum indent for subsequent parameters +indent_oc_msg_colon = 0 # unsigned number + +# (OC) Whether to prioritize aligning with initial colon (and stripping spaces +# from lines, if necessary). +# +# Default: true +indent_oc_msg_prioritize_first_colon = true # true/false + +# (OC) Whether to indent blocks the way that Xcode does by default +# (from the keyword if the parameter is on its own line; otherwise, from the +# previous indentation level). Requires indent_oc_block_msg=true. +indent_oc_block_msg_xcode_style = false # true/false + +# (OC) Whether to indent blocks from where the brace is, relative to a +# message keyword. Requires indent_oc_block_msg=true. +indent_oc_block_msg_from_keyword = false # true/false + +# (OC) Whether to indent blocks from where the brace is, relative to a message +# colon. Requires indent_oc_block_msg=true. +indent_oc_block_msg_from_colon = false # true/false + +# (OC) Whether to indent blocks from where the block caret is. +# Requires indent_oc_block_msg=true. +indent_oc_block_msg_from_caret = false # true/false + +# (OC) Whether to indent blocks from where the brace caret is. +# Requires indent_oc_block_msg=true. +indent_oc_block_msg_from_brace = false # true/false + +# When indenting after virtual brace open and newline add further spaces to +# reach this minimum indent. +indent_min_vbrace_open = 0 # unsigned number + +# Whether to add further spaces after regular indent to reach next tabstop +# when indenting after virtual brace open and newline. +indent_vbrace_open_on_tabstop = false # true/false + +# How to indent after a brace followed by another token (not a newline). +# true: indent all contained lines to match the token +# false: indent all contained lines to match the brace +# +# Default: true +indent_token_after_brace = true # true/false + +# Whether to indent the body of a C++11 lambda. +indent_cpp_lambda_body = false # true/false + +# How to indent compound literals that are being returned. +# true: add both the indent from return & the compound literal open brace +# (i.e. 2 indent levels) +# false: only indent 1 level, don't add the indent for the open brace, only +# add the indent for the return. +# +# Default: true +indent_compound_literal_return = true # true/false + +# (C#) Whether to indent a 'using' block if no braces are used. +# +# Default: true +indent_using_block = true # true/false + +# How to indent the continuation of ternary operator. +# +# 0: Off (default) +# 1: When the `if_false` is a continuation, indent it under the `if_true` branch +# 2: When the `:` is a continuation, indent it under `?` +indent_ternary_operator = 0 # unsigned number + +# Whether to indent the statements inside ternary operator. +indent_inside_ternary_operator = false # true/false + +# If true, the indentation of the chunks after a `return` sequence will be set at return indentation column. +indent_off_after_return = false # true/false + +# If true, the indentation of the chunks after a `return new` sequence will be set at return indentation column. +indent_off_after_return_new = false # true/false + +# If true, the tokens after return are indented with regular single indentation. By default (false) the indentation is after the return token. +indent_single_after_return = false # true/false + +# Whether to ignore indent and alignment for 'asm' blocks (i.e. assume they +# have their own indentation). +indent_ignore_asm_block = false # true/false + +# Don't indent the close parenthesis of a function definition, +# if the parenthesis is on its own line. +donot_indent_func_def_close_paren = false # true/false + +# +# Newline adding and removing options +# + +# Whether to collapse empty blocks between '{' and '}' except for functions. +# Use nl_collapse_empty_body_functions to specify how empty function braces +# should be formatted. +nl_collapse_empty_body = false # true/false + +# Whether to collapse empty blocks between '{' and '}' for functions only. +# If true, overrides nl_inside_empty_func. +nl_collapse_empty_body_functions = false # true/false + +# Don't split one-line braced assignments, as in 'foo_t f = { 1, 2 };'. +nl_assign_leave_one_liners = true # true/false + +# Don't split one-line braced statements inside a 'class xx { }' body. +nl_class_leave_one_liners = true # true/false + +# Don't split one-line enums, as in 'enum foo { BAR = 15 };' +nl_enum_leave_one_liners = true # true/false + +# Don't split one-line get or set functions. +nl_getset_leave_one_liners = true # true/false + +# (C#) Don't split one-line property get or set functions. +nl_cs_property_leave_one_liners = false # true/false + +# Don't split one-line function definitions, as in 'int foo() { return 0; }'. +# might modify nl_func_type_name +nl_func_leave_one_liners = true # true/false + +# Don't split one-line C++11 lambdas, as in '[]() { return 0; }'. +nl_cpp_lambda_leave_one_liners = false # true/false + +# Don't split one-line if/else statements, as in 'if(...) b++;'. +nl_if_leave_one_liners = true # true/false + +# Don't split one-line while statements, as in 'while(...) b++;'. +nl_while_leave_one_liners = false # true/false + +# Don't split one-line do statements, as in 'do { b++; } while(...);'. +nl_do_leave_one_liners = true # true/false + +# Don't split one-line for statements, as in 'for(...) b++;'. +nl_for_leave_one_liners = false # true/false + +# (OC) Don't split one-line Objective-C messages. +nl_oc_msg_leave_one_liner = false # true/false + +# (OC) Add or remove newline between method declaration and '{'. +nl_oc_mdef_brace = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove newline between Objective-C block signature and '{'. +nl_oc_block_brace = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove blank line before '@interface' statement. +nl_oc_before_interface = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove blank line before '@implementation' statement. +nl_oc_before_implementation = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove blank line before '@end' statement. +nl_oc_before_end = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove newline between '@interface' and '{'. +nl_oc_interface_brace = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove newline between '@implementation' and '{'. +nl_oc_implementation_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove newlines at the start of the file. +nl_start_of_file = ignore # ignore/add/remove/force/not_defined + +# The minimum number of newlines at the start of the file (only used if +# nl_start_of_file is 'add' or 'force'). +nl_start_of_file_min = 0 # unsigned number + +# Add or remove newline at the end of the file. +nl_end_of_file = add # ignore/add/remove/force/not_defined + +# The minimum number of newlines at the end of the file (only used if +# nl_end_of_file is 'add' or 'force'). +nl_end_of_file_min = 0 # unsigned number + +# Add or remove newline between '=' and '{'. +nl_assign_brace = remove # ignore/add/remove/force/not_defined + +# (D) Add or remove newline between '=' and '['. +nl_assign_square = remove # ignore/add/remove/force/not_defined + +# Add or remove newline between '[]' and '{'. +nl_tsquare_brace = ignore # ignore/add/remove/force/not_defined + +# (D) Add or remove newline after '= ['. Will also affect the newline before +# the ']'. +nl_after_square_assign = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between a function call's ')' and '{', as in +# 'list_for_each(item, &list) { }'. +nl_fcall_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'enum' and '{'. +nl_enum_brace = remove # ignore/add/remove/force/not_defined + +# Add or remove newline between 'enum' and 'class'. +nl_enum_class = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'enum class' and the identifier. +nl_enum_class_identifier = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'enum class' type and ':'. +nl_enum_identifier_colon = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'enum class identifier :' and type. +nl_enum_colon_type = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'struct and '{'. +nl_struct_brace = remove # ignore/add/remove/force/not_defined + +# Add or remove newline between 'union' and '{'. +nl_union_brace = remove # ignore/add/remove/force/not_defined + +# Add or remove newline between 'if' and '{'. +nl_if_brace = remove # ignore/add/remove/force/not_defined + +# Add or remove newline between '}' and 'else'. +nl_brace_else = add # ignore/add/remove/force/not_defined + +# Add or remove newline between 'else if' and '{'. If set to ignore, +# nl_if_brace is used instead. +nl_elseif_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'else' and '{'. +nl_else_brace = remove # ignore/add/remove/force/not_defined + +# Add or remove newline between 'else' and 'if'. +nl_else_if = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline before '{' opening brace +nl_before_opening_brace_func_class_def = remove # ignore/add/remove/force/not_defined + +# Add or remove newline before 'if'/'else if' closing parenthesis. +nl_before_if_closing_paren = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between '}' and 'finally'. +nl_brace_finally = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'finally' and '{'. +nl_finally_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'try' and '{'. +nl_try_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between get/set and '{'. +nl_getset_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'for' and '{'. +nl_for_brace = remove # ignore/add/remove/force/not_defined + +# Add or remove newline before the '{' of a 'catch' statement, as in +# 'catch (decl) {'. +nl_catch_brace = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove newline before the '{' of a '@catch' statement, as in +# '@catch (decl) {'. If set to ignore, nl_catch_brace is used. +nl_oc_catch_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between '}' and 'catch'. +nl_brace_catch = ignore # ignore/add/remove/force/not_defined + +# (OC) Add or remove newline between '}' and '@catch'. If set to ignore, +# nl_brace_catch is used. +nl_oc_brace_catch = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between '}' and ']'. +nl_brace_square = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between '}' and ')' in a function invocation. +nl_brace_fparen = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'while' and '{'. +nl_while_brace = remove # ignore/add/remove/force/not_defined + +# (D) Add or remove newline between 'scope (x)' and '{'. +nl_scope_brace = ignore # ignore/add/remove/force/not_defined + +# (D) Add or remove newline between 'unittest' and '{'. +nl_unittest_brace = ignore # ignore/add/remove/force/not_defined + +# (D) Add or remove newline between 'version (x)' and '{'. +nl_version_brace = ignore # ignore/add/remove/force/not_defined + +# (C#) Add or remove newline between 'using' and '{'. +nl_using_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between two open or close braces. Due to general +# newline/brace handling, REMOVE may not work. +nl_brace_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'do' and '{'. +nl_do_brace = remove # ignore/add/remove/force/not_defined + +# Add or remove newline between '}' and 'while' of 'do' statement. +nl_brace_while = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'switch' and '{'. +nl_switch_brace = remove # ignore/add/remove/force/not_defined + +# Add or remove newline between 'synchronized' and '{'. +nl_synchronized_brace = ignore # ignore/add/remove/force/not_defined + +# Add a newline between ')' and '{' if the ')' is on a different line than the +# if/for/etc. +# +# Overrides nl_for_brace, nl_if_brace, nl_switch_brace, nl_while_switch and +# nl_catch_brace. +nl_multi_line_cond = false # true/false + +# Add a newline after '(' if an if/for/while/switch condition spans multiple +# lines +nl_multi_line_sparen_open = ignore # ignore/add/remove/force/not_defined + +# Add a newline before ')' if an if/for/while/switch condition spans multiple +# lines. Overrides nl_before_if_closing_paren if both are specified. +nl_multi_line_sparen_close = add # ignore/add/remove/force/not_defined + +# Force a newline in a define after the macro name for multi-line defines. +nl_multi_line_define = false # true/false + +# Whether to add a newline before 'case', and a blank line before a 'case' +# statement that follows a ';' or '}'. +nl_before_case = false # true/false + +# Whether to add a newline after a 'case' statement. +nl_after_case = false # true/false + +# Add or remove newline between a case ':' and '{'. +# +# Overrides nl_after_case. +nl_case_colon_brace = remove # ignore/add/remove/force/not_defined + +# Add or remove newline between ')' and 'throw'. +nl_before_throw = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'namespace' and '{'. +nl_namespace_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after 'template<...>' of a template class. +nl_template_class = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after 'template<...>' of a template class declaration. +# +# Overrides nl_template_class. +nl_template_class_decl = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after 'template<>' of a specialized class declaration. +# +# Overrides nl_template_class_decl. +nl_template_class_decl_special = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after 'template<...>' of a template class definition. +# +# Overrides nl_template_class. +nl_template_class_def = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after 'template<>' of a specialized class definition. +# +# Overrides nl_template_class_def. +nl_template_class_def_special = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after 'template<...>' of a template function. +nl_template_func = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after 'template<...>' of a template function +# declaration. +# +# Overrides nl_template_func. +nl_template_func_decl = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after 'template<>' of a specialized function +# declaration. +# +# Overrides nl_template_func_decl. +nl_template_func_decl_special = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after 'template<...>' of a template function +# definition. +# +# Overrides nl_template_func. +nl_template_func_def = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after 'template<>' of a specialized function +# definition. +# +# Overrides nl_template_func_def. +nl_template_func_def_special = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after 'template<...>' of a template variable. +nl_template_var = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'template<...>' and 'using' of a templated +# type alias. +nl_template_using = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'class' and '{'. +nl_class_brace = remove # ignore/add/remove/force/not_defined + +# Add or remove newline before or after (depending on pos_class_comma, +# may not be IGNORE) each',' in the base class list. +nl_class_init_args = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after each ',' in the constructor member +# initialization. Related to nl_constr_colon, pos_constr_colon and +# pos_constr_comma. +nl_constr_init_args = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline before first element, after comma, and after last +# element, in 'enum'. +nl_enum_own_lines = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between return type and function name in a function +# definition. +# might be modified by nl_func_leave_one_liners +nl_func_type_name = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between return type and function name inside a class +# definition. If set to ignore, nl_func_type_name or nl_func_proto_type_name +# is used instead. +nl_func_type_name_class = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between class specification and '::' +# in 'void A::f() { }'. Only appears in separate member implementation (does +# not appear with in-line implementation). +nl_func_class_scope = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between function scope and name, as in +# 'void A :: f() { }'. +nl_func_scope_name = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between return type and function name in a prototype. +nl_func_proto_type_name = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between a function name and the opening '(' in the +# declaration. +nl_func_paren = ignore # ignore/add/remove/force/not_defined + +# Overrides nl_func_paren for functions with no parameters. +nl_func_paren_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between a function name and the opening '(' in the +# definition. +nl_func_def_paren = ignore # ignore/add/remove/force/not_defined + +# Overrides nl_func_def_paren for functions with no parameters. +nl_func_def_paren_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between a function name and the opening '(' in the +# call. +nl_func_call_paren = ignore # ignore/add/remove/force/not_defined + +# Overrides nl_func_call_paren for functions with no parameters. +nl_func_call_paren_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after '(' in a function declaration. +nl_func_decl_start = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after '(' in a function definition. +nl_func_def_start = ignore # ignore/add/remove/force/not_defined + +# Overrides nl_func_decl_start when there is only one parameter. +nl_func_decl_start_single = ignore # ignore/add/remove/force/not_defined + +# Overrides nl_func_def_start when there is only one parameter. +nl_func_def_start_single = ignore # ignore/add/remove/force/not_defined + +# Whether to add a newline after '(' in a function declaration if '(' and ')' +# are in different lines. If false, nl_func_decl_start is used instead. +nl_func_decl_start_multi_line = false # true/false + +# Whether to add a newline after '(' in a function definition if '(' and ')' +# are in different lines. If false, nl_func_def_start is used instead. +nl_func_def_start_multi_line = false # true/false + +# Add or remove newline after each ',' in a function declaration. +nl_func_decl_args = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after each ',' in a function definition. +nl_func_def_args = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline after each ',' in a function call. +nl_func_call_args = ignore # ignore/add/remove/force/not_defined + +# Whether to add a newline after each ',' in a function declaration if '(' +# and ')' are in different lines. If false, nl_func_decl_args is used instead. +nl_func_decl_args_multi_line = false # true/false + +# Whether to add a newline after each ',' in a function definition if '(' +# and ')' are in different lines. If false, nl_func_def_args is used instead. +nl_func_def_args_multi_line = false # true/false + +# Add or remove newline before the ')' in a function declaration. +nl_func_decl_end = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline before the ')' in a function definition. +nl_func_def_end = ignore # ignore/add/remove/force/not_defined + +# Overrides nl_func_decl_end when there is only one parameter. +nl_func_decl_end_single = ignore # ignore/add/remove/force/not_defined + +# Overrides nl_func_def_end when there is only one parameter. +nl_func_def_end_single = ignore # ignore/add/remove/force/not_defined + +# Whether to add a newline before ')' in a function declaration if '(' and ')' +# are in different lines. If false, nl_func_decl_end is used instead. +nl_func_decl_end_multi_line = false # true/false + +# Whether to add a newline before ')' in a function definition if '(' and ')' +# are in different lines. If false, nl_func_def_end is used instead. +nl_func_def_end_multi_line = false # true/false + +# Add or remove newline between '()' in a function declaration. +nl_func_decl_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between '()' in a function definition. +nl_func_def_empty = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between '()' in a function call. +nl_func_call_empty = ignore # ignore/add/remove/force/not_defined + +# Whether to add a newline after '(' in a function call, +# has preference over nl_func_call_start_multi_line. +nl_func_call_start = ignore # ignore/add/remove/force/not_defined + +# Whether to add a newline before ')' in a function call. +nl_func_call_end = ignore # ignore/add/remove/force/not_defined + +# Whether to add a newline after '(' in a function call if '(' and ')' are in +# different lines. +nl_func_call_start_multi_line = false # true/false + +# Whether to add a newline after each ',' in a function call if '(' and ')' +# are in different lines. +nl_func_call_args_multi_line = false # true/false + +# Whether to add a newline before ')' in a function call if '(' and ')' are in +# different lines. +nl_func_call_end_multi_line = false # true/false + +# Whether to respect nl_func_call_XXX option in case of closure args. +nl_func_call_args_multi_line_ignore_closures = false # true/false + +# Whether to add a newline after '<' of a template parameter list. +nl_template_start = false # true/false + +# Whether to add a newline after each ',' in a template parameter list. +nl_template_args = false # true/false + +# Whether to add a newline before '>' of a template parameter list. +nl_template_end = false # true/false + +# (OC) Whether to put each Objective-C message parameter on a separate line. +# See nl_oc_msg_leave_one_liner. +nl_oc_msg_args = false # true/false + +# (OC) Minimum number of Objective-C message parameters before applying nl_oc_msg_args. +nl_oc_msg_args_min_params = 0 # unsigned number + +# (OC) Max code width of Objective-C message before applying nl_oc_msg_args. +nl_oc_msg_args_max_code_width = 0 # unsigned number + +# Add or remove newline between function signature and '{'. +nl_fdef_brace = remove # ignore/add/remove/force/not_defined + +# Add or remove newline between function signature and '{', +# if signature ends with ')'. Overrides nl_fdef_brace. +nl_fdef_brace_cond = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between C++11 lambda signature and '{'. +nl_cpp_ldef_brace = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'return' and the return expression. +nl_return_expr = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline between 'throw' and the throw expression. +nl_throw_expr = ignore # ignore/add/remove/force/not_defined + +# Whether to add a newline after semicolons, except in 'for' statements. +nl_after_semicolon = false # true/false + +# (Java) Add or remove newline between the ')' and '{{' of the double brace +# initializer. +nl_paren_dbrace_open = ignore # ignore/add/remove/force/not_defined + +# Whether to add a newline after the type in an unnamed temporary +# direct-list-initialization, better: +# before a direct-list-initialization. +nl_type_brace_init_lst = ignore # ignore/add/remove/force/not_defined + +# Whether to add a newline after the open brace in an unnamed temporary +# direct-list-initialization. +nl_type_brace_init_lst_open = ignore # ignore/add/remove/force/not_defined + +# Whether to add a newline before the close brace in an unnamed temporary +# direct-list-initialization. +nl_type_brace_init_lst_close = ignore # ignore/add/remove/force/not_defined + +# Whether to add a newline before '{'. +nl_before_brace_open = false # true/false + +# Whether to add a newline after '{'. +nl_after_brace_open = true # true/false + +# Whether to add a newline between the open brace and a trailing single-line +# comment. Requires nl_after_brace_open=true. +nl_after_brace_open_cmt = false # true/false + +# Whether to add a newline after a virtual brace open with a non-empty body. +# These occur in un-braced if/while/do/for statement bodies. +nl_after_vbrace_open = false # true/false + +# Whether to add a newline after a virtual brace open with an empty body. +# These occur in un-braced if/while/do/for statement bodies. +nl_after_vbrace_open_empty = false # true/false + +# Whether to add a newline after '}'. Does not apply if followed by a +# necessary ';'. +nl_after_brace_close = true # true/false + +# Whether to add a newline after a virtual brace close, +# as in 'if (foo) a++; return;'. +nl_after_vbrace_close = false # true/false + +# Add or remove newline between the close brace and identifier, +# as in 'struct { int a; } b;'. Affects enumerations, unions and +# structures. If set to ignore, uses nl_after_brace_close. +nl_brace_struct_var = ignore # ignore/add/remove/force/not_defined + +# Whether to alter newlines in '#define' macros. +nl_define_macro = false # true/false + +# Whether to alter newlines between consecutive parenthesis closes. The number +# of closing parentheses in a line will depend on respective open parenthesis +# lines. +nl_squeeze_paren_close = false # true/false + +# Whether to remove blanks after '#ifxx' and '#elxx', or before '#elxx' and +# '#endif'. Does not affect top-level #ifdefs. +nl_squeeze_ifdef = false # true/false + +# Makes the nl_squeeze_ifdef option affect the top-level #ifdefs as well. +nl_squeeze_ifdef_top_level = false # true/false + +# Add or remove blank line before 'if'. +nl_before_if = ignore # ignore/add/remove/force/not_defined + +# Add or remove blank line after 'if' statement. Add/Force work only if the +# next token is not a closing brace. +nl_after_if = ignore # ignore/add/remove/force/not_defined + +# Add or remove blank line before 'for'. +nl_before_for = ignore # ignore/add/remove/force/not_defined + +# Add or remove blank line after 'for' statement. +nl_after_for = ignore # ignore/add/remove/force/not_defined + +# Add or remove blank line before 'while'. +nl_before_while = ignore # ignore/add/remove/force/not_defined + +# Add or remove blank line after 'while' statement. +nl_after_while = ignore # ignore/add/remove/force/not_defined + +# Add or remove blank line before 'switch'. +nl_before_switch = ignore # ignore/add/remove/force/not_defined + +# Add or remove blank line after 'switch' statement. +nl_after_switch = ignore # ignore/add/remove/force/not_defined + +# Add or remove blank line before 'synchronized'. +nl_before_synchronized = ignore # ignore/add/remove/force/not_defined + +# Add or remove blank line after 'synchronized' statement. +nl_after_synchronized = ignore # ignore/add/remove/force/not_defined + +# Add or remove blank line before 'do'. +nl_before_do = ignore # ignore/add/remove/force/not_defined + +# Add or remove blank line after 'do/while' statement. +nl_after_do = ignore # ignore/add/remove/force/not_defined + +# Ignore nl_before_{if,for,switch,do,synchronized} if the control +# statement is immediately after a case statement. +# if nl_before_{if,for,switch,do} is set to remove, this option +# does nothing. +nl_before_ignore_after_case = false # true/false + +# Whether to put a blank line before 'return' statements, unless after an open +# brace. +nl_before_return = false # true/false + +# Whether to put a blank line after 'return' statements, unless followed by a +# close brace. +nl_after_return = false # true/false + +# Whether to put a blank line before a member '.' or '->' operators. +nl_before_member = ignore # ignore/add/remove/force/not_defined + +# (Java) Whether to put a blank line after a member '.' or '->' operators. +nl_after_member = ignore # ignore/add/remove/force/not_defined + +# Whether to double-space commented-entries in 'struct'/'union'/'enum'. +nl_ds_struct_enum_cmt = false # true/false + +# Whether to force a newline before '}' of a 'struct'/'union'/'enum'. +# (Lower priority than eat_blanks_before_close_brace.) +nl_ds_struct_enum_close_brace = false # true/false + +# Add or remove newline before or after (depending on pos_class_colon) a class +# colon, as in 'class Foo : public Bar'. +nl_class_colon = ignore # ignore/add/remove/force/not_defined + +# Add or remove newline around a class constructor colon. The exact position +# depends on nl_constr_init_args, pos_constr_colon and pos_constr_comma. +nl_constr_colon = ignore # ignore/add/remove/force/not_defined + +# Whether to collapse a two-line namespace, like 'namespace foo\n{ decl; }' +# into a single line. If true, prevents other brace newline rules from turning +# such code into four lines. If true, it also preserves one-liner namespaces. +nl_namespace_two_to_one_liner = false # true/false + +# Whether to remove a newline in simple unbraced if statements, turning them +# into one-liners, as in 'if(b)\n i++;' => 'if(b) i++;'. +nl_create_if_one_liner = false # true/false + +# Whether to remove a newline in simple unbraced for statements, turning them +# into one-liners, as in 'for (...)\n stmt;' => 'for (...) stmt;'. +nl_create_for_one_liner = true # true/false + +# Whether to remove a newline in simple unbraced while statements, turning +# them into one-liners, as in 'while (expr)\n stmt;' => 'while (expr) stmt;'. +nl_create_while_one_liner = true # true/false + +# Whether to collapse a function definition whose body (not counting braces) +# is only one line so that the entire definition (prototype, braces, body) is +# a single line. +nl_create_func_def_one_liner = false # true/false + +# Whether to split one-line simple list definitions into three lines by +# adding newlines, as in 'int a[12] = { 0 };'. +nl_create_list_one_liner = false # true/false + +# Whether to split one-line simple unbraced if statements into two lines by +# adding a newline, as in 'if(b) i++;'. +nl_split_if_one_liner = false # true/false + +# Whether to split one-line simple unbraced for statements into two lines by +# adding a newline, as in 'for (...) stmt;'. +nl_split_for_one_liner = false # true/false + +# Whether to split one-line simple unbraced while statements into two lines by +# adding a newline, as in 'while (expr) stmt;'. +nl_split_while_one_liner = false # true/false + +# Don't add a newline before a cpp-comment in a parameter list of a function +# call. +donot_add_nl_before_cpp_comment = false # true/false + +# +# Blank line options +# + +# The maximum number of consecutive newlines (3 = 2 blank lines). +nl_max = 0 # unsigned number + +# The maximum number of consecutive newlines in a function. +nl_max_blank_in_func = 0 # unsigned number + +# The number of newlines inside an empty function body. +# This option overrides eat_blanks_after_open_brace and +# eat_blanks_before_close_brace, but is ignored when +# nl_collapse_empty_body_functions=true +nl_inside_empty_func = 0 # unsigned number + +# The number of newlines before a function prototype. +nl_before_func_body_proto = 0 # unsigned number + +# The number of newlines before a multi-line function definition. Where +# applicable, this option is overridden with eat_blanks_after_open_brace=true +nl_before_func_body_def = 0 # unsigned number + +# The number of newlines before a class constructor/destructor prototype. +nl_before_func_class_proto = 0 # unsigned number + +# The number of newlines before a class constructor/destructor definition. +nl_before_func_class_def = 0 # unsigned number + +# The number of newlines after a function prototype. +nl_after_func_proto = 0 # unsigned number + +# The number of newlines after a function prototype, if not followed by +# another function prototype. +nl_after_func_proto_group = 0 # unsigned number + +# The number of newlines after a class constructor/destructor prototype. +nl_after_func_class_proto = 0 # unsigned number + +# The number of newlines after a class constructor/destructor prototype, +# if not followed by another constructor/destructor prototype. +nl_after_func_class_proto_group = 0 # unsigned number + +# Whether one-line method definitions inside a class body should be treated +# as if they were prototypes for the purposes of adding newlines. +# +# Requires nl_class_leave_one_liners=true. Overrides nl_before_func_body_def +# and nl_before_func_class_def for one-liners. +nl_class_leave_one_liner_groups = false # true/false + +# The number of newlines after '}' of a multi-line function body. +nl_after_func_body = 0 # unsigned number + +# The number of newlines after '}' of a multi-line function body in a class +# declaration. Also affects class constructors/destructors. +# +# Overrides nl_after_func_body. +nl_after_func_body_class = 0 # unsigned number + +# The number of newlines after '}' of a single line function body. Also +# affects class constructors/destructors. +# +# Overrides nl_after_func_body and nl_after_func_body_class. +nl_after_func_body_one_liner = 0 # unsigned number + +# The number of newlines before a block of typedefs. If nl_after_access_spec +# is non-zero, that option takes precedence. +# +# 0: No change (default). +nl_typedef_blk_start = 0 # unsigned number + +# The number of newlines after a block of typedefs. +# +# 0: No change (default). +nl_typedef_blk_end = 0 # unsigned number + +# The maximum number of consecutive newlines within a block of typedefs. +# +# 0: No change (default). +nl_typedef_blk_in = 0 # unsigned number + +# The minimum number of blank lines after a block of variable definitions +# at the top of a function body. If any preprocessor directives appear +# between the opening brace of the function and the variable block, then +# it is considered as not at the top of the function.Newlines are added +# before trailing preprocessor directives, if any exist. +# +# 0: No change (default). +nl_var_def_blk_end_func_top = 0 # unsigned number + +# The minimum number of empty newlines before a block of variable definitions +# not at the top of a function body. If nl_after_access_spec is non-zero, +# that option takes precedence. Newlines are not added at the top of the +# file or just after an opening brace. Newlines are added above any +# preprocessor directives before the block. +# +# 0: No change (default). +nl_var_def_blk_start = 0 # unsigned number + +# The minimum number of empty newlines after a block of variable definitions +# not at the top of a function body. Newlines are not added if the block +# is at the bottom of the file or just before a preprocessor directive. +# +# 0: No change (default). +nl_var_def_blk_end = 0 # unsigned number + +# The maximum number of consecutive newlines within a block of variable +# definitions. +# +# 0: No change (default). +nl_var_def_blk_in = 0 # unsigned number + +# The minimum number of newlines before a multi-line comment. +# Doesn't apply if after a brace open or another multi-line comment. +nl_before_block_comment = 0 # unsigned number + +# The minimum number of newlines before a single-line C comment. +# Doesn't apply if after a brace open or other single-line C comments. +nl_before_c_comment = 0 # unsigned number + +# The minimum number of newlines before a CPP comment. +# Doesn't apply if after a brace open or other CPP comments. +nl_before_cpp_comment = 0 # unsigned number + +# Whether to force a newline after a multi-line comment. +nl_after_multiline_comment = false # true/false + +# Whether to force a newline after a label's colon. +nl_after_label_colon = false # true/false + +# The number of newlines before a struct definition. +nl_before_struct = 0 # unsigned number + +# The number of newlines after '}' or ';' of a struct/enum/union definition. +nl_after_struct = 0 # unsigned number + +# The number of newlines before a class definition. +nl_before_class = 0 # unsigned number + +# The number of newlines after '}' or ';' of a class definition. +nl_after_class = 2 # unsigned number + +# The number of newlines before a namespace. +nl_before_namespace = 0 # unsigned number + +# The number of newlines after '{' of a namespace. This also adds newlines +# before the matching '}'. +# +# 0: Apply eat_blanks_after_open_brace or eat_blanks_before_close_brace if +# applicable, otherwise no change. +# +# Overrides eat_blanks_after_open_brace and eat_blanks_before_close_brace. +nl_inside_namespace = 0 # unsigned number + +# The number of newlines after '}' of a namespace. +nl_after_namespace = 0 # unsigned number + +# The number of newlines before an access specifier label. This also includes +# the Qt-specific 'signals:' and 'slots:'. Will not change the newline count +# if after a brace open. +# +# 0: No change (default). +nl_before_access_spec = 0 # unsigned number + +# The number of newlines after an access specifier label. This also includes +# the Qt-specific 'signals:' and 'slots:'. Will not change the newline count +# if after a brace open. +# +# 0: No change (default). +# +# Overrides nl_typedef_blk_start and nl_var_def_blk_start. +nl_after_access_spec = 0 # unsigned number + +# The number of newlines between a function definition and the function +# comment, as in '// comment\n void foo() {...}'. +# +# 0: No change (default). +nl_comment_func_def = 0 # unsigned number + +# The number of newlines after a try-catch-finally block that isn't followed +# by a brace close. +# +# 0: No change (default). +nl_after_try_catch_finally = 0 # unsigned number + +# (C#) The number of newlines before and after a property, indexer or event +# declaration. +# +# 0: No change (default). +nl_around_cs_property = 0 # unsigned number + +# (C#) The number of newlines between the get/set/add/remove handlers. +# +# 0: No change (default). +nl_between_get_set = 0 # unsigned number + +# (C#) Add or remove newline between property and the '{'. +nl_property_brace = ignore # ignore/add/remove/force/not_defined + +# Whether to remove blank lines after '{'. +eat_blanks_after_open_brace = false # true/false + +# Whether to remove blank lines before '}'. +eat_blanks_before_close_brace = false # true/false + +# How aggressively to remove extra newlines not in preprocessor. +# +# 0: No change (default) +# 1: Remove most newlines not handled by other config +# 2: Remove all newlines and reformat completely by config +nl_remove_extra_newlines = 0 # unsigned number + +# (Java) Add or remove newline after an annotation statement. Only affects +# annotations that are after a newline. +nl_after_annotation = ignore # ignore/add/remove/force/not_defined + +# (Java) Add or remove newline between two annotations. +nl_between_annotation = ignore # ignore/add/remove/force/not_defined + +# The number of newlines before a whole-file #ifdef. +# +# 0: No change (default). +nl_before_whole_file_ifdef = 0 # unsigned number + +# The number of newlines after a whole-file #ifdef. +# +# 0: No change (default). +nl_after_whole_file_ifdef = 0 # unsigned number + +# The number of newlines before a whole-file #endif. +# +# 0: No change (default). +nl_before_whole_file_endif = 0 # unsigned number + +# The number of newlines after a whole-file #endif. +# +# 0: No change (default). +nl_after_whole_file_endif = 0 # unsigned number + +# +# Positioning options +# + +# The position of arithmetic operators in wrapped expressions. +pos_arith = ignore # ignore/break/force/lead/trail/join/lead_break/lead_force/trail_break/trail_force + +# The position of assignment in wrapped expressions. Do not affect '=' +# followed by '{'. +pos_assign = ignore # ignore/break/force/lead/trail/join/lead_break/lead_force/trail_break/trail_force + +# The position of Boolean operators in wrapped expressions. +pos_bool = ignore # ignore/break/force/lead/trail/join/lead_break/lead_force/trail_break/trail_force + +# The position of comparison operators in wrapped expressions. +pos_compare = ignore # ignore/break/force/lead/trail/join/lead_break/lead_force/trail_break/trail_force + +# The position of conditional operators, as in the '?' and ':' of +# 'expr ? stmt : stmt', in wrapped expressions. +pos_conditional = ignore # ignore/break/force/lead/trail/join/lead_break/lead_force/trail_break/trail_force + +# The position of the comma in wrapped expressions. +pos_comma = ignore # ignore/break/force/lead/trail/join/lead_break/lead_force/trail_break/trail_force + +# The position of the comma in enum entries. +pos_enum_comma = ignore # ignore/break/force/lead/trail/join/lead_break/lead_force/trail_break/trail_force + +# The position of the comma in the base class list if there is more than one +# line. Affects nl_class_init_args. +pos_class_comma = ignore # ignore/break/force/lead/trail/join/lead_break/lead_force/trail_break/trail_force + +# The position of the comma in the constructor initialization list. +# Related to nl_constr_colon, nl_constr_init_args and pos_constr_colon. +pos_constr_comma = ignore # ignore/break/force/lead/trail/join/lead_break/lead_force/trail_break/trail_force + +# The position of trailing/leading class colon, between class and base class +# list. Affects nl_class_colon. +pos_class_colon = ignore # ignore/break/force/lead/trail/join/lead_break/lead_force/trail_break/trail_force + +# The position of colons between constructor and member initialization. +# Related to nl_constr_colon, nl_constr_init_args and pos_constr_comma. +pos_constr_colon = ignore # ignore/break/force/lead/trail/join/lead_break/lead_force/trail_break/trail_force + +# The position of shift operators in wrapped expressions. +pos_shift = ignore # ignore/break/force/lead/trail/join/lead_break/lead_force/trail_break/trail_force + +# +# Line splitting options +# + +# Try to limit code width to N columns. +code_width = 0 # unsigned number + +# Whether to fully split long 'for' statements at semi-colons. +ls_for_split_full = false # true/false + +# Whether to fully split long function prototypes/calls at commas. +# The option ls_code_width has priority over the option ls_func_split_full. +ls_func_split_full = false # true/false + +# Whether to split lines as close to code_width as possible and ignore some +# groupings. +# The option ls_code_width has priority over the option ls_func_split_full. +ls_code_width = false # true/false + +# +# Code alignment options (not left column spaces/tabs) +# + +# Whether to keep non-indenting tabs. +align_keep_tabs = false # true/false + +# Whether to use tabs for aligning. +align_with_tabs = false # true/false + +# Whether to bump out to the next tab when aligning. +align_on_tabstop = false # true/false + +# Whether to right-align numbers. +align_number_right = false # true/false + +# Whether to keep whitespace not required for alignment. +align_keep_extra_space = false # true/false + +# Whether to align variable definitions in prototypes and functions. +align_func_params = false # true/false + +# The span for aligning parameter definitions in function on parameter name. +# +# 0: Don't align (default). +align_func_params_span = 0 # unsigned number + +# The threshold for aligning function parameter definitions. +# Use a negative number for absolute thresholds. +# +# 0: No limit (default). +align_func_params_thresh = 0 # number + +# The gap for aligning function parameter definitions. +align_func_params_gap = 0 # unsigned number + +# The span for aligning constructor value. +# +# 0: Don't align (default). +align_constr_value_span = 0 # unsigned number + +# The threshold for aligning constructor value. +# Use a negative number for absolute thresholds. +# +# 0: No limit (default). +align_constr_value_thresh = 0 # number + +# The gap for aligning constructor value. +align_constr_value_gap = 0 # unsigned number + +# Whether to align parameters in single-line functions that have the same +# name. The function names must already be aligned with each other. +align_same_func_call_params = false # true/false + +# The span for aligning function-call parameters for single line functions. +# +# 0: Don't align (default). +align_same_func_call_params_span = 0 # unsigned number + +# The threshold for aligning function-call parameters for single line +# functions. +# Use a negative number for absolute thresholds. +# +# 0: No limit (default). +align_same_func_call_params_thresh = 0 # number + +# The span for aligning variable definitions. +# +# 0: Don't align (default). +align_var_def_span = 0 # unsigned number + +# How to consider (or treat) the '*' in the alignment of variable definitions. +# +# 0: Part of the type 'void * foo;' (default) +# 1: Part of the variable 'void *foo;' +# 2: Dangling 'void *foo;' +# Dangling: the '*' will not be taken into account when aligning. +align_var_def_star_style = 1 # unsigned number + +# How to consider (or treat) the '&' in the alignment of variable definitions. +# +# 0: Part of the type 'long & foo;' (default) +# 1: Part of the variable 'long &foo;' +# 2: Dangling 'long &foo;' +# Dangling: the '&' will not be taken into account when aligning. +align_var_def_amp_style = 0 # unsigned number + +# The threshold for aligning variable definitions. +# Use a negative number for absolute thresholds. +# +# 0: No limit (default). +align_var_def_thresh = 0 # number + +# The gap for aligning variable definitions. +align_var_def_gap = 0 # unsigned number + +# Whether to align the colon in struct bit fields. +align_var_def_colon = false # true/false + +# The gap for aligning the colon in struct bit fields. +align_var_def_colon_gap = 0 # unsigned number + +# Whether to align any attribute after the variable name. +align_var_def_attribute = false # true/false + +# Whether to align inline struct/enum/union variable definitions. +align_var_def_inline = false # true/false + +# The span for aligning on '=' in assignments. +# +# 0: Don't align (default). +align_assign_span = 0 # unsigned number + +# The span for aligning on '=' in function prototype modifier. +# +# 0: Don't align (default). +align_assign_func_proto_span = 0 # unsigned number + +# The threshold for aligning on '=' in assignments. +# Use a negative number for absolute thresholds. +# +# 0: No limit (default). +align_assign_thresh = 0 # number + +# Whether to align on the left most assignment when multiple +# definitions are found on the same line. +# Depends on 'align_assign_span' and 'align_assign_thresh' settings. +align_assign_on_multi_var_defs = false # true/false + +# The span for aligning on '{' in braced init list. +# +# 0: Don't align (default). +align_braced_init_list_span = 0 # unsigned number + +# The threshold for aligning on '{' in braced init list. +# Use a negative number for absolute thresholds. +# +# 0: No limit (default). +align_braced_init_list_thresh = 0 # number + +# How to apply align_assign_span to function declaration "assignments", i.e. +# 'virtual void foo() = 0' or '~foo() = {default|delete}'. +# +# 0: Align with other assignments (default) +# 1: Align with each other, ignoring regular assignments +# 2: Don't align +align_assign_decl_func = 0 # unsigned number + +# The span for aligning on '=' in enums. +# +# 0: Don't align (default). +align_enum_equ_span = 0 # unsigned number + +# The threshold for aligning on '=' in enums. +# Use a negative number for absolute thresholds. +# +# 0: no limit (default). +align_enum_equ_thresh = 0 # number + +# The span for aligning class member definitions. +# +# 0: Don't align (default). +align_var_class_span = 0 # unsigned number + +# The threshold for aligning class member definitions. +# Use a negative number for absolute thresholds. +# +# 0: No limit (default). +align_var_class_thresh = 0 # number + +# The gap for aligning class member definitions. +align_var_class_gap = 0 # unsigned number + +# The span for aligning struct/union member definitions. +# +# 0: Don't align (default). +align_var_struct_span = 0 # unsigned number + +# The threshold for aligning struct/union member definitions. +# Use a negative number for absolute thresholds. +# +# 0: No limit (default). +align_var_struct_thresh = 0 # number + +# The gap for aligning struct/union member definitions. +align_var_struct_gap = 0 # unsigned number + +# The span for aligning struct initializer values. +# +# 0: Don't align (default). +align_struct_init_span = 0 # unsigned number + +# The span for aligning single-line typedefs. +# +# 0: Don't align (default). +align_typedef_span = 0 # unsigned number + +# The minimum space between the type and the synonym of a typedef. +align_typedef_gap = 0 # unsigned number + +# How to align typedef'd functions with other typedefs. +# +# 0: Don't mix them at all (default) +# 1: Align the open parenthesis with the types +# 2: Align the function type name with the other type names +align_typedef_func = 0 # unsigned number + +# How to consider (or treat) the '*' in the alignment of typedefs. +# +# 0: Part of the typedef type, 'typedef int * pint;' (default) +# 1: Part of type name: 'typedef int *pint;' +# 2: Dangling: 'typedef int *pint;' +# Dangling: the '*' will not be taken into account when aligning. +align_typedef_star_style = 1 # unsigned number + +# How to consider (or treat) the '&' in the alignment of typedefs. +# +# 0: Part of the typedef type, 'typedef int & intref;' (default) +# 1: Part of type name: 'typedef int &intref;' +# 2: Dangling: 'typedef int &intref;' +# Dangling: the '&' will not be taken into account when aligning. +align_typedef_amp_style = 0 # unsigned number + +# The span for aligning comments that end lines. +# +# 0: Don't align (default). +align_right_cmt_span = 0 # unsigned number + +# Minimum number of columns between preceding text and a trailing comment in +# order for the comment to qualify for being aligned. Must be non-zero to have +# an effect. +align_right_cmt_gap = 0 # unsigned number + +# If aligning comments, whether to mix with comments after '}' and #endif with +# less than three spaces before the comment. +align_right_cmt_mix = false # true/false + +# Whether to only align trailing comments that are at the same brace level. +align_right_cmt_same_level = false # true/false + +# Minimum column at which to align trailing comments. Comments which are +# aligned beyond this column, but which can be aligned in a lesser column, +# may be "pulled in". +# +# 0: Ignore (default). +align_right_cmt_at_col = 0 # unsigned number + +# The span for aligning function prototypes. +# +# 0: Don't align (default). +align_func_proto_span = 0 # unsigned number + +# How to consider (or treat) the '*' in the alignment of function prototypes. +# +# 0: Part of the type 'void * foo();' (default) +# 1: Part of the function 'void *foo();' +# 2: Dangling 'void *foo();' +# Dangling: the '*' will not be taken into account when aligning. +align_func_proto_star_style = 0 # unsigned number + +# How to consider (or treat) the '&' in the alignment of function prototypes. +# +# 0: Part of the type 'long & foo();' (default) +# 1: Part of the function 'long &foo();' +# 2: Dangling 'long &foo();' +# Dangling: the '&' will not be taken into account when aligning. +align_func_proto_amp_style = 0 # unsigned number + +# The threshold for aligning function prototypes. +# Use a negative number for absolute thresholds. +# +# 0: No limit (default). +align_func_proto_thresh = 0 # number + +# Minimum gap between the return type and the function name. +align_func_proto_gap = 0 # unsigned number + +# Whether to align function prototypes on the 'operator' keyword instead of +# what follows. +align_on_operator = false # true/false + +# Whether to mix aligning prototype and variable declarations. If true, +# align_var_def_XXX options are used instead of align_func_proto_XXX options. +align_mix_var_proto = false # true/false + +# Whether to align single-line functions with function prototypes. +# Uses align_func_proto_span. +align_single_line_func = false # true/false + +# Whether to align the open brace of single-line functions. +# Requires align_single_line_func=true. Uses align_func_proto_span. +align_single_line_brace = false # true/false + +# Gap for align_single_line_brace. +align_single_line_brace_gap = 0 # unsigned number + +# (OC) The span for aligning Objective-C message specifications. +# +# 0: Don't align (default). +align_oc_msg_spec_span = 0 # unsigned number + +# Whether and how to align backslashes that split a macro onto multiple lines. +# This will not work right if the macro contains a multi-line comment. +# +# 0: Do nothing (default) +# 1: Align the backslashes in the column at the end of the longest line +# 2: Align with the backslash that is farthest to the left, or, if that +# backslash is farther left than the end of the longest line, at the end of +# the longest line +# 3: Align with the backslash that is farthest to the right +align_nl_cont = 0 # unsigned number + +# Whether to align macro functions and variables together. +align_pp_define_together = true # true/false + +# The span for aligning on '#define' bodies. +# +# =0: Don't align (default) +# >0: Number of lines (including comments) between blocks +align_pp_define_span = 0 # unsigned number + +# The minimum space between label and value of a preprocessor define. +align_pp_define_gap = 0 # unsigned number + +# Whether to align lines that start with '<<' with previous '<<'. +# +# Default: true +align_left_shift = true # true/false + +# Whether to align comma-separated statements following '<<' (as used to +# initialize Eigen matrices). +align_eigen_comma_init = false # true/false + +# Whether to align text after 'asm volatile ()' colons. +align_asm_colon = false # true/false + +# (OC) Span for aligning parameters in an Objective-C message call +# on the ':'. +# +# 0: Don't align. +align_oc_msg_colon_span = 0 # unsigned number + +# (OC) Whether to always align with the first parameter, even if it is too +# short. +align_oc_msg_colon_first = false # true/false + +# (OC) Whether to align parameters in an Objective-C '+' or '-' declaration +# on the ':'. +align_oc_decl_colon = false # true/false + +# (OC) Whether to not align parameters in an Objectve-C message call if first +# colon is not on next line of the message call (the same way Xcode does +# alignment) +align_oc_msg_colon_xcode_like = false # true/false + +# +# Comment modification options +# + +# Try to wrap comments at N columns. +cmt_width = 0 # unsigned number + +# How to reflow comments. +# +# 0: No reflowing (apart from the line wrapping due to cmt_width) (default) +# 1: No touching at all +# 2: Full reflow (enable cmt_indent_multi for indent with line wrapping due to cmt_width) +cmt_reflow_mode = 1 # unsigned number + +# Path to a file that contains regular expressions describing patterns for +# which the end of one line and the beginning of the next will be folded into +# the same sentence or paragraph during full comment reflow. The regular +# expressions are described using ECMAScript syntax. The syntax for this +# specification is as follows, where "..." indicates the custom regular +# expression and "n" indicates the nth end_of_prev_line_regex and +# beg_of_next_line_regex regular expression pair: +# +# end_of_prev_line_regex[1] = "...$" +# beg_of_next_line_regex[1] = "^..." +# end_of_prev_line_regex[2] = "...$" +# beg_of_next_line_regex[2] = "^..." +# . +# . +# . +# end_of_prev_line_regex[n] = "...$" +# beg_of_next_line_regex[n] = "^..." +# +# Note that use of this option overrides the default reflow fold regular +# expressions, which are internally defined as follows: +# +# end_of_prev_line_regex[1] = "[\w,\]\)]$" +# beg_of_next_line_regex[1] = "^[\w,\[\(]" +# end_of_prev_line_regex[2] = "\.$" +# beg_of_next_line_regex[2] = "^[A-Z]" +cmt_reflow_fold_regex_file = "" # string + +# Whether to indent wrapped lines to the start of the encompassing paragraph +# during full comment reflow (cmt_reflow_mode = 2). Overrides the value +# specified by cmt_sp_after_star_cont. +# +# Note that cmt_align_doxygen_javadoc_tags overrides this option for +# paragraphs associated with javadoc tags +cmt_reflow_indent_to_paragraph_start = false # true/false + +# Whether to convert all tabs to spaces in comments. If false, tabs in +# comments are left alone, unless used for indenting. +cmt_convert_tab_to_spaces = true # true/false + +# Whether to apply changes to multi-line comments, including cmt_width, +# keyword substitution and leading chars. +# +# Default: true +cmt_indent_multi = false # true/false + +# Whether to align doxygen javadoc-style tags ('@param', '@return', etc.) +# and corresponding fields such that groups of consecutive block tags, +# parameter names, and descriptions align with one another. Overrides that +# which is specified by the cmt_sp_after_star_cont. If cmt_width > 0, it may +# be necessary to enable cmt_indent_multi and set cmt_reflow_mode = 2 +# in order to achieve the desired alignment for line-wrapping. +cmt_align_doxygen_javadoc_tags = false # true/false + +# The number of spaces to insert after the star and before doxygen +# javadoc-style tags (@param, @return, etc). Requires enabling +# cmt_align_doxygen_javadoc_tags. Overrides that which is specified by the +# cmt_sp_after_star_cont. +# +# Default: 1 +cmt_sp_before_doxygen_javadoc_tags = 1 # unsigned number + +# Whether to change trailing, single-line c-comments into cpp-comments. +cmt_trailing_single_line_c_to_cpp = true # true/false + +# Whether to group c-comments that look like they are in a block. +cmt_c_group = false # true/false + +# Whether to put an empty '/*' on the first line of the combined c-comment. +cmt_c_nl_start = true # true/false + +# Whether to add a newline before the closing '*/' of the combined c-comment. +cmt_c_nl_end = false # true/false + +# Whether to change cpp-comments into c-comments. +cmt_cpp_to_c = false # true/false + +# Whether to group cpp-comments that look like they are in a block. Only +# meaningful if cmt_cpp_to_c=true. +cmt_cpp_group = false # true/false + +# Whether to put an empty '/*' on the first line of the combined cpp-comment +# when converting to a c-comment. +# +# Requires cmt_cpp_to_c=true and cmt_cpp_group=true. +cmt_cpp_nl_start = false # true/false + +# Whether to add a newline before the closing '*/' of the combined cpp-comment +# when converting to a c-comment. +# +# Requires cmt_cpp_to_c=true and cmt_cpp_group=true. +cmt_cpp_nl_end = false # true/false + +# Whether to put a star on subsequent comment lines. +cmt_star_cont = true # true/false + +# The number of spaces to insert at the start of subsequent comment lines. +cmt_sp_before_star_cont = 1 # unsigned number + +# The number of spaces to insert after the star on subsequent comment lines. +cmt_sp_after_star_cont = 1 # unsigned number + +# For multi-line comments with a '*' lead, remove leading spaces if the first +# and last lines of the comment are the same length. +# +# Default: true +cmt_multi_check_last = true # true/false + +# For multi-line comments with a '*' lead, remove leading spaces if the first +# and last lines of the comment are the same length AND if the length is +# bigger as the first_len minimum. +# +# Default: 4 +cmt_multi_first_len_minimum = 4 # unsigned number + +# Path to a file that contains text to insert at the beginning of a file if +# the file doesn't start with a C/C++ comment. If the inserted text contains +# '$(filename)', that will be replaced with the current file's name. +cmt_insert_file_header = "./buildroot/share/extras/file_header.h" # string + +# Path to a file that contains text to insert at the end of a file if the +# file doesn't end with a C/C++ comment. If the inserted text contains +# '$(filename)', that will be replaced with the current file's name. +cmt_insert_file_footer = "" # string + +# Path to a file that contains text to insert before a function definition if +# the function isn't preceded by a C/C++ comment. If the inserted text +# contains '$(function)', '$(javaparam)' or '$(fclass)', these will be +# replaced with, respectively, the name of the function, the javadoc '@param' +# and '@return' stuff, or the name of the class to which the member function +# belongs. +cmt_insert_func_header = "" # string + +# Path to a file that contains text to insert before a class if the class +# isn't preceded by a C/C++ comment. If the inserted text contains '$(class)', +# that will be replaced with the class name. +cmt_insert_class_header = "" # string + +# Path to a file that contains text to insert before an Objective-C message +# specification, if the method isn't preceded by a C/C++ comment. If the +# inserted text contains '$(message)' or '$(javaparam)', these will be +# replaced with, respectively, the name of the function, or the javadoc +# '@param' and '@return' stuff. +cmt_insert_oc_msg_header = "" # string + +# Whether a comment should be inserted if a preprocessor is encountered when +# stepping backwards from a function name. +# +# Applies to cmt_insert_oc_msg_header, cmt_insert_func_header and +# cmt_insert_class_header. +cmt_insert_before_preproc = false # true/false + +# Whether a comment should be inserted if a function is declared inline to a +# class definition. +# +# Applies to cmt_insert_func_header. +# +# Default: true +cmt_insert_before_inlines = true # true/false + +# Whether a comment should be inserted if the function is a class constructor +# or destructor. +# +# Applies to cmt_insert_func_header. +cmt_insert_before_ctor_dtor = false # true/false + +# +# Code modifying options (non-whitespace) +# + +# Add or remove braces on a single-line 'do' statement. +mod_full_brace_do = ignore # ignore/add/remove/force/not_defined + +# Add or remove braces on a single-line 'for' statement. +mod_full_brace_for = ignore # ignore/add/remove/force/not_defined + +# (Pawn) Add or remove braces on a single-line function definition. +mod_full_brace_function = ignore # ignore/add/remove/force/not_defined + +# Add or remove braces on a single-line 'if' statement. Braces will not be +# removed if the braced statement contains an 'else'. +mod_full_brace_if = ignore # ignore/add/remove/force/not_defined + +# Whether to enforce that all blocks of an 'if'/'else if'/'else' chain either +# have, or do not have, braces. Overrides mod_full_brace_if. +# +# 0: Don't override mod_full_brace_if +# 1: Add braces to all blocks if any block needs braces and remove braces if +# they can be removed from all blocks +# 2: Add braces to all blocks if any block already has braces, regardless of +# whether it needs them +# 3: Add braces to all blocks if any block needs braces and remove braces if +# they can be removed from all blocks, except if all blocks have braces +# despite none needing them +mod_full_brace_if_chain = 1 # unsigned number + +# Whether to add braces to all blocks of an 'if'/'else if'/'else' chain. +# If true, mod_full_brace_if_chain will only remove braces from an 'if' that +# does not have an 'else if' or 'else'. +mod_full_brace_if_chain_only = false # true/false + +# Add or remove braces on single-line 'while' statement. +mod_full_brace_while = ignore # ignore/add/remove/force/not_defined + +# Add or remove braces on single-line 'using ()' statement. +mod_full_brace_using = ignore # ignore/add/remove/force/not_defined + +# Don't remove braces around statements that span N newlines +mod_full_brace_nl = 0 # unsigned number + +# Whether to prevent removal of braces from 'if'/'for'/'while'/etc. blocks +# which span multiple lines. +# +# Affects: +# mod_full_brace_for +# mod_full_brace_if +# mod_full_brace_if_chain +# mod_full_brace_if_chain_only +# mod_full_brace_while +# mod_full_brace_using +# +# Does not affect: +# mod_full_brace_do +# mod_full_brace_function +mod_full_brace_nl_block_rem_mlcond = false # true/false + +# Add or remove unnecessary parentheses on 'return' statement. +mod_paren_on_return = ignore # ignore/add/remove/force/not_defined + +# Add or remove unnecessary parentheses on 'throw' statement. +mod_paren_on_throw = ignore # ignore/add/remove/force/not_defined + +# (Pawn) Whether to change optional semicolons to real semicolons. +mod_pawn_semicolon = false # true/false + +# Whether to fully parenthesize Boolean expressions in 'while' and 'if' +# statement, as in 'if (a && b > c)' => 'if (a && (b > c))'. +mod_full_paren_if_bool = false # true/false + +# Whether to fully parenthesize Boolean expressions after '=' +# statement, as in 'x = a && b > c;' => 'x = (a && (b > c));'. +mod_full_paren_assign_bool = false # true/false + +# Whether to fully parenthesize Boolean expressions after '=' +# statement, as in 'return a && b > c;' => 'return (a && (b > c));'. +mod_full_paren_return_bool = false # true/false + +# Whether to remove superfluous semicolons. +mod_remove_extra_semicolon = true # true/false + +# Whether to remove duplicate include. +mod_remove_duplicate_include = false # true/false + +# the following options (mod_XX_closebrace_comment) use different comment, +# depending of the setting of the next option. +# false: Use the c comment (default) +# true : Use the cpp comment +mod_add_force_c_closebrace_comment = false # true/false + +# If a function body exceeds the specified number of newlines and doesn't have +# a comment after the close brace, a comment will be added. +mod_add_long_function_closebrace_comment = 0 # unsigned number + +# If a namespace body exceeds the specified number of newlines and doesn't +# have a comment after the close brace, a comment will be added. +mod_add_long_namespace_closebrace_comment = 0 # unsigned number + +# If a class body exceeds the specified number of newlines and doesn't have a +# comment after the close brace, a comment will be added. +mod_add_long_class_closebrace_comment = 0 # unsigned number + +# If a switch body exceeds the specified number of newlines and doesn't have a +# comment after the close brace, a comment will be added. +mod_add_long_switch_closebrace_comment = 0 # unsigned number + +# If an #ifdef body exceeds the specified number of newlines and doesn't have +# a comment after the #endif, a comment will be added. +mod_add_long_ifdef_endif_comment = 20 # unsigned number + +# If an #ifdef or #else body exceeds the specified number of newlines and +# doesn't have a comment after the #else, a comment will be added. +mod_add_long_ifdef_else_comment = 20 # unsigned number + +# Whether to take care of the case by the mod_sort_xx options. +mod_sort_case_sensitive = false # true/false + +# Whether to sort consecutive single-line 'import' statements. +mod_sort_import = false # true/false + +# (C#) Whether to sort consecutive single-line 'using' statements. +mod_sort_using = false # true/false + +# Whether to sort consecutive single-line '#include' statements (C/C++) and +# '#import' statements (Objective-C). Be aware that this has the potential to +# break your code if your includes/imports have ordering dependencies. +mod_sort_include = false # true/false + +# Whether to prioritize '#include' and '#import' statements that contain +# filename without extension when sorting is enabled. +mod_sort_incl_import_prioritize_filename = false # true/false + +# Whether to prioritize '#include' and '#import' statements that does not +# contain extensions when sorting is enabled. +mod_sort_incl_import_prioritize_extensionless = false # true/false + +# Whether to prioritize '#include' and '#import' statements that contain +# angle over quotes when sorting is enabled. +mod_sort_incl_import_prioritize_angle_over_quotes = false # true/false + +# Whether to ignore file extension in '#include' and '#import' statements +# for sorting comparison. +mod_sort_incl_import_ignore_extension = false # true/false + +# Whether to group '#include' and '#import' statements when sorting is enabled. +mod_sort_incl_import_grouping_enabled = false # true/false + +# Whether to move a 'break' that appears after a fully braced 'case' before +# the close brace, as in 'case X: { ... } break;' => 'case X: { ... break; }'. +mod_move_case_break = false # true/false + +# Whether to move a 'return' that appears after a fully braced 'case' before +# the close brace, as in 'case X: { ... } return;' => 'case X: { ... return; }'. +mod_move_case_return = false # true/false + +# Add or remove braces around a fully braced case statement. Will only remove +# braces if there are no variable declarations in the block. +mod_case_brace = ignore # ignore/add/remove/force/not_defined + +# Whether to remove a void 'return;' that appears as the last statement in a +# function. +mod_remove_empty_return = false # true/false + +# Add or remove the comma after the last value of an enumeration. +mod_enum_last_comma = ignore # ignore/add/remove/force/not_defined + +# Syntax to use for infinite loops. +# +# 0: Leave syntax alone (default) +# 1: Rewrite as `for(;;)` +# 2: Rewrite as `while(true)` +# 3: Rewrite as `do`...`while(true);` +# 4: Rewrite as `while(1)` +# 5: Rewrite as `do`...`while(1);` +# +# Infinite loops that do not already match one of these syntaxes are ignored. +# Other options that affect loop formatting will be applied after transforming +# the syntax. +mod_infinite_loop = 0 # unsigned number + +# Add or remove the 'int' keyword in 'int short'. +mod_int_short = ignore # ignore/add/remove/force/not_defined + +# Add or remove the 'int' keyword in 'short int'. +mod_short_int = ignore # ignore/add/remove/force/not_defined + +# Add or remove the 'int' keyword in 'int long'. +mod_int_long = ignore # ignore/add/remove/force/not_defined + +# Add or remove the 'int' keyword in 'long int'. +mod_long_int = ignore # ignore/add/remove/force/not_defined + +# Add or remove the 'int' keyword in 'int signed'. +mod_int_signed = ignore # ignore/add/remove/force/not_defined + +# Add or remove the 'int' keyword in 'signed int'. +mod_signed_int = ignore # ignore/add/remove/force/not_defined + +# Add or remove the 'int' keyword in 'int unsigned'. +mod_int_unsigned = ignore # ignore/add/remove/force/not_defined + +# Add or remove the 'int' keyword in 'unsigned int'. +mod_unsigned_int = ignore # ignore/add/remove/force/not_defined + +# If there is a situation where mod_int_* and mod_*_int would result in +# multiple int keywords, whether to keep the rightmost int (the default) or the +# leftmost int. +mod_int_prefer_int_on_left = false # true/false + +# (OC) Whether to organize the properties. If true, properties will be +# rearranged according to the mod_sort_oc_property_*_weight factors. +mod_sort_oc_properties = false # true/false + +# (OC) Weight of a class property modifier. +mod_sort_oc_property_class_weight = 0 # number + +# (OC) Weight of 'atomic' and 'nonatomic'. +mod_sort_oc_property_thread_safe_weight = 0 # number + +# (OC) Weight of 'readwrite' when organizing properties. +mod_sort_oc_property_readwrite_weight = 0 # number + +# (OC) Weight of a reference type specifier ('retain', 'copy', 'assign', +# 'weak', 'strong') when organizing properties. +mod_sort_oc_property_reference_weight = 0 # number + +# (OC) Weight of getter type ('getter=') when organizing properties. +mod_sort_oc_property_getter_weight = 0 # number + +# (OC) Weight of setter type ('setter=') when organizing properties. +mod_sort_oc_property_setter_weight = 0 # number + +# (OC) Weight of nullability type ('nullable', 'nonnull', 'null_unspecified', +# 'null_resettable') when organizing properties. +mod_sort_oc_property_nullability_weight = 0 # number + +# +# Preprocessor options +# + +# How to use tabs when indenting preprocessor code. +# +# -1: Use 'indent_with_tabs' setting (default) +# 0: Spaces only +# 1: Indent with tabs to brace level, align with spaces +# 2: Indent and align with tabs, using spaces when not on a tabstop +# +# Default: -1 +pp_indent_with_tabs = -1 # number + +# Add or remove indentation of preprocessor directives inside #if blocks +# at brace level 0 (file-level). +pp_indent = add # ignore/add/remove/force/not_defined + +# Whether to indent #if/#else/#endif at the brace level. If false, these are +# indented from column 1. +pp_indent_at_level = true # true/false + +# Whether to indent #if/#else/#endif at the parenthesis level if the brace +# level is 0. If false, these are indented from column 1. +pp_indent_at_level0 = false # true/false + +# Specifies the number of columns to indent preprocessors per level +# at brace level 0 (file-level). If pp_indent_at_level=false, also specifies +# the number of columns to indent preprocessors per level +# at brace level > 0 (function-level). +# +# Default: 1 +pp_indent_count = 2 # unsigned number + +# Add or remove space after # based on pp level of #if blocks. +pp_space_after = ignore # ignore/add/remove/force/not_defined + +# Sets the number of spaces per level added with pp_space_after. +pp_space_count = 0 # unsigned number + +# The indent for '#region' and '#endregion' in C# and '#pragma region' in +# C/C++. Negative values decrease indent down to the first column. +pp_indent_region = 0 # number + +# Whether to indent the code between #region and #endregion. +pp_region_indent_code = false # true/false + +# If pp_indent_at_level=true, sets the indent for #if, #else and #endif when +# not at file-level. Negative values decrease indent down to the first column. +# +# =0: Indent preprocessors using output_tab_size +# >0: Column at which all preprocessors will be indented +pp_indent_if = 0 # number + +# Whether to indent the code between #if, #else and #endif. +pp_if_indent_code = true # true/false + +# Whether to indent the body of an #if that encompasses all the code in the file. +pp_indent_in_guard = false # true/false + +# Whether to indent '#define' at the brace level. If false, these are +# indented from column 1. +pp_define_at_level = true # true/false + +# Whether to indent '#include' at the brace level. +pp_include_at_level = false # true/false + +# Whether to ignore the '#define' body while formatting. +pp_ignore_define_body = false # true/false + +# An offset value that controls the indentation of the body of a multiline #define. +# 'body' refers to all the lines of a multiline #define except the first line. +# Requires 'pp_ignore_define_body = false'. +# +# <0: Absolute column: the body indentation starts off at the specified column +# (ex. -3 ==> the body is indented starting from column 3) +# >=0: Relative to the column of the '#' of '#define' +# (ex. 3 ==> the body is indented starting 3 columns at the right of '#') +# +# Default: 8 +pp_multiline_define_body_indent = 8 # number + +# Whether to indent case statements between #if, #else, and #endif. +# Only applies to the indent of the preprocessor that the case statements +# directly inside of. +# +# Default: true +pp_indent_case = true # true/false + +# Whether to indent whole function definitions between #if, #else, and #endif. +# Only applies to the indent of the preprocessor that the function definition +# is directly inside of. +# +# Default: true +pp_indent_func_def = true # true/false + +# Whether to indent extern C blocks between #if, #else, and #endif. +# Only applies to the indent of the preprocessor that the extern block is +# directly inside of. +# +# Default: true +pp_indent_extern = true # true/false + +# How to indent braces directly inside #if, #else, and #endif. +# Requires pp_if_indent_code=true and only applies to the indent of the +# preprocessor that the braces are directly inside of. +# 0: No extra indent +# 1: Indent by one level +# -1: Preserve original indentation +# +# Default: 1 +pp_indent_brace = 1 # number + +# Whether to print warning messages for unbalanced #if and #else blocks. +# This will print a message in the following cases: +# - if an #ifdef block ends on a different indent level than +# where it started from. Example: +# +# #ifdef TEST +# int i; +# { +# int j; +# #endif +# +# - an #elif/#else block ends on a different indent level than +# the corresponding #ifdef block. Example: +# +# #ifdef TEST +# int i; +# #else +# } +# int j; +# #endif +pp_warn_unbalanced_if = false # true/false + +# +# Sort includes options +# + +# The regex for include category with priority 0. +include_category_0 = "" # string + +# The regex for include category with priority 1. +include_category_1 = "" # string + +# The regex for include category with priority 2. +include_category_2 = "" # string + +# +# Use or Do not Use options +# + +# true: indent_func_call_param will be used (default) +# false: indent_func_call_param will NOT be used +# +# Default: true +use_indent_func_call_param = true # true/false + +# The value of the indentation for a continuation line is calculated +# differently if the statement is: +# - a declaration: your case with QString fileName ... +# - an assignment: your case with pSettings = new QSettings( ... +# +# At the second case the indentation value might be used twice: +# - at the assignment +# - at the function call (if present) +# +# To prevent the double use of the indentation value, use this option with the +# value 'true'. +# +# true: indent_continue will be used only once +# false: indent_continue will be used every time (default) +# +# Requires indent_ignore_first_continue=false. +use_indent_continue_only_once = false # true/false + +# The indentation can be: +# - after the assignment, at the '[' character +# - at the beginning of the lambda body +# +# true: indentation will be at the beginning of the lambda body +# false: indentation will be after the assignment (default) +indent_cpp_lambda_only_once = false # true/false + +# Whether sp_after_angle takes precedence over sp_inside_fparen. This was the +# historic behavior, but is probably not the desired behavior, so this is off +# by default. +use_sp_after_angle_always = false # true/false + +# Whether to apply special formatting for Qt SIGNAL/SLOT macros. Essentially, +# this tries to format these so that they match Qt's normalized form (i.e. the +# result of QMetaObject::normalizedSignature), which can slightly improve the +# performance of the QObject::connect call, rather than how they would +# otherwise be formatted. +# +# See options_for_QT.cpp for details. +# +# Default: true +use_options_overriding_for_qt_macros = true # true/false + +# If true: the form feed character is removed from the list of whitespace +# characters. See https://en.cppreference.com/w/cpp/string/byte/isspace. +use_form_feed_no_more_as_whitespace_character = false # true/false + +# +# Warn levels - 1: error, 2: warning (default), 3: note +# + +# (C#) Warning is given if doing tab-to-\t replacement and we have found one +# in a C# verbatim string literal. +# +# Default: 2 +warn_level_tabs_found_in_verbatim_string_literals = 2 # unsigned number + +# Limit the number of loops. +# Used by uncrustify.cpp to exit from infinite loop. +# 0: no limit. +debug_max_number_of_loops = 0 # number + +# Set the number of the line to protocol; +# Used in the function prot_the_line if the 2. parameter is zero. +# 0: nothing protocol. +debug_line_number_to_protocol = 0 # number + +# Set the number of second(s) before terminating formatting the current file, +# 0: no timeout. +# only for linux +debug_timeout = 0 # number + +# Set the number of characters to be printed if the text is too long, +# 0: do not truncate. +debug_truncate = 0 # unsigned number + +# sort (or not) the tracking info. +# +# Default: true +debug_sort_the_tracks = true # true/false + +# decode (or not) the flags as a new line. +# only if the -p option is set. +debug_decode_the_flags = false # true/false + +# insert the number of the line at the beginning of each line +set_numbering_for_html_output = false # true/false + +# Meaning of the settings: +# Ignore - do not do any changes +# Add - makes sure there is 1 or more space/brace/newline/etc +# Force - makes sure there is exactly 1 space/brace/newline/etc, +# behaves like Add in some contexts +# Remove - removes space/brace/newline/etc +# +# +# - Token(s) can be treated as specific type(s) with the 'set' option: +# `set tokenType tokenString [tokenString...]` +# +# Example: +# `set BOOL __AND__ __OR__` +# +# tokenTypes are defined in src/token_enum.h, use them without the +# 'CT_' prefix: 'CT_BOOL' => 'BOOL' +# +# +# - Token(s) can be treated as type(s) with the 'type' option. +# `type tokenString [tokenString...]` +# +# Example: +# `type int c_uint_8 Rectangle` +# +# This can also be achieved with `set TYPE int c_uint_8 Rectangle` +# +# +# To embed whitespace in tokenStrings use the '\' escape character, or quote +# the tokenStrings. These quotes are supported: "'` +# +# +# - Support for the auto detection of languages through the file ending can be +# added using the 'file_ext' command. +# `file_ext langType langString [langString..]` +# +# Example: +# `file_ext CPP .ch .cxx .cpp.in` +# +# langTypes are defined in uncrusify_types.h in the lang_flag_e enum, use +# them without the 'LANG_' prefix: 'LANG_CPP' => 'CPP' +# +# +# - Custom macro-based indentation can be set up using 'macro-open', +# 'macro-else' and 'macro-close'. +# `(macro-open | macro-else | macro-close) tokenString` +# +# Example: +# `macro-open BEGIN_TEMPLATE_MESSAGE_MAP` +# `macro-open BEGIN_MESSAGE_MAP` +# `macro-close END_MESSAGE_MAP` +# +# +# option(s) with 'not default' value: 0 +# diff --git a/buildroot/share/git/mfconfig b/buildroot/share/git/mfconfig index 852885944621..0c4a0de5c8b6 100755 --- a/buildroot/share/git/mfconfig +++ b/buildroot/share/git/mfconfig @@ -144,7 +144,7 @@ if [[ $ACTION == "init" ]]; then find config -name "Conf*.h" -print0 | while read -d $'\0' fn ; do fldr=$(dirname "$fn") blank_line=$(awk '/^\s*$/ {print NR; exit}' "$fn") - $SED -i~ "${blank_line}i\\\n#define CONFIG_EXAMPLES_DIR \"$fldr\"\\ " "$fn" + $SED -i~ "${blank_line}i\\\n#define CONFIG_EXAMPLES_DIR \"$fldr\"" "$fn" rm -f "$fn~" done } diff --git a/buildroot/share/git/mfhelp b/buildroot/share/git/mfhelp index 1afc4c686b81..46a0ebfc5333 100755 --- a/buildroot/share/git/mfhelp +++ b/buildroot/share/git/mfhelp @@ -8,7 +8,7 @@ Marlin Firmware Commands: firstpush ... Push and set-upstream the current branch to 'origin' ghpc ........ Push the current branch to its upstream branch - ghtp ........ Set the transfer protolcol for all your remotes + ghtp ........ Set the transfer protocol for all your remotes mfadd ....... Fetch a remote branch from any Marlin fork mfclean ..... Attempt to clean up merged and deleted branches mfdoc ....... Build the website, serve locally, and browse @@ -25,4 +25,22 @@ Marlin Firmware Commands: Enter [command] --help for more information. +Build / Test Commands: + + mftest ............... Run a platform test locally with PlatformIO + build_all_examples ... Build all configurations of a branch, stop on error + +Modify Configuration.h / Configuration_adv.h: + + opt_add .............. Add a configuration option (to the top of Configuration.h) + opt_disable .......... Disable a configuration option (modifies ) + opt_enable ........... Enable a configuration option + opt_set .............. Set the value of a configuration option + use_example_configs .. Download configs from a remote branch on GitHub + +Modify pins files: + + pins_set ............. Set the value of a pin in a pins file + pinsformat.js ........ Node.js script to format pins files + THIS diff --git a/buildroot/share/pixmaps/logo/marlin-240x250.png b/buildroot/share/pixmaps/logo/marlin-240x250.png new file mode 100644 index 000000000000..2a6b69230681 Binary files /dev/null and b/buildroot/share/pixmaps/logo/marlin-240x250.png differ diff --git a/buildroot/share/scripts/MarlinBinaryProtocol.py b/buildroot/share/scripts/MarlinBinaryProtocol.py index ecf9df35e2f5..6d902dbeeb0b 100644 --- a/buildroot/share/scripts/MarlinBinaryProtocol.py +++ b/buildroot/share/scripts/MarlinBinaryProtocol.py @@ -11,11 +11,14 @@ import datetime import random try: - import heatshrink + import heatshrink2 as heatshrink heatshrink_exists = True except ImportError: - heatshrink_exists = False - + try: + import heatshrink + heatshrink_exists = True + except ImportError: + heatshrink_exists = False def millis(): return time.perf_counter() * 1000 @@ -72,7 +75,7 @@ def __init__(self, device, baud, bsize, simerr, timeout): self.device = device self.baud = baud self.block_size = int(bsize) - self.simulate_errors = max(min(simerr, 1.0), 0.0); + self.simulate_errors = max(min(simerr, 1.0), 0.0) self.connected = True self.response_timeout = timeout @@ -234,8 +237,8 @@ def build_packet(self, protocol, packet_type, data = bytearray()): # checksum 16 fletchers def checksum(self, cs, value): - cs_low = (((cs & 0xFF) + value) % 255); - return ((((cs >> 8) + cs_low) % 255) << 8) | cs_low; + cs_low = (((cs & 0xFF) + value) % 255) + return ((((cs >> 8) + cs_low) % 255) << 8) | cs_low def build_checksum(self, buffer): cs = 0 @@ -267,7 +270,7 @@ def disconnect(self): def response_ok(self, data): try: - packet_id = int(data); + packet_id = int(data) except ValueError: return if packet_id != self.sync: @@ -276,7 +279,7 @@ def response_ok(self, data): self.packet_status = 1 def response_resend(self, data): - packet_id = int(data); + packet_id = int(data) self.errors += 1 if not self.syncronised: print("Retrying syncronisation") @@ -327,7 +330,7 @@ def await_response(self, timeout = None): return self.responses.popleft() def connect(self): - self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.QUERY); + self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.QUERY) token, data = self.await_response() if token != 'PFT:version:': @@ -349,7 +352,7 @@ def open(self, filename, compression, dummy): timeout = TimeOut(5000) token = None - self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.OPEN, payload); + 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) @@ -360,7 +363,7 @@ def open(self, filename, compression, dummy): print("Broken transfer detected, purging") self.abort() time.sleep(0.1) - self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.OPEN, payload); + self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.OPEN, payload) timeout.reset() elif token == 'PFT:fail': raise Exception("Can not open file on client") @@ -369,10 +372,10 @@ def open(self, filename, compression, dummy): raise ReadTimeout() def write(self, data): - self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.WRITE, data); + self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.WRITE, data) def close(self): - self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.CLOSE); + self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.CLOSE) token, data = self.await_response(1000) if token == 'PFT:success': print("File closed") @@ -385,7 +388,7 @@ def close(self): return False def abort(self): - self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.ABORT); + self.protocol.send(FileTransferProtocol.protocol_id, FileTransferProtocol.Packet.ABORT) token, data = self.await_response() if token == 'PFT:success': print("Transfer Aborted") @@ -393,18 +396,19 @@ def abort(self): def copy(self, filename, dest_filename, compression, dummy): self.connect() - compression_support = heatshrink_exists and self.compression['algorithm'] == 'heatshrink' and compression - if compression and (not heatshrink_exists or not self.compression['algorithm'] == 'heatshrink'): - print("Compression not supported by client") - #compression_support = False + has_heatshrink = heatshrink_exists and self.compression['algorithm'] == 'heatshrink' + if compression and not has_heatshrink: + hs = '2' if sys.version_info[0] > 2 else '' + print("Compression not supported by client. Use 'pip install heatshrink%s' to fix." % hs) + compression = False data = open(filename, "rb").read() filesize = len(data) - self.open(dest_filename, compression_support, dummy) + self.open(dest_filename, compression, dummy) block_size = self.protocol.block_size - if compression_support: + if compression: data = heatshrink.encode(data, window_sz2=self.compression['window'], lookahead_sz2=self.compression['lookahead']) cratio = filesize / len(data) @@ -419,17 +423,17 @@ def copy(self, filename, dest_filename, compression, dummy): self.write(data[start:end]) kibs = (( (i+1) * block_size) / 1024) / (millis() + 1 - start_time) * 1000 if (i / blocks) >= dump_pctg: - print("\r{0:2.0f}% {1:4.2f}KiB/s {2} Errors: {3}".format((i / blocks) * 100, kibs, "[{0:4.2f}KiB/s]".format(kibs * cratio) if compression_support else "", self.protocol.errors), end='') + print("\r{0:2.0f}% {1:4.2f}KiB/s {2} Errors: {3}".format((i / blocks) * 100, kibs, "[{0:4.2f}KiB/s]".format(kibs * cratio) if compression else "", self.protocol.errors), end='') dump_pctg += 0.1 if self.protocol.errors > 0: # Dump last status (errors may not be visible) - print("\r{0:2.0f}% {1:4.2f}KiB/s {2} Errors: {3} - Aborting...".format((i / blocks) * 100, kibs, "[{0:4.2f}KiB/s]".format(kibs * cratio) if compression_support else "", self.protocol.errors), end='') + print("\r{0:2.0f}% {1:4.2f}KiB/s {2} Errors: {3} - Aborting...".format((i / blocks) * 100, kibs, "[{0:4.2f}KiB/s]".format(kibs * cratio) if compression else "", self.protocol.errors), end='') print("") # New line to break the transfer speed line self.close() print("Transfer aborted due to protocol errors") #raise Exception("Transfer aborted due to protocol errors") - return False; - print("\r{0:2.0f}% {1:4.2f}KiB/s {2} Errors: {3}".format(100, kibs, "[{0:4.2f}KiB/s]".format(kibs * cratio) if compression_support else "", self.protocol.errors)) # no one likes transfers finishing at 99.8% + return False + print("\r{0:2.0f}% {1:4.2f}KiB/s {2} Errors: {3}".format(100, kibs, "[{0:4.2f}KiB/s]".format(kibs * cratio) if compression else "", self.protocol.errors)) # no one likes transfers finishing at 99.8% if not self.close(): print("Transfer failed") diff --git a/buildroot/share/scripts/__init__.py b/buildroot/share/scripts/__init__.py new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/buildroot/share/scripts/findMissingTranslations.sh b/buildroot/share/scripts/findMissingTranslations.sh index 24a2a910a21c..366075d5b969 100755 --- a/buildroot/share/scripts/findMissingTranslations.sh +++ b/buildroot/share/scripts/findMissingTranslations.sh @@ -9,6 +9,29 @@ # If no language codes are specified then all languages will be checked # +langname() { + case "$1" in + an ) echo "Aragonese" ;; bg ) echo "Bulgarian" ;; + ca ) echo "Catalan" ;; cz ) echo "Czech" ;; + da ) echo "Danish" ;; de ) echo "German" ;; + el ) echo "Greek" ;; el_CY ) echo "Greek (Cyprus)" ;; + el_gr) echo "Greek (Greece)" ;; en ) echo "English" ;; + es ) echo "Spanish" ;; eu ) echo "Basque-Euskera" ;; + fi ) echo "Finnish" ;; fr ) echo "French" ;; + fr_na) echo "French (no accent)" ;; gl ) echo "Galician" ;; + hr ) echo "Croatian (Hrvatski)" ;; hu ) echo "Hungarian / Magyar" ;; + it ) echo "Italian" ;; jp_kana) echo "Japanese (Kana)" ;; + ko_KR) echo "Korean" ;; nl ) echo "Dutch" ;; + pl ) echo "Polish" ;; pt ) echo "Portuguese" ;; + pt_br) echo "Portuguese (Brazil)" ;; ro ) echo "Romanian" ;; + ru ) echo "Russian" ;; sk ) echo "Slovak" ;; + sv ) echo "Swedish" ;; tr ) echo "Turkish" ;; + uk ) echo "Ukrainian" ;; vi ) echo "Vietnamese" ;; + zh_CN) echo "Simplified Chinese" ;; zh_TW ) echo "Traditional Chinese" ;; + * ) echo "" ;; + esac +} + LANGHOME="Marlin/src/lcd/language" [ -d $LANGHOME ] && cd $LANGHOME @@ -20,7 +43,7 @@ TEST_LANGS="" if [[ -n $@ ]]; then for K in "$@"; do for F in $FILES; do - [[ "$F" != "${F%$K*}" ]] && TEST_LANGS+="$F " + [[ $F == $K ]] && TEST_LANGS+="$F " done done [[ -z $TEST_LANGS ]] && { echo "No languages matching $@." ; exit 0 ; } @@ -28,20 +51,54 @@ else TEST_LANGS=$FILES fi -echo "Missing strings for $TEST_LANGS..." +echo "Finding all missing strings for $TEST_LANGS..." + +WORD_LINES=() # Complete lines for all words (or, grep out of en at the end instead) +ALL_MISSING=() # All missing languages for each missing word +#NEED_WORDS=() # All missing words across all specified languages + +WORD_COUNT=0 +# Go through all strings in the English language file +# For each word, query all specified languages for the word +# If the word is missing, add its language to the list for WORD in $(awk '/LSTR/{print $2}' language_en.h); do + # Skip MSG_MARLIN [[ $WORD == "MSG_MARLIN" ]] && break - LANG_LIST="" + + ((WORD_COUNT++)) + + # Find all selected languages that lack the string + LANG_MISSING=" " for LANG in $TEST_LANGS; do if [[ $(grep -c -E "^ *LSTR +$WORD\b" language_${LANG}.h) -eq 0 ]]; then INHERIT=$(awk '/using namespace/{print $3}' language_${LANG}.h | sed -E 's/Language_([a-zA-Z_]+)\s*;/\1/') if [[ -z $INHERIT || $INHERIT == "en" ]]; then - LANG_LIST+=" $LANG" + LANG_MISSING+="$LANG " elif [[ $(grep -c -E "^ *LSTR +$WORD\b" language_${INHERIT}.h) -eq 0 ]]; then - LANG_LIST+=" $LANG" + LANG_MISSING+="$LANG " fi fi done - [[ -n $LANG_LIST ]] && printf "%-38s :%s\n" "$WORD" "$LANG_LIST" + # For each word store all the missing languages + if [[ $LANG_MISSING != " " ]]; then + WORD_LINES+=("$(grep -m 1 -E "$WORD\b" language_en.h)") + ALL_MISSING+=("$LANG_MISSING") + #NEED_WORDS+=($WORD) + fi +done + +echo +echo "${#WORD_LINES[@]} out of $WORD_COUNT LCD strings need translation" + +for LANG in $TEST_LANGS; do + HED=0 ; IND=0 + for WORDLANGS in "${ALL_MISSING[@]}"; do + # If the current word is missing from the current language then print it + if [[ $WORDLANGS =~ " $LANG " ]]; then + [[ $HED == 0 ]] && { echo ; echo "Missing strings for language_$LANG.h ($(langname $LANG)):" ; HED=1 ; } + echo "${WORD_LINES[$IND]}" + fi + ((IND++)) + done done diff --git a/buildroot/share/scripts/languageExport.py b/buildroot/share/scripts/languageExport.py new file mode 100755 index 000000000000..46485aa1241c --- /dev/null +++ b/buildroot/share/scripts/languageExport.py @@ -0,0 +1,153 @@ +#!/usr/bin/env python3 +''' +languageExport.py + +Export LCD language strings to CSV files for easier translation. +Use importTranslations.py to import CSV into the language files. + +''' + +import re +from pathlib import Path +from languageUtil import namebyid + +LANGHOME = "Marlin/src/lcd/language" + +# Write multiple sheets if true, otherwise write one giant sheet +MULTISHEET = True +OUTDIR = 'out-csv' + +# Check for the path to the language files +if not Path(LANGHOME).is_dir(): + print("Error: Couldn't find the '%s' directory." % LANGHOME) + print("Edit LANGHOME or cd to the root of the repo before running.") + exit(1) + +# A limit just for testing +LIMIT = 0 + +# A dictionary to contain strings for each language. +# Init with 'en' so English will always be first. +language_strings = { 'en': 0 } + +# A dictionary to contain all distinct LCD string names +names = {} + +# Get all "language_*.h" files +langfiles = sorted(list(Path(LANGHOME).glob('language_*.h'))) + +# Read each language file +for langfile in langfiles: + # Get the language code from the filename + langcode = langfile.name.replace('language_', '').replace('.h', '') + + # Skip 'test' and any others that we don't want + if langcode in ['test']: continue + + # Open the file + f = open(langfile, 'r', encoding='utf-8') + if not f: continue + + # Flags to indicate a wide or tall section + wideflag, tallflag = False, False + # A counter for the number of strings in the file + stringcount = 0 + # A dictionary to hold all the strings + strings = { 'narrow': {}, 'wide': {}, 'tall': {} } + # Read each line in the file + for line in f: + # Clean up the line for easier parsing + line = line.split("//")[0].strip() + if line.endswith(';'): line = line[:-1].strip() + + # Check for wide or tall sections, assume no complicated nesting + if line.startswith("#endif") or line.startswith("#else"): + wideflag, tallflag = False, False + elif re.match(r'#if.*WIDTH\s*>=?\s*2[01].*', line): wideflag = True + elif re.match(r'#if.*LCD_HEIGHT\s*>=?\s*4.*', line): tallflag = True + + # For string-defining lines capture the string data + match = re.match(r'LSTR\s+([A-Z0-9_]+)\s*=\s*(.+)\s*', line) + if match: + # Name and quote-sanitized value + name, value = match.group(1), match.group(2).replace('\\"', '$$$') + + # Remove all _UxGT wrappers from the value in a non-greedy way + value = re.sub(r'_UxGT\((".*?")\)', r'\1', value) + + # Multi-line strings get one or more bars | for identification + multiline = 0 + multimatch = re.match(r'.*MSG_(\d)_LINE\s*\(\s*(.+?)\s*\).*', value) + if multimatch: + multiline = int(multimatch.group(1)) + value = '|' + re.sub(r'"\s*,\s*"', '|', multimatch.group(2)) + + # Wrap inline defines in parentheses + value = re.sub(r' *([A-Z0-9]+_[A-Z0-9_]+) *', r'(\1)', value) + # Remove quotes around strings + value = re.sub(r'"(.*?)"', r'\1', value).replace('$$$', '""') + # Store all unique names as dictionary keys + names[name] = 1 + # Store the string as narrow or wide + strings['tall' if tallflag else 'wide' if wideflag else 'narrow'][name] = value + + # Increment the string counter + stringcount += 1 + # Break for testing + if LIMIT and stringcount >= LIMIT: break + + # Close the file + f.close() + # Store the array in the dict + language_strings[langcode] = strings + +# Get the language codes from the dictionary +langcodes = list(language_strings.keys()) + +# Print the array +#print(language_strings) + +# Report the total number of unique strings +print("Found %s distinct LCD strings." % len(names)) + +# Write a single language entry to the CSV file with narrow, wide, and tall strings +def write_csv_lang(f, strings, name): + f.write(',') + if name in strings['narrow']: f.write('"%s"' % strings['narrow'][name]) + f.write(',') + if name in strings['wide']: f.write('"%s"' % strings['wide'][name]) + f.write(',') + if name in strings['tall']: f.write('"%s"' % strings['tall'][name]) + +if MULTISHEET: + # + # Export a separate sheet for each language + # + Path.mkdir(Path(OUTDIR), exist_ok=True) + + for lang in langcodes: + with open("%s/language_%s.csv" % (OUTDIR, lang), 'w', encoding='utf-8') as f: + lname = lang + ' ' + namebyid(lang) + header = ['name', lname, lname + ' (wide)', lname + ' (tall)'] + f.write('"' + '","'.join(header) + '"\n') + + for name in names.keys(): + f.write('"' + name + '"') + write_csv_lang(f, language_strings[lang], name) + f.write('\n') + +else: + # + # Export one large sheet containing all languages + # + with open("languages.csv", 'w', encoding='utf-8') as f: + header = ['name'] + for lang in langcodes: + lname = lang + ' ' + namebyid(lang) + header += [lname, lname + ' (wide)', lname + ' (tall)'] + f.write('"' + '","'.join(header) + '"\n') + + for name in names.keys(): + f.write('"' + name + '"') + for lang in langcodes: write_csv_lang(f, language_strings[lang], name) + f.write('\n') diff --git a/buildroot/share/scripts/languageImport.py b/buildroot/share/scripts/languageImport.py new file mode 100755 index 000000000000..a535040ad085 --- /dev/null +++ b/buildroot/share/scripts/languageImport.py @@ -0,0 +1,219 @@ +#!/usr/bin/env python3 +""" +languageImport.py + +Import LCD language strings from a CSV file or Google Sheets +and write Marlin LCD language files based on the data. + +Use languageExport.py to export CSV from the language files. + +Google Sheets Link: +https://docs.google.com/spreadsheets/d/12yiy-kS84ajKFm7oQIrC4CF8ZWeu9pAR4zrgxH4ruk4/edit#gid=84528699 + +TODO: Use the defines and comments above the namespace from existing language files. + Get the 'constexpr uint8_t CHARSIZE' from existing language files. + Get the correct 'using namespace' for languages that don't inherit from English. + +""" + +import sys, re, requests, csv, datetime +from languageUtil import namebyid + +LANGHOME = "Marlin/src/lcd/language" +OUTDIR = 'out-language' + +# Get the file path from the command line +FILEPATH = sys.argv[1] if len(sys.argv) > 1 else None + +download = FILEPATH == 'download' + +if not FILEPATH or download: + SHEETID = "12yiy-kS84ajKFm7oQIrC4CF8ZWeu9pAR4zrgxH4ruk4" + FILEPATH = 'https://docs.google.com/spreadsheet/ccc?key=%s&output=csv' % SHEETID + +if FILEPATH.startswith('http'): + response = requests.get(FILEPATH) + assert response.status_code == 200, 'GET failed for %s' % FILEPATH + csvdata = response.content.decode('utf-8') +else: + if not FILEPATH.endswith('.csv'): FILEPATH += '.csv' + with open(FILEPATH, 'r', encoding='utf-8') as f: csvdata = f.read() + +if not csvdata: + print("Error: couldn't read CSV data from %s" % FILEPATH) + exit(1) + +if download: + DLNAME = sys.argv[2] if len(sys.argv) > 2 else 'languages.csv' + if not DLNAME.endswith('.csv'): DLNAME += '.csv' + with open(DLNAME, 'w', encoding='utf-8') as f: f.write(csvdata) + print("Downloaded %s from %s" % (DLNAME, FILEPATH)) + exit(0) + +lines = csvdata.splitlines() +print(lines) +reader = csv.reader(lines, delimiter=',') +gothead = False +columns = [''] +numcols = 0 +strings_per_lang = {} +for row in reader: + if not gothead: + gothead = True + numcols = len(row) + if row[0] != 'name': + print('Error: first column should be "name"') + exit(1) + # The rest of the columns are language codes and names + for i in range(1, numcols): + elms = row[i].split(' ') + lang = elms[0] + style = ('Wide' if elms[-1] == '(wide)' else 'Tall' if elms[-1] == '(tall)' else 'Narrow') + columns.append({ 'lang': lang, 'style': style }) + if not lang in strings_per_lang: strings_per_lang[lang] = {} + if not style in strings_per_lang[lang]: strings_per_lang[lang][style] = {} + continue + # Add the named string for all the included languages + name = row[0] + for i in range(1, numcols): + str = row[i] + if str: + col = columns[i] + strings_per_lang[col['lang']][col['style']][name] = str + +# Create a folder for the imported language outfiles +from pathlib import Path +Path.mkdir(Path(OUTDIR), exist_ok=True) + +FILEHEADER = ''' +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 + +/** + * %s + * + * LCD Menu Messages + * See also https://marlinfw.org/docs/development/lcd_language.html + * + * Substitutions are applied for the following characters when used in menu items titles: + * + * $ displays an inserted string + * { displays '0'....'10' for indexes 0 - 10 + * ~ displays '1'....'11' for indexes 0 - 10 + * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) + * @ displays an axis name such as XYZUVW, or E for an extruder + */ + +''' + +# Iterate over the languages which correspond to the columns +# The columns are assumed to be grouped by language in the order Narrow, Wide, Tall +# TODO: Go through lang only, then impose the order Narrow, Wide, Tall. +# So if something is missing or out of order everything still gets built correctly. + +f = None +gotlang = {} +for i in range(1, numcols): + #if i > 6: break # Testing + col = columns[i] + lang, style = col['lang'], col['style'] + + # If we haven't already opened a file for this language, do so now + if not lang in gotlang: + gotlang[lang] = {} + if f: f.close() + fn = "%s/language_%s.h" % (OUTDIR, lang) + f = open(fn, 'w', encoding='utf-8') + if not f: + print("Failed to open %s." % fn) + exit(1) + + # Write the opening header for the new language file + #f.write(FILEHEADER % namebyid(lang)) + f.write('/**\n * Imported from %s on %s at %s\n */\n' % (FILEPATH, datetime.date.today(), datetime.datetime.now().strftime("%H:%M:%S"))) + + # Start a namespace for the language and style + f.write('\nnamespace Language%s_%s {\n' % (style, lang)) + + # Wide and tall namespaces inherit from the others + if style == 'Wide': + f.write(' using namespace LanguageNarrow_%s;\n' % lang) + f.write(' #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2\n') + elif style == 'Tall': + f.write(' using namespace LanguageWide_%s;\n' % lang) + f.write(' #if LCD_HEIGHT >= 4\n') + elif lang != 'en': + f.write(' using namespace Language_en; // Inherit undefined strings from English\n') + + # Formatting for the lines + indent = ' ' if style == 'Narrow' else ' ' + width = 34 if style == 'Narrow' else 32 + lstr_fmt = '%sLSTR %%-%ds = %%s;%%s\n' % (indent, width) + + # Emit all the strings for this language and style + for name in strings_per_lang[lang][style].keys(): + # Get the raw string value + val = strings_per_lang[lang][style][name] + # Count the number of bars + if val.startswith('|'): + bars = val.count('|') + val = val[1:] + else: + bars = 0 + # Escape backslashes, substitute quotes, and wrap in _UxGT("...") + val = '_UxGT("%s")' % val.replace('\\', '\\\\').replace('"', '$$$') + # Move named references outside of the macro + val = re.sub(r'\(([A-Z0-9]+_[A-Z0-9_]+)\)', r'") \1 _UxGT("', val) + # Remove all empty _UxGT("") that result from the above + val = re.sub(r'\s*_UxGT\(""\)\s*', '', val) + # No wrapper needed for just spaces + val = re.sub(r'_UxGT\((" +")\)', r'\1', val) + # Multi-line strings start with a bar... + if bars: + # Wrap the string in MSG_#_LINE(...) and split on bars + val = re.sub(r'^_UxGT\((.+)\)', r'_UxGT(MSG_%s_LINE(\1))' % bars, val) + val = val.replace('|', '", "') + # Restore quotes inside the string + val = val.replace('$$$', '\\"') + # Add a comment with the English string for reference + comm = '' + if lang != 'en' and 'en' in strings_per_lang: + en = strings_per_lang['en'] + if name in en[style]: str = en[style][name] + elif name in en['Narrow']: str = en['Narrow'][name] + if str: + cfmt = '%%%ss// %%s' % (50 - len(val) if len(val) < 50 else 1) + comm = cfmt % (' ', str) + + # Write out the string definition + f.write(lstr_fmt % (name, val, comm)) + + if style == 'Wide' or style == 'Tall': f.write(' #endif\n') + + f.write('}\n') # End namespace + + # Assume the 'Tall' namespace comes last + if style == 'Tall': f.write('\nnamespace Language_%s {\n using namespace LanguageTall_%s;\n}\n' % (lang, lang)) + +# Close the last-opened output file +if f: f.close() diff --git a/buildroot/share/scripts/languageUtil.py b/buildroot/share/scripts/languageUtil.py new file mode 100755 index 000000000000..789561e7b9a4 --- /dev/null +++ b/buildroot/share/scripts/languageUtil.py @@ -0,0 +1,41 @@ +#!/usr/bin/env python3 +# +# marlang.py +# + +# A dictionary to contain language names +LANGNAME = { + 'an': "Aragonese", + 'bg': "Bulgarian", + 'ca': "Catalan", + 'cz': "Czech", + 'da': "Danish", + 'de': "German", + 'el': "Greek", 'el_CY': "Greek (Cyprus)", 'el_gr': "Greek (Greece)", + 'en': "English", + 'es': "Spanish", + 'eu': "Basque-Euskera", + 'fi': "Finnish", + 'fr': "French", 'fr_na': "French (no accent)", + 'gl': "Galician", + 'hr': "Croatian (Hrvatski)", + 'hu': "Hungarian / Magyar", + 'it': "Italian", + 'jp_kana': "Japanese (Kana)", + 'ko_KR': "Korean", + 'nl': "Dutch", + 'pl': "Polish", + 'pt': "Portuguese", 'pt_br': "Portuguese (Brazil)", + 'ro': "Romanian", + 'ru': "Russian", + 'sk': "Slovak", + 'sv': "Swedish", + 'tr': "Turkish", + 'uk': "Ukrainian", + 'vi': "Vietnamese", + 'zh_CN': "Simplified Chinese", 'zh_TW': "Traditional Chinese" +} + +def namebyid(id): + if id in LANGNAME: return LANGNAME[id] + return '' diff --git a/buildroot/share/scripts/pinsformat.js b/buildroot/share/scripts/pinsformat.js index 1ce0d75d9a14..16e9dcb88f08 100755 --- a/buildroot/share/scripts/pinsformat.js +++ b/buildroot/share/scripts/pinsformat.js @@ -10,6 +10,11 @@ const fs = require("fs"); +var do_log = false +function logmsg(msg, line='') { + if (do_log) console.log(msg, line); +} + // String lpad / rpad String.prototype.lpad = function(len, chr) { if (!len) return this; @@ -27,8 +32,17 @@ String.prototype.rpad = function(len, chr) { return s; }; +// Concatenate a string, adding a space if necessary +// to avoid merging two words +String.prototype.concat_with_space = function(str) { + const c = this.substr(-1), d = str.charAt(0); + if (c !== ' ' && c !== '' && d !== ' ' && d !== '') + str = ' ' + str; + return this + str; +}; + const mpatt = [ '-?\\d{1,3}', 'P[A-I]\\d+', 'P\\d_\\d+', 'Pin[A-Z]\\d\\b' ], - definePatt = new RegExp(`^\\s*(//)?#define\\s+[A-Z_][A-Z0-9_]+\\s+(${mpatt[0]}|${mpatt[1]}|${mpatt[2]}|${mpatt[3]})\\s*(//.*)?$`, 'gm'), + definePatt = new RegExp(`^\\s*(//)?#define\\s+[A-Z_][A-Z0-9_]+\\s+(${mpatt.join('|')})\\s*(//.*)?$`, 'gm'), ppad = [ 3, 4, 5, 5 ], col_comment = 50, col_value_rj = col_comment - 3; @@ -38,11 +52,11 @@ for (let m of mpatt) mexpr.push(new RegExp('^' + m + '$')); const argv = process.argv.slice(2), argc = argv.length; -var src_file = 0, src_name = 'STDIN', dst_file, do_log = false; +var src_file = 0, dst_file; if (argc > 0) { let ind = 0; if (argv[0] == '-v') { do_log = true; ind++; } - dst_file = src_file = src_name = argv[ind++]; + dst_file = src_file = argv[ind++]; if (ind < argc) dst_file = argv[ind]; } @@ -56,6 +70,7 @@ else // Find the pin pattern so non-pin defines can be skipped function get_pin_pattern(txt) { var r, m = 0, match_count = [ 0, 0, 0, 0 ]; + var max_match_count = 0, max_match_index = -1; definePatt.lastIndex = 0; while ((r = definePatt.exec(txt)) !== null) { let ind = -1; @@ -65,12 +80,15 @@ function get_pin_pattern(txt) { return r[2].match(p); }) ) { const m = ++match_count[ind]; - if (m >= 5) { - return { match: mpatt[ind], pad:ppad[ind] }; + if (m > max_match_count) { + max_match_count = m; + max_match_index = ind; } } } - return null; + if (max_match_index === -1) return null; + + return { match:mpatt[max_match_index], pad:ppad[max_match_index] }; } function process_text(txt) { @@ -79,13 +97,14 @@ function process_text(txt) { if (!patt) return txt; const pindefPatt = new RegExp(`^(\\s*(//)?#define)\\s+([A-Z_][A-Z0-9_]+)\\s+(${patt.match})\\s*(//.*)?$`), noPinPatt = new RegExp(`^(\\s*(//)?#define)\\s+([A-Z_][A-Z0-9_]+)\\s+(-1)\\s*(//.*)?$`), - skipPatt1 = new RegExp('^(\\s*(//)?#define)\\s+(AT90USB|USBCON|(BOARD|DAC|FLASH|HAS|IS|USE)_.+|.+_(ADDRESS|AVAILABLE|BAUDRATE|CLOCK|CONNECTION|DEFAULT|FREQ|ITEM|MODULE|NAME|ONLY|PERIOD|RANGE|RATE|SERIAL|SIZE|SPI|STATE|STEP|TIMER))\\s+(.+)\\s*(//.*)?$'), + skipPatt1 = new RegExp('^(\\s*(//)?#define)\\s+(AT90USB|USBCON|(BOARD|DAC|FLASH|HAS|IS|USE)_.+|.+_(ADDRESS|AVAILABLE|BAUDRATE|CLOCK|CONNECTION|DEFAULT|ERROR|EXTRUDERS|FREQ|ITEM|MKS_BASE_VERSION|MODULE|NAME|ONLY|ORIENTATION|PERIOD|RANGE|RATE|READ_RETRIES|SERIAL|SIZE|SPI|STATE|STEP|TIMER|VERSION))\\s+(.+)\\s*(//.*)?$'), skipPatt2 = new RegExp('^(\\s*(//)?#define)\\s+([A-Z_][A-Z0-9_]+)\\s+(0x[0-9A-Fa-f]+|\d+|.+[a-z].+)\\s*(//.*)?$'), + skipPatt3 = /^\s*#e(lse|ndif)\b.*$/, aliasPatt = new RegExp('^(\\s*(//)?#define)\\s+([A-Z_][A-Z0-9_]+)\\s+([A-Z_][A-Z0-9_()]+)\\s*(//.*)?$'), switchPatt = new RegExp('^(\\s*(//)?#define)\\s+([A-Z_][A-Z0-9_]+)\\s*(//.*)?$'), undefPatt = new RegExp('^(\\s*(//)?#undef)\\s+([A-Z_][A-Z0-9_]+)\\s*(//.*)?$'), defPatt = new RegExp('^(\\s*(//)?#define)\\s+([A-Z_][A-Z0-9_]+)\\s+([-_\\w]+)\\s*(//.*)?$'), - condPatt = new RegExp('^(\\s*(//)?#(if|ifn?def|else|elif)(\\s+\\S+)*)\\s+(//.*)$'), + condPatt = new RegExp('^(\\s*(//)?#(if|ifn?def|elif)(\\s+\\S+)*)\\s+(//.*)$'), commPatt = new RegExp('^\\s{20,}(//.*)?$'); const col_value_lj = col_comment - patt.pad - 2; var r, out = '', check_comment_next = false; @@ -101,74 +120,75 @@ function process_text(txt) { // // #define SKIP_ME // - if (do_log) console.log("skip:", line); + logmsg("skip:", line); } else if ((r = pindefPatt.exec(line)) !== null) { // // #define MY_PIN [pin] // - if (do_log) console.log("pin:", line); + logmsg("pin:", line); const pinnum = r[4].charAt(0) == 'P' ? r[4] : r[4].lpad(patt.pad); line = r[1] + ' ' + r[3]; - line = line.rpad(col_value_lj) + pinnum; - if (r[5]) line = line.rpad(col_comment) + r[5]; + line = line.rpad(col_value_lj).concat_with_space(pinnum); + if (r[5]) line = line.rpad(col_comment).concat_with_space(r[5]); } else if ((r = noPinPatt.exec(line)) !== null) { // // #define MY_PIN -1 // - if (do_log) console.log("pin -1:", line); + logmsg("pin -1:", line); line = r[1] + ' ' + r[3]; - line = line.rpad(col_value_lj) + '-1'; - if (r[5]) line = line.rpad(col_comment) + r[5]; + line = line.rpad(col_value_lj).concat_with_space('-1'); + if (r[5]) line = line.rpad(col_comment).concat_with_space(r[5]); } - else if (skipPatt2.exec(line) !== null) { + else if (skipPatt2.exec(line) !== null || skipPatt3.exec(line) !== null) { // // #define SKIP_ME + // #else, #endif // - if (do_log) console.log("skip:", line); + logmsg("skip:", line); } else if ((r = aliasPatt.exec(line)) !== null) { // // #define ALIAS OTHER // - if (do_log) console.log("alias:", line); + logmsg("alias:", line); line = r[1] + ' ' + r[3]; - line += r[4].lpad(col_value_rj + 1 - line.length); - if (r[5]) line = line.rpad(col_comment) + r[5]; + line = line.concat_with_space(r[4].lpad(col_value_rj + 1 - line.length)); + if (r[5]) line = line.rpad(col_comment).concat_with_space(r[5]); } else if ((r = switchPatt.exec(line)) !== null) { // // #define SWITCH // - if (do_log) console.log("switch:", line); + logmsg("switch:", line); line = r[1] + ' ' + r[3]; - if (r[4]) line = line.rpad(col_comment) + r[4]; + if (r[4]) line = line.rpad(col_comment).concat_with_space(r[4]); check_comment_next = true; } else if ((r = defPatt.exec(line)) !== null) { // // #define ... // - if (do_log) console.log("def:", line); + logmsg("def:", line); line = r[1] + ' ' + r[3] + ' '; - line += r[4].lpad(col_value_rj + 1 - line.length); + line = line.concat_with_space(r[4].lpad(col_value_rj + 1 - line.length)); if (r[5]) line = line.rpad(col_comment - 1) + ' ' + r[5]; } else if ((r = undefPatt.exec(line)) !== null) { // // #undef ... // - if (do_log) console.log("undef:", line); + logmsg("undef:", line); line = r[1] + ' ' + r[3]; - if (r[4]) line = line.rpad(col_comment) + r[4]; + if (r[4]) line = line.rpad(col_comment).concat_with_space(r[4]); } else if ((r = condPatt.exec(line)) !== null) { // - // #if ... + // #if, #ifdef, #ifndef, #elif ... // - if (do_log) console.log("cond:", line); - line = r[1].rpad(col_comment) + r[5]; + logmsg("cond:", line); + line = r[1].rpad(col_comment).concat_with_space(r[5]); check_comment_next = true; } out += line + '\n'; diff --git a/buildroot/share/scripts/pinsformat.py b/buildroot/share/scripts/pinsformat.py new file mode 100755 index 000000000000..b49ae4931d09 --- /dev/null +++ b/buildroot/share/scripts/pinsformat.py @@ -0,0 +1,272 @@ +#!/usr/bin/env python3 + +# +# Formatter script for pins_MYPINS.h files +# +# Usage: pinsformat.py [infile] [outfile] +# +# With no parameters convert STDIN to STDOUT +# + +import sys, re + +do_log = False +def logmsg(msg, line): + if do_log: print(msg, line) + +col_comment = 50 + +# String lpad / rpad +def lpad(astr, fill, c=' '): + if not fill: return astr + need = fill - len(astr) + return astr if need <= 0 else (need * c) + astr + +def rpad(astr, fill, c=' '): + if not fill: return astr + need = fill - len(astr) + return astr if need <= 0 else astr + (need * c) + +# Pin patterns +mpatt = [ r'-?\d{1,3}', r'P[A-I]\d+', r'P\d_\d+', r'Pin[A-Z]\d\b' ] +mstr = '|'.join(mpatt) +mexpr = [ re.compile(f'^{m}$') for m in mpatt ] + +# Corrsponding padding for each pattern +ppad = [ 3, 4, 5, 5 ] + +# Match a define line +definePatt = re.compile(rf'^\s*(//)?#define\s+[A-Z_][A-Z0-9_]+\s+({mstr})\s*(//.*)?$') + +def format_pins(argv): + src_file = 'stdin' + dst_file = None + + scnt = 0 + for arg in argv: + if arg == '-v': + do_log = True + elif scnt == 0: + # Get a source file if specified. Default destination is the same file + src_file = dst_file = arg + scnt += 1 + elif scnt == 1: + # Get destination file if specified + dst_file = arg + scnt += 1 + + # No text to process yet + file_text = '' + + if src_file == 'stdin': + # If no source file specified read from STDIN + file_text = sys.stdin.read() + else: + # Open and read the file src_file + with open(src_file, 'r') as rf: file_text = rf.read() + + if len(file_text) == 0: + print('No text to process') + return + + # Read from file or STDIN until it terminates + filtered = process_text(file_text) + if dst_file: + with open(dst_file, 'w') as wf: wf.write(filtered) + else: + print(filtered) + +# Find the pin pattern so non-pin defines can be skipped +def get_pin_pattern(txt): + r = '' + m = 0 + match_count = [ 0, 0, 0, 0 ] + + # Find the most common matching pattern + match_threshold = 5 + for line in txt.split('\n'): + r = definePatt.match(line) + if r == None: continue + ind = -1 + for p in mexpr: + ind += 1 + if not p.match(r[2]): continue + match_count[ind] += 1 + if match_count[ind] >= match_threshold: + return { 'match': mpatt[ind], 'pad':ppad[ind] } + return None + +def process_text(txt): + if len(txt) == 0: return '(no text)' + patt = get_pin_pattern(txt) + if patt == None: return txt + + pmatch = patt['match'] + pindefPatt = re.compile(rf'^(\s*(//)?#define)\s+([A-Z_][A-Z0-9_]+)\s+({pmatch})\s*(//.*)?$') + noPinPatt = re.compile(r'^(\s*(//)?#define)\s+([A-Z_][A-Z0-9_]+)\s+(-1)\s*(//.*)?$') + skipPatt1 = re.compile(r'^(\s*(//)?#define)\s+(AT90USB|USBCON|(BOARD|DAC|FLASH|HAS|IS|USE)_.+|.+_(ADDRESS|AVAILABLE|BAUDRATE|CLOCK|CONNECTION|DEFAULT|ERROR|EXTRUDERS|FREQ|ITEM|MKS_BASE_VERSION|MODULE|NAME|ONLY|ORIENTATION|PERIOD|RANGE|RATE|READ_RETRIES|SERIAL|SIZE|SPI|STATE|STEP|TIMER|VERSION))\s+(.+)\s*(//.*)?$') + skipPatt2 = re.compile(r'^(\s*(//)?#define)\s+([A-Z_][A-Z0-9_]+)\s+(0x[0-9A-Fa-f]+|\d+|.+[a-z].+)\s*(//.*)?$') + skipPatt3 = re.compile(r'^\s*#e(lse|ndif)\b.*$') + aliasPatt = re.compile(r'^(\s*(//)?#define)\s+([A-Z_][A-Z0-9_]+)\s+([A-Z_][A-Z0-9_()]+)\s*(//.*)?$') + switchPatt = re.compile(r'^(\s*(//)?#define)\s+([A-Z_][A-Z0-9_]+)\s*(//.*)?$') + undefPatt = re.compile(r'^(\s*(//)?#undef)\s+([A-Z_][A-Z0-9_]+)\s*(//.*)?$') + defPatt = re.compile(r'^(\s*(//)?#define)\s+([A-Z_][A-Z0-9_]+)\s+([-_\w]+)\s*(//.*)?$') + condPatt = re.compile(r'^(\s*(//)?#(if|ifn?def|elif)(\s+\S+)*)\s+(//.*)$') + commPatt = re.compile(r'^\s{20,}(//.*)?$') + + col_value_lj = col_comment - patt['pad'] - 2 + col_value_rj = col_comment - 3 + + # + # #define SKIP_ME + # + def trySkip1(d): + if skipPatt1.match(d['line']) == None: return False + logmsg("skip:", d['line']) + return True + + # + # #define MY_PIN [pin] + # + def tryPindef(d): + line = d['line'] + r = pindefPatt.match(line) + if r == None: return False + logmsg("pin:", line) + pinnum = r[4] if r[4][0] == 'P' else lpad(r[4], patt['pad']) + line = f'{r[1]} {r[3]}' + line = rpad(line, col_value_lj) + pinnum + if r[5]: line = rpad(line, col_comment) + r[5] + d['line'] = line + return True + + # + # #define MY_PIN -1 + # + def tryNoPin(d): + line = d['line'] + r = noPinPatt.match(line) + if r == None: return False + logmsg("pin -1:", line) + line = f'{r[1]} {r[3]}' + line = rpad(line, col_value_lj) + '-1' + if r[5]: line = rpad(line, col_comment) + r[5] + d['line'] = line + return True + + # + # #define SKIP_ME_TOO + # + def trySkip2(d): + if skipPatt2.match( d['line']) == None: return False + logmsg("skip:", d['line']) + return True + + # + # #else|endif + # + def trySkip3(d): + if skipPatt3.match( d['line']) == None: return False + logmsg("skip:", d['line']) + return True + + # + # #define ALIAS OTHER + # + def tryAlias(d): + line = d['line'] + r = aliasPatt.match(line) + if r == None: return False + logmsg("alias:", line) + line = f'{r[1]} {r[3]}' + line += lpad(r[4], col_value_rj + 1 - len(line)) + if r[5]: line = rpad(line, col_comment) + r[5] + d['line'] = line + return True + + # + # #define SWITCH + # + def trySwitch(d): + line = d['line'] + r = switchPatt.match(line) + if r == None: return False + logmsg("switch:", line) + line = f'{r[1]} {r[3]}' + if r[4]: line = rpad(line, col_comment) + r[4] + d['line'] = line + d['check_comment_next'] = True + return True + + # + # #define ... + # + def tryDef(d): + line = d['line'] + r = defPatt.match(line) + if r == None: return False + logmsg("def:", line) + line = f'{r[1]} {r[3]} ' + line += lpad(r[4], col_value_rj + 1 - len(line)) + if r[5]: line = rpad(line, col_comment - 1) + ' ' + r[5] + d['line'] = line + return True + + # + # #undef ... + # + def tryUndef(d): + line = d['line'] + r = undefPatt.match(line) + if r == None: return False + logmsg("undef:", line) + line = f'{r[1]} {r[3]}' + if r[4]: line = rpad(line, col_comment) + r[4] + d['line'] = line + return True + + # + # #if|ifdef|ifndef|elif ... + # + def tryCond(d): + line = d['line'] + r = condPatt.match(line) + if r == None: return False + logmsg("cond:", line) + line = rpad(r[1], col_comment) + r[5] + d['line'] = line + d['check_comment_next'] = True + return True + + out = '' + wDict = { 'check_comment_next': False } + + # Transform each line and add it to the output + for line in txt.split('\n'): + wDict['line'] = line + if wDict['check_comment_next']: + r = commPatt.match(line) + wDict['check_comment_next'] = (r != None) + + if wDict['check_comment_next']: + # Comments in column 50 + line = rpad('', col_comment) + r[1] + + elif trySkip1(wDict): pass #define SKIP_ME + elif tryPindef(wDict): pass #define MY_PIN [pin] + elif tryNoPin(wDict): pass #define MY_PIN -1 + elif trySkip2(wDict): pass #define SKIP_ME_TOO + elif trySkip3(wDict): pass #else|endif + elif tryAlias(wDict): pass #define ALIAS OTHER + elif trySwitch(wDict): pass #define SWITCH + elif tryDef(wDict): pass #define ... + elif tryUndef(wDict): pass #undef ... + elif tryCond(wDict): pass #if|ifdef|ifndef|elif ... + + out += wDict['line'] + '\n' + + return re.sub('\n\n$', '\n', re.sub(r'\n\n+', '\n\n', out)) + +# Python standard startup for command line with arguments +if __name__ == '__main__': + format_pins(sys.argv[1:]) diff --git a/buildroot/share/scripts/rle16_compress_cpp_image_data.py b/buildroot/share/scripts/rle16_compress_cpp_image_data.py new file mode 100755 index 000000000000..aeb7e65d3a01 --- /dev/null +++ b/buildroot/share/scripts/rle16_compress_cpp_image_data.py @@ -0,0 +1,142 @@ +#!/usr/bin/env python3 +# +# Utility to compress Marlin RGB565 TFT data to RLE16 format. +# Reads the existing Marlin RGB565 cpp file and generates a new file with the additional RLE16 data. +# +# Usage: rle16_compress_cpp_image_data.py INPUT_FILE.cpp OUTPUT_FILE.cpp +# +import sys,struct +import re + +def addCompressedData(input_file, output_file): + ofile = open(output_file, 'wt') + + c_data_section = False + c_skip_data = False + c_footer = False + raw_data = [] + rle_value = [] + rle_count = [] + arrname = '' + + line = input_file.readline() + while line: + if not c_footer: + if not c_skip_data: ofile.write(line) + + if "};" in line: + c_skip_data = False + c_data_section = False + c_footer = True + + if c_data_section: + cleaned = re.sub(r"\s|,|\n", "", line) + as_list = cleaned.split("0x") + as_list.pop(0) + raw_data += [int(x, 16) for x in as_list] + + if "const uint" in line: + # e.g.: const uint16_t marlin_logo_480x320x16[153600] = { + if "_rle16" in line: + c_skip_data = True + else: + c_data_section = True + arrname = line.split('[')[0].split(' ')[-1] + print("Found data array", arrname) + + line = input_file.readline() + + input_file.close() + + # + # RLE16 (run length 16) encoding + # Convert data from from raw RGB565 to a simple run-length-encoded format for each word of data. + # - Each sequence begins with a count byte N. + # - If the high bit is set in N the run contains N & 0x7F + 1 unique words. + # - Otherwise it repeats the following word N + 1 times. + # - Each RGB565 word is stored in MSB / LSB order. + # + def rle_encode(data): + warn = "This may take a while" if len(data) > 300000 else "" + print("Compressing image data...", warn) + rledata = [] + distinct = [] + i = 0 + while i < len(data): + v = data[i] + i += 1 + rsize = 1 + for j in range(i, len(data)): + if v != data[j]: break + i += 1 + rsize += 1 + if rsize >= 128: break + + # If the run is one, add to the distinct values + if rsize == 1: distinct.append(v) + + # If distinct length >= 127, or the repeat run is 2 or more, + # store the distinct run. + nr = len(distinct) + if nr and (nr >= 128 or rsize > 1 or i >= len(data)): + rledata += [(nr - 1) | 0x80] + distinct + distinct = [] + + # If the repeat run is 2 or more, store the repeat run. + if rsize > 1: rledata += [rsize - 1, v] + + return rledata + + def append_byte(data, byte, cols=240): + if data == '': data = ' ' + data += ('0x{0:02X}, '.format(byte)) # 6 characters + if len(data) % (cols * 6 + 2) == 0: data = data.rstrip() + "\n " + return data + + def rle_emit(ofile, arrname, rledata, rawsize): + col = 0 + i = 0 + outstr = '' + size = 0 + while i < len(rledata): + rval = rledata[i] + i += 1 + if rval & 0x80: + count = (rval & 0x7F) + 1 + outstr = append_byte(outstr, rval) + size += 1 + for j in range(count): + outstr = append_byte(outstr, rledata[i + j] >> 8) + outstr = append_byte(outstr, rledata[i + j] & 0xFF) + size += 2 + i += count + else: + outstr = append_byte(outstr, rval) + outstr = append_byte(outstr, rledata[i] >> 8) + outstr = append_byte(outstr, rledata[i] & 0xFF) + i += 1 + size += 3 + + outstr = outstr.rstrip()[:-1] + ofile.write("\n// Saves %i bytes\nconst uint8_t %s_rle16[%d] = {\n%s\n};\n" % (rawsize - size, arrname, size, outstr)) + + (w, h, d) = arrname.split("_")[-1].split('x') + ofile.write("\nconst tImage MarlinLogo{0}x{1}x16 = MARLIN_LOGO_CHOSEN({0}, {1});\n".format(w, h)) + ofile.write("\n#endif // HAS_GRAPHICAL_TFT && SHOW_BOOTSCREEN\n".format(w, h)) + + # Encode the data, write it out, close the file + rledata = rle_encode(raw_data) + rle_emit(ofile, arrname, rledata, len(raw_data) * 2) + ofile.close() + +if len(sys.argv) <= 2: + print("Utility to compress Marlin RGB565 TFT data to RLE16 format.") + print("Reads a Marlin RGB565 cpp file and generates a new file with the additional RLE16 data.") + print("Usage: rle16_compress_cpp_image_data.py INPUT_FILE.cpp OUTPUT_FILE.cpp") + exit(1) + +output_cpp = sys.argv[2] +inname = sys.argv[1].replace('//', '/') +input_cpp = open(inname) +print("Processing", inname, "...") +addCompressedData(input_cpp, output_cpp) diff --git a/buildroot/share/scripts/rle_compress_bitmap.py b/buildroot/share/scripts/rle_compress_bitmap.py new file mode 100755 index 000000000000..c3f673c61699 --- /dev/null +++ b/buildroot/share/scripts/rle_compress_bitmap.py @@ -0,0 +1,200 @@ +#!/usr/bin/env python3 +# +# Bitwise RLE compress a Marlin mono DOGM bitmap. +# Input: An existing Marlin Marlin mono DOGM bitmap .cpp or .h file. +# Output: A new file with the original and compressed data. +# +# Usage: rle_compress_bitmap.py INPUT_FILE OUTPUT_FILE +# +import sys,struct +import re + +def addCompressedData(input_file, output_file): + ofile = open(output_file, 'wt') + + datatype = "uint8_t" + bytewidth = 16 + raw_data = [] + arrname = '' + + c_data_section = False ; c_skip_data = False ; c_footer = False + while True: + line = input_file.readline() + if not line: break + + if not c_footer: + if not c_skip_data: ofile.write(line) + + mat = re.match(r'.+CUSTOM_BOOTSCREEN_BMPWIDTH\s+(\d+)', line) + if mat: bytewidth = (int(mat[1]) + 7) // 8 + + if "};" in line: + c_skip_data = False + c_data_section = False + c_footer = True + + if c_data_section: + cleaned = re.sub(r"\s|,|\n", "", line) + mat = re.match(r'(0b|B)[01]{8}', cleaned) + if mat: + as_list = cleaned.split(mat[1]) + as_list.pop(0) + raw_data += [int(x, 2) for x in as_list] + else: + as_list = cleaned.split("0x") + as_list.pop(0) + raw_data += [int(x, 16) for x in as_list] + + mat = re.match(r'const (uint\d+_t|unsigned char)', line) + if mat: + # e.g.: const unsigned char custom_start_bmp[] PROGMEM = { + datatype = mat[0] + if "_rle" in line: + c_skip_data = True + else: + c_data_section = True + arrname = line.split('[')[0].split(' ')[-1] + print("Found data array", arrname) + + input_file.close() + + #print("\nRaw Bitmap Data", raw_data) + + # + # Bitwise RLE (run length) encoding + # Convert data from raw mono bitmap to a bitwise run-length-encoded format. + # - The first nybble is the starting bit state. Changing this nybble inverts the bitmap. + # - The following bytes provide the runs for alternating on/off bits. + # - A value of 0-14 encodes a run of 1-15. + # - A value of 16 indicates a run of 16-270 calculated using the next two bytes. + # + def bitwise_rle_encode(data): + + def get_bit(data, n): return 1 if (data[n // 8] & (0x80 >> (n & 7))) else 0 + + def try_encode(data, isext): + bitslen = len(data) * 8 + bitstate = get_bit(data, 0) + rledata = [ bitstate ] + bigrun = 256 if isext else 272 + medrun = False + + i = 0 + runlen = -1 + while i <= bitslen: + if i < bitslen: b = get_bit(data, i) + runlen += 1 + if bitstate != b or i == bitslen: + if runlen >= bigrun: + isext = True + if medrun: return [], isext + rem = runlen & 0xFF + rledata += [ 15, 15, rem // 16, rem % 16 ] + elif runlen >= 16: + rledata += [ 15, runlen // 16 - 1, runlen % 16 ] + if runlen >= 256: medrun = True + else: + rledata += [ runlen - 1 ] + bitstate ^= 1 + runlen = 0 + i += 1 + + #print("\nrledata", rledata) + + encoded = [] + ri = 0 + rlen = len(rledata) + while ri < rlen: + v = rledata[ri] << 4 + if (ri < rlen - 1): v |= rledata[ri + 1] + encoded += [ v ] + ri += 2 + + #print("\nencoded", encoded) + return encoded, isext + + # Try to encode with the original isext flag + warn = "This may take a while" if len(data) > 300000 else "" + print("Compressing image data...", warn) + isext = False + encoded, isext = try_encode(data, isext) + if len(encoded) == 0: + encoded, isext = try_encode(data, True) + return encoded, isext + + def bitwise_rle_decode(isext, rledata, invert=0): + expanded = [] + for n in rledata: expanded += [ n >> 4, n & 0xF ] + + decoded = [] + bitstate = 0 ; workbyte = 0 ; outindex = 0 + i = 0 + while i < len(expanded): + c = expanded[i] + i += 1 + + if i == 1: bitstate = c ; continue + + if c == 15: + d = expanded[i] ; e = expanded[i + 1] + if isext and d == 15: + c = 256 + 16 * e + expanded[i + 2] - 1 + i += 1 + else: + c = 16 * d + e + 15 + i += 2 + + for _ in range(c, -1, -1): + bitval = 0x80 >> (outindex & 7) + if bitstate: workbyte |= bitval + if bitval == 1: + decoded += [ workbyte ] + workbyte = 0 + outindex += 1 + + bitstate ^= 1 + + print("\nDecoded RLE data:") + pretty = [ '{0:08b}'.format(v) for v in decoded ] + rows = [pretty[i:i+bytewidth] for i in range(0, len(pretty), bytewidth)] + for row in rows: print(f"{''.join(row)}") + + return decoded + + def rle_emit(ofile, arrname, rledata, rawsize, isext): + + outstr = '' + rows = [ rledata[i:i+16] for i in range(0, len(rledata), 16) ] + for i in range(0, len(rows)): + rows[i] = [ '0x{0:02X}'.format(v) for v in rows[i] ] + outstr += f" {', '.join(rows[i])},\n" + + outstr = outstr[:-2] + size = len(rledata) + defname = 'COMPACT_CUSTOM_BOOTSCREEN_EXT' if isext else 'COMPACT_CUSTOM_BOOTSCREEN' + ofile.write(f"\n// Saves {rawsize - size} bytes\n#define {defname}\n{datatype} {arrname}_rle[{size}] PROGMEM = {{\n{outstr}\n}};\n") + + # Encode the data, write it out, close the file + rledata, isext = bitwise_rle_encode(raw_data) + rle_emit(ofile, arrname, rledata, len(raw_data), isext) + ofile.close() + + # Validate that code properly compressed (and decompressed) the data + checkdata = bitwise_rle_decode(isext, rledata) + for i in range(0, len(checkdata)): + if raw_data[i] != checkdata[i]: + print(f'Data mismatch at byte offset {i} (should be {raw_data[i]} but got {checkdata[i]})') + break + +if len(sys.argv) <= 2: + print('Usage: rle_compress_bitmap.py INPUT_FILE OUTPUT_FILE') + exit(1) + +output_cpp = sys.argv[2] +inname = sys.argv[1].replace('//', '/') +try: + input_cpp = open(inname) + print("Processing", inname, "...") + addCompressedData(input_cpp, output_cpp) +except OSError: + print("Can't find input file", inname) diff --git a/buildroot/share/scripts/upload.py b/buildroot/share/scripts/upload.py index af15a825906e..9fb927c42685 100644 --- a/buildroot/share/scripts/upload.py +++ b/buildroot/share/scripts/upload.py @@ -7,17 +7,6 @@ Import("env") -# Needed (only) for compression, but there are problems with pip install heatshrink -#try: -# import heatshrink -#except ImportError: -# # Install heatshrink -# print("Installing 'heatshrink' python module...") -# env.Execute(env.subst("$PYTHONEXE -m pip install heatshrink")) -# -# Not tested: If it's safe to install python libraries in PIO python try: -# env.Execute(env.subst("$PYTHONEXE -m pip install https://github.com/p3p/pyheatshrink/releases/download/0.3.3/pyheatshrink-pip.zip")) - import MarlinBinaryProtocol #-----------------# @@ -168,7 +157,8 @@ def _RollbackUpload(FirmwareFile): 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_firmware_source_name = env['PROGNAME'] + '.bin' if 'PROGNAME' in env else 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 @@ -191,6 +181,21 @@ def _RollbackUpload(FirmwareFile): # "upload_random_name": generate a random 8.3 firmware filename to upload upload_random_filename = upload_delete_old_bins and not marlin_long_filename_host_support + # Heatshrink module is needed (only) for compression + if upload_compression: + if sys.version_info[0] > 2: + try: + import heatshrink2 + except ImportError: + print("Installing 'heatshrink2' python module...") + env.Execute(env.subst("$PYTHONEXE -m pip install heatshrink2")) + else: + try: + import heatshrink + except ImportError: + print("Installing 'heatshrink' python module...") + env.Execute(env.subst("$PYTHONEXE -m pip install heatshrink")) + try: # Start upload job diff --git a/buildroot/share/sublime/MarlinFirmware.sublime-project b/buildroot/share/sublime/MarlinFirmware.sublime-project index e0cf953fa813..62607ac0c6d1 100644 --- a/buildroot/share/sublime/MarlinFirmware.sublime-project +++ b/buildroot/share/sublime/MarlinFirmware.sublime-project @@ -11,7 +11,7 @@ ".vscode" ], "binary_file_patterns": - [ "*.psd", "*.png", "*.jpg", "*.jpeg", "*.bdf", "*.patch", "avrdude_5.*", "*.svg", "*.bin", "*.woff" ], + [ "*.psd", "*.png", "*.jpg", "*.jpeg", "*.bdf", "*.patch", "avrdude_5.*", "*.svg", "*.bin", "*.woff", "*.otf" ], "file_exclude_patterns": [ "Marlin/platformio.ini", @@ -30,6 +30,7 @@ "ensure_newline_at_eof_on_save": true, "tab_size": 2, "translate_tabs_to_spaces": true, - "trim_trailing_white_space_on_save": true + "trim_trailing_white_space_on_save": true, + "uncrustify_config" : "${project_dir}/../extras/uncrustify.cfg" } } diff --git a/buildroot/share/vscode/auto_build.py b/buildroot/share/vscode/auto_build.py index 31ef2715515b..80b8b2e6c119 100644 --- a/buildroot/share/vscode/auto_build.py +++ b/buildroot/share/vscode/auto_build.py @@ -499,7 +499,7 @@ def get_starting_env(board_name_full, version): possible_envs = None for i, line in enumerate(pins_h): if 0 < line.find("Unknown MOTHERBOARD value set in Configuration.h"): - invalid_board(); + invalid_board() if list_start_found == False and 0 < line.find('1280'): list_start_found = True elif list_start_found == False: # skip lines until find start of CPU list @@ -1103,7 +1103,7 @@ def update(self): else: try: temp_text = IO_queue.get(block=False) - except Queue.Empty: + except queue.Empty: continue_updates = False # queue is exhausted so no need for further updates else: self.insert('end', temp_text[0], temp_text[1]) @@ -1267,6 +1267,7 @@ def main(): global build_type global target_env global board_name + global Marlin_ver board_name, Marlin_ver = get_board_name() diff --git a/buildroot/share/vscode/avrdude.conf b/buildroot/share/vscode/avrdude.conf index 991d255750f5..a1a3ef4ba4b8 100644 --- a/buildroot/share/vscode/avrdude.conf +++ b/buildroot/share/vscode/avrdude.conf @@ -240,8 +240,8 @@ #define AT86RF401 0xD0 #define AT89START 0xE0 -#define AT89S51 0xE0 -#define AT89S52 0xE1 +#define AT89S51 0xE0 +#define AT89S52 0xE1 # The following table lists the devices in the original AVR910 # appnote: @@ -293,15 +293,15 @@ # in the Internet. These add the following codes (only devices that # actually exist are listed): -# ATmega8515 0x3A -# ATmega128 0x43 -# ATmega64 0x45 -# ATtiny26 0x5E -# ATmega8535 0x69 -# ATmega32 0x72 -# ATmega16 0x74 -# ATmega8 0x76 -# ATmega169 0x78 +# ATmega8515 0x3A +# ATmega128 0x43 +# ATmega64 0x45 +# ATtiny26 0x5E +# ATmega8535 0x69 +# ATmega32 0x72 +# ATmega16 0x74 +# ATmega8 0x76 +# ATmega169 0x78 # # Overall avrdude defaults @@ -894,63 +894,63 @@ programmer # This is an HVSP-only device. part - id = "t11"; - desc = "ATtiny11"; - stk500_devcode = 0x11; - signature = 0x1e 0x90 0x04; - chip_erase_delay = 20000; - - timeout = 200; - hvsp_controlstack = - 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x00, - 0x68, 0x78, 0x68, 0x68, 0x00, 0x00, 0x68, 0x78, - 0x78, 0x00, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, - 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - hvspcmdexedelay = 0; - synchcycles = 6; - latchcycles = 1; - togglevtg = 1; - poweroffdelay = 25; - resetdelayms = 0; - resetdelayus = 50; - hvleavestabdelay = 100; - resetdelay = 25; - chiperasepolltimeout = 40; - chiperasetime = 0; - programfusepolltimeout = 25; - programlockpolltimeout = 25; - - memory "eeprom" - size = 64; - blocksize = 64; - readsize = 256; - delay = 5; - ; - - memory "flash" - size = 1024; - blocksize = 128; - readsize = 256; - delay = 3; - ; - - memory "signature" - size = 3; - ; - - memory "lock" - size = 1; - ; - - memory "calibration" - size = 1; - ; - - memory "fuse" - size = 1; - ; + id = "t11"; + desc = "ATtiny11"; + stk500_devcode = 0x11; + signature = 0x1e 0x90 0x04; + chip_erase_delay = 20000; + + timeout = 200; + hvsp_controlstack = + 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x00, + 0x68, 0x78, 0x68, 0x68, 0x00, 0x00, 0x68, 0x78, + 0x78, 0x00, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, + 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + hvspcmdexedelay = 0; + synchcycles = 6; + latchcycles = 1; + togglevtg = 1; + poweroffdelay = 25; + resetdelayms = 0; + resetdelayus = 50; + hvleavestabdelay = 100; + resetdelay = 25; + chiperasepolltimeout = 40; + chiperasetime = 0; + programfusepolltimeout = 25; + programlockpolltimeout = 25; + + memory "eeprom" + size = 64; + blocksize = 64; + readsize = 256; + delay = 5; + ; + + memory "flash" + size = 1024; + blocksize = 128; + readsize = 256; + delay = 3; + ; + + memory "signature" + size = 3; + ; + + memory "lock" + size = 1; + ; + + memory "calibration" + size = 1; + ; + + memory "fuse" + size = 1; + ; ; #------------------------------------------------------------ @@ -958,132 +958,132 @@ part #------------------------------------------------------------ part - id = "t12"; - desc = "ATtiny12"; - stk500_devcode = 0x12; - avr910_devcode = 0x55; - signature = 0x1e 0x90 0x05; - chip_erase_delay = 20000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - hvsp_controlstack = - 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x00, - 0x68, 0x78, 0x68, 0x68, 0x00, 0x00, 0x68, 0x78, - 0x78, 0x00, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, - 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; - hventerstabdelay = 100; - hvspcmdexedelay = 0; - synchcycles = 6; - latchcycles = 1; - togglevtg = 1; - poweroffdelay = 25; - resetdelayms = 0; - resetdelayus = 50; - hvleavestabdelay = 100; - resetdelay = 25; - chiperasepolltimeout = 40; - chiperasetime = 0; - programfusepolltimeout = 25; - programlockpolltimeout = 25; - - memory "eeprom" - size = 64; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 x x x x x x x x", - "x x a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 x x x x x x x x", - "x x a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - mode = 0x04; - delay = 8; - blocksize = 64; - readsize = 256; - ; - - memory "flash" - size = 1024; - min_write_delay = 4500; - max_write_delay = 20000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - write_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 5; - blocksize = 128; - readsize = 256; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", - "x x x x x x x x x x x x x o o x"; - - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", - "x x x x x x x x x x x x x x x x"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "fuse" - size = 1; - read = "0 1 0 1 0 0 0 0 x x x x x x x x", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 x x x x x", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; + id = "t12"; + desc = "ATtiny12"; + stk500_devcode = 0x12; + avr910_devcode = 0x55; + signature = 0x1e 0x90 0x05; + chip_erase_delay = 20000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + hvsp_controlstack = + 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x00, + 0x68, 0x78, 0x68, 0x68, 0x00, 0x00, 0x68, 0x78, + 0x78, 0x00, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, + 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; + hventerstabdelay = 100; + hvspcmdexedelay = 0; + synchcycles = 6; + latchcycles = 1; + togglevtg = 1; + poweroffdelay = 25; + resetdelayms = 0; + resetdelayus = 50; + hvleavestabdelay = 100; + resetdelay = 25; + chiperasepolltimeout = 40; + chiperasetime = 0; + programfusepolltimeout = 25; + programlockpolltimeout = 25; + + memory "eeprom" + size = 64; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 x x x x x x x x", + "x x a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 x x x x x x x x", + "x x a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + mode = 0x04; + delay = 8; + blocksize = 64; + readsize = 256; + ; + + memory "flash" + size = 1024; + min_write_delay = 4500; + max_write_delay = 20000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + write_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 5; + blocksize = 128; + readsize = 256; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", + "x x x x x x x x x x x x x o o x"; + + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", + "x x x x x x x x x x x x x x x x"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "fuse" + size = 1; + read = "0 1 0 1 0 0 0 0 x x x x x x x x", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 x x x x x", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; ; #------------------------------------------------------------ @@ -1091,170 +1091,170 @@ part #------------------------------------------------------------ part - id = "t13"; - desc = "ATtiny13"; - has_debugwire = yes; - flash_instr = 0xB4, 0x0E, 0x1E; - eeprom_instr = 0xBB, 0xFE, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, - 0xBC, 0x0E, 0xB4, 0x0E, 0xBA, 0x0D, 0xBB, 0xBC, - 0x99, 0xE1, 0xBB, 0xAC; - stk500_devcode = 0x14; - signature = 0x1e 0x90 0x07; - chip_erase_delay = 4000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - hvsp_controlstack = + id = "t13"; + desc = "ATtiny13"; + has_debugwire = yes; + flash_instr = 0xB4, 0x0E, 0x1E; + eeprom_instr = 0xBB, 0xFE, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, + 0xBC, 0x0E, 0xB4, 0x0E, 0xBA, 0x0D, 0xBB, 0xBC, + 0x99, 0xE1, 0xBB, 0xAC; + stk500_devcode = 0x14; + signature = 0x1e 0x90 0x07; + chip_erase_delay = 4000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + hvsp_controlstack = 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66, - 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, - 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, - 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - hvspcmdexedelay = 0; - synchcycles = 6; - latchcycles = 1; - togglevtg = 1; - poweroffdelay = 25; - resetdelayms = 0; - resetdelayus = 90; - hvleavestabdelay = 100; - resetdelay = 25; - chiperasepolltimeout = 40; - chiperasetime = 0; - programfusepolltimeout = 25; - programlockpolltimeout = 25; - - memory "eeprom" - size = 64; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x", - "x x a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x", - "x x a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, + 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, + 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + hvspcmdexedelay = 0; + synchcycles = 6; + latchcycles = 1; + togglevtg = 1; + poweroffdelay = 25; + resetdelayms = 0; + resetdelayus = 90; + hvleavestabdelay = 100; + resetdelay = 25; + chiperasepolltimeout = 40; + chiperasetime = 0; + programfusepolltimeout = 25; + programlockpolltimeout = 25; + + memory "eeprom" + size = 64; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x", + "x x a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x", + "x x a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " x x a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 5; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 1024; - page_size = 32; - num_pages = 32; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 0 0 0 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 0 0 0 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x x a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x x a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 0 0 0 a8", - " a7 a6 a5 a4 x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 32; - readsize = 256; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "lock" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; + mode = 0x41; + delay = 5; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 1024; + page_size = 32; + num_pages = 32; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 0 0 0 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 0 0 0 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x x a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x x a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 0 0 0 a8", + " a7 a6 a5 a4 x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 32; + readsize = 256; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "lock" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; + "x x x x x x x x x x o o o o o o"; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; - memory "calibration" - size = 2; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 a0 o o o o o o o o"; - ; + memory "calibration" + size = 2; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 a0 o o o o o o o o"; + ; - memory "lfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; + memory "lfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - ; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + ; - memory "hfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; + memory "hfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - ; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + ; ; @@ -1264,132 +1264,132 @@ part #------------------------------------------------------------ part - id = "t15"; - desc = "ATtiny15"; - stk500_devcode = 0x13; - avr910_devcode = 0x56; - signature = 0x1e 0x90 0x06; - chip_erase_delay = 8200; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - hvsp_controlstack = - 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x00, - 0x68, 0x78, 0x68, 0x68, 0x00, 0x00, 0x68, 0x78, - 0x78, 0x00, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, - 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; - hventerstabdelay = 100; - hvspcmdexedelay = 5; - synchcycles = 6; - latchcycles = 16; - togglevtg = 1; - poweroffdelay = 25; - resetdelayms = 0; - resetdelayus = 50; - hvleavestabdelay = 100; - resetdelay = 25; - chiperasepolltimeout = 40; - chiperasetime = 0; - programfusepolltimeout = 25; - programlockpolltimeout = 25; - - memory "eeprom" - size = 64; - min_write_delay = 8200; - max_write_delay = 8200; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 x x x x x x x x", - "x x a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 x x x x x x x x", - "x x a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - mode = 0x04; - delay = 10; - blocksize = 64; - readsize = 256; - ; - - memory "flash" - size = 1024; - min_write_delay = 4100; - max_write_delay = 4100; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - write_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 5; - blocksize = 128; - readsize = 256; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", - "x x x x x x x x x x x x x o o x"; - - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", - "x x x x x x x x x x x x x x x x"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "fuse" - size = 1; - read = "0 1 0 1 0 0 0 0 x x x x x x x x", - "x x x x x x x x o o o o x x o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 x x x x x", - "x x x x x x x x i i i i 1 1 i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; + id = "t15"; + desc = "ATtiny15"; + stk500_devcode = 0x13; + avr910_devcode = 0x56; + signature = 0x1e 0x90 0x06; + chip_erase_delay = 8200; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + hvsp_controlstack = + 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x00, + 0x68, 0x78, 0x68, 0x68, 0x00, 0x00, 0x68, 0x78, + 0x78, 0x00, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, + 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; + hventerstabdelay = 100; + hvspcmdexedelay = 5; + synchcycles = 6; + latchcycles = 16; + togglevtg = 1; + poweroffdelay = 25; + resetdelayms = 0; + resetdelayus = 50; + hvleavestabdelay = 100; + resetdelay = 25; + chiperasepolltimeout = 40; + chiperasetime = 0; + programfusepolltimeout = 25; + programlockpolltimeout = 25; + + memory "eeprom" + size = 64; + min_write_delay = 8200; + max_write_delay = 8200; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 x x x x x x x x", + "x x a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 x x x x x x x x", + "x x a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + mode = 0x04; + delay = 10; + blocksize = 64; + readsize = 256; + ; + + memory "flash" + size = 1024; + min_write_delay = 4100; + max_write_delay = 4100; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + write_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 5; + blocksize = 128; + readsize = 256; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", + "x x x x x x x x x x x x x o o x"; + + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", + "x x x x x x x x x x x x x x x x"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "fuse" + size = 1; + read = "0 1 0 1 0 0 0 0 x x x x x x x x", + "x x x x x x x x o o o o x x o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 x x x x x", + "x x x x x x x x i i i i 1 1 i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; ; #------------------------------------------------------------ @@ -1397,114 +1397,114 @@ part #------------------------------------------------------------ part - id = "1200"; - desc = "AT90S1200"; - stk500_devcode = 0x33; - avr910_devcode = 0x13; - signature = 0x1e 0x90 0x01; - pagel = 0xd7; - bs2 = 0xa0; - chip_erase_delay = 20000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 1; - bytedelay = 0; - pollindex = 0; - pollvalue = 0xFF; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 0; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 15; - chiperasepolltimeout = 0; - programfusepulsewidth = 2; - programfusepolltimeout = 0; - programlockpulsewidth = 0; - programlockpolltimeout = 1; - - memory "eeprom" - size = 64; - min_write_delay = 4000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 x x x x x x x x", - "x x a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 x x x x x x x x", - "x x a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - mode = 0x04; - delay = 20; - blocksize = 32; - readsize = 256; - ; - memory "flash" - size = 1024; - min_write_delay = 4000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - write_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x02; - delay = 15; - blocksize = 128; - readsize = 256; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "fuse" - size = 1; - ; - memory "lock" - size = 1; - min_write_delay = 9000; - max_write_delay = 20000; - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", - "x x x x x x x x x x x x x x x x"; - ; + id = "1200"; + desc = "AT90S1200"; + stk500_devcode = 0x33; + avr910_devcode = 0x13; + signature = 0x1e 0x90 0x01; + pagel = 0xd7; + bs2 = 0xa0; + chip_erase_delay = 20000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 1; + bytedelay = 0; + pollindex = 0; + pollvalue = 0xFF; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 0; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 15; + chiperasepolltimeout = 0; + programfusepulsewidth = 2; + programfusepolltimeout = 0; + programlockpulsewidth = 0; + programlockpolltimeout = 1; + + memory "eeprom" + size = 64; + min_write_delay = 4000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 x x x x x x x x", + "x x a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 x x x x x x x x", + "x x a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + mode = 0x04; + delay = 20; + blocksize = 32; + readsize = 256; + ; + memory "flash" + size = 1024; + min_write_delay = 4000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + write_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x02; + delay = 15; + blocksize = 128; + readsize = 256; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "fuse" + size = 1; + ; + memory "lock" + size = 1; + min_write_delay = 9000; + max_write_delay = 20000; + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", + "x x x x x x x x x x x x x x x x"; + ; ; #------------------------------------------------------------ @@ -1512,112 +1512,112 @@ part #------------------------------------------------------------ part - id = "4414"; - desc = "AT90S4414"; - stk500_devcode = 0x50; - avr910_devcode = 0x28; - signature = 0x1e 0x92 0x01; - chip_erase_delay = 20000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 0; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 15; - chiperasepolltimeout = 0; - programfusepulsewidth = 2; - programfusepolltimeout = 0; - programlockpulsewidth = 0; - programlockpolltimeout = 1; - - memory "eeprom" - size = 256; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0x80; - readback_p2 = 0x7f; - read = " 1 0 1 0 0 0 0 0 x x x x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0 x x x x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 64; - readsize = 256; - ; - memory "flash" - size = 4096; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0x7f; - readback_p2 = 0x7f; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write_lo = " 0 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - write_hi = " 0 1 0 0 1 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 64; - readsize = 256; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "fuse" - size = 1; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", + id = "4414"; + desc = "AT90S4414"; + stk500_devcode = 0x50; + avr910_devcode = 0x28; + signature = 0x1e 0x92 0x01; + chip_erase_delay = 20000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 0; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 15; + chiperasepolltimeout = 0; + programfusepulsewidth = 2; + programfusepolltimeout = 0; + programlockpulsewidth = 0; + programlockpolltimeout = 1; + + memory "eeprom" + size = 256; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0x80; + readback_p2 = 0x7f; + read = " 1 0 1 0 0 0 0 0 x x x x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0 x x x x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 64; + readsize = 256; + ; + memory "flash" + size = 4096; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0x7f; + readback_p2 = 0x7f; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write_lo = " 0 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + write_hi = " 0 1 0 0 1 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 64; + readsize = 256; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "fuse" + size = 1; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", "x x x x x x x x x x x x x x x x"; - min_write_delay = 9000; - max_write_delay = 9000; - ; + min_write_delay = 9000; + max_write_delay = 9000; + ; ; #------------------------------------------------------------ @@ -1625,112 +1625,112 @@ part #------------------------------------------------------------ part - id = "2313"; - desc = "AT90S2313"; - stk500_devcode = 0x40; - avr910_devcode = 0x20; - signature = 0x1e 0x91 0x01; - chip_erase_delay = 20000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 0; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 15; - chiperasepolltimeout = 0; - programfusepulsewidth = 2; - programfusepolltimeout = 0; - programlockpulsewidth = 0; - programlockpolltimeout = 1; - - memory "eeprom" - size = 128; - min_write_delay = 4000; - max_write_delay = 9000; - readback_p1 = 0x80; - readback_p2 = 0x7f; - read = "1 0 1 0 0 0 0 0 x x x x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 x x x x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 64; - readsize = 256; - ; - memory "flash" - size = 2048; - min_write_delay = 4000; - max_write_delay = 9000; - readback_p1 = 0x7f; - readback_p2 = 0x7f; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - write_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 128; - readsize = 256; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "fuse" - size = 1; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 x x i i x", - "x x x x x x x x x x x x x x x x"; - min_write_delay = 9000; - max_write_delay = 9000; - ; + id = "2313"; + desc = "AT90S2313"; + stk500_devcode = 0x40; + avr910_devcode = 0x20; + signature = 0x1e 0x91 0x01; + chip_erase_delay = 20000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 0; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 15; + chiperasepolltimeout = 0; + programfusepulsewidth = 2; + programfusepolltimeout = 0; + programlockpulsewidth = 0; + programlockpolltimeout = 1; + + memory "eeprom" + size = 128; + min_write_delay = 4000; + max_write_delay = 9000; + readback_p1 = 0x80; + readback_p2 = 0x7f; + read = "1 0 1 0 0 0 0 0 x x x x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 x x x x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 64; + readsize = 256; + ; + memory "flash" + size = 2048; + min_write_delay = 4000; + max_write_delay = 9000; + readback_p1 = 0x7f; + readback_p2 = 0x7f; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + write_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 128; + readsize = 256; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "fuse" + size = 1; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 x x i i x", + "x x x x x x x x x x x x x x x x"; + min_write_delay = 9000; + max_write_delay = 9000; + ; ; #------------------------------------------------------------ @@ -1738,126 +1738,126 @@ part #------------------------------------------------------------ part - id = "2333"; + id = "2333"; ##### WARNING: No XML file for device 'AT90S2333'! ##### - desc = "AT90S2333"; - stk500_devcode = 0x42; - avr910_devcode = 0x34; - signature = 0x1e 0x91 0x05; - chip_erase_delay = 20000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 0; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 15; - chiperasepolltimeout = 0; - programfusepulsewidth = 2; - programfusepolltimeout = 0; - programlockpulsewidth = 0; - programlockpolltimeout = 1; - - memory "eeprom" - size = 128; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0x00; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 x x x x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 x x x x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 128; - readsize = 256; - ; - - memory "flash" - size = 2048; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - write_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 128; - readsize = 256; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "fuse" - size = 1; - min_write_delay = 9000; - max_write_delay = 20000; - pwroff_after_write = yes; - read = "0 1 0 1 0 0 0 0 x x x x x x x x", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 i i i i i", - "x x x x x x x x x x x x x x x x"; - ; - memory "lock" - size = 1; - min_write_delay = 9000; - max_write_delay = 20000; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", - "x x x x x x x x x x x x x o o x"; - - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", - "x x x x x x x x x x x x x x x x"; - ; + desc = "AT90S2333"; + stk500_devcode = 0x42; + avr910_devcode = 0x34; + signature = 0x1e 0x91 0x05; + chip_erase_delay = 20000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 0; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 15; + chiperasepolltimeout = 0; + programfusepulsewidth = 2; + programfusepolltimeout = 0; + programlockpulsewidth = 0; + programlockpolltimeout = 1; + + memory "eeprom" + size = 128; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0x00; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 x x x x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 x x x x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 128; + readsize = 256; + ; + + memory "flash" + size = 2048; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + write_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 128; + readsize = 256; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "fuse" + size = 1; + min_write_delay = 9000; + max_write_delay = 20000; + pwroff_after_write = yes; + read = "0 1 0 1 0 0 0 0 x x x x x x x x", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 i i i i i", + "x x x x x x x x x x x x x x x x"; + ; + memory "lock" + size = 1; + min_write_delay = 9000; + max_write_delay = 20000; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", + "x x x x x x x x x x x x x o o x"; + + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", + "x x x x x x x x x x x x x x x x"; + ; ; @@ -1866,122 +1866,122 @@ part #------------------------------------------------------------ part - id = "2343"; - desc = "AT90S2343"; - stk500_devcode = 0x43; - avr910_devcode = 0x4c; - signature = 0x1e 0x91 0x03; - chip_erase_delay = 18000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - hvsp_controlstack = - 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x00, - 0x68, 0x78, 0x68, 0x68, 0x00, 0x00, 0x68, 0x78, - 0x78, 0x00, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, - 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; - hventerstabdelay = 100; - hvspcmdexedelay = 0; - synchcycles = 6; - latchcycles = 1; - togglevtg = 0; - poweroffdelay = 25; - resetdelayms = 0; - resetdelayus = 50; - hvleavestabdelay = 100; - resetdelay = 25; - chiperasepolltimeout = 40; - chiperasetime = 0; - programfusepolltimeout = 25; - programlockpolltimeout = 25; - - memory "eeprom" - size = 128; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0x00; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0", - "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0", - "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 64; - readsize = 256; - ; - memory "flash" - size = 2048; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - write_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 128; - readsize = 128; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "fuse" - size = 1; - min_write_delay = 9000; - max_write_delay = 20000; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", - "x x x x x x x x o o o x x x x o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 1 1 1 1 i", - "x x x x x x x x x x x x x x x x"; - ; - memory "lock" - size = 1; - min_write_delay = 9000; - max_write_delay = 20000; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", - "x x x x x x x x o o o x x x x o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", - "x x x x x x x x x x x x x x x x"; - ; + id = "2343"; + desc = "AT90S2343"; + stk500_devcode = 0x43; + avr910_devcode = 0x4c; + signature = 0x1e 0x91 0x03; + chip_erase_delay = 18000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + hvsp_controlstack = + 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x00, + 0x68, 0x78, 0x68, 0x68, 0x00, 0x00, 0x68, 0x78, + 0x78, 0x00, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, + 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; + hventerstabdelay = 100; + hvspcmdexedelay = 0; + synchcycles = 6; + latchcycles = 1; + togglevtg = 0; + poweroffdelay = 25; + resetdelayms = 0; + resetdelayus = 50; + hvleavestabdelay = 100; + resetdelay = 25; + chiperasepolltimeout = 40; + chiperasetime = 0; + programfusepolltimeout = 25; + programlockpolltimeout = 25; + + memory "eeprom" + size = 128; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0x00; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0", + "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0", + "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 64; + readsize = 256; + ; + memory "flash" + size = 2048; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + write_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 128; + readsize = 128; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "fuse" + size = 1; + min_write_delay = 9000; + max_write_delay = 20000; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", + "x x x x x x x x o o o x x x x o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 1 1 1 1 i", + "x x x x x x x x x x x x x x x x"; + ; + memory "lock" + size = 1; + min_write_delay = 9000; + max_write_delay = 20000; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", + "x x x x x x x x o o o x x x x o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", + "x x x x x x x x x x x x x x x x"; + ; ; @@ -1990,123 +1990,123 @@ part #------------------------------------------------------------ part - id = "4433"; - desc = "AT90S4433"; - stk500_devcode = 0x51; - avr910_devcode = 0x30; - signature = 0x1e 0x92 0x03; - chip_erase_delay = 20000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 0; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 15; - chiperasepolltimeout = 0; - programfusepulsewidth = 2; - programfusepolltimeout = 0; - programlockpulsewidth = 0; - programlockpolltimeout = 1; - - memory "eeprom" - size = 256; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0x00; - readback_p2 = 0xff; - read = " 1 0 1 0 0 0 0 0 x x x x x x x x", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0 x x x x x x x x", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 128; - readsize = 256; - ; - memory "flash" - size = 4096; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write_lo = " 0 1 0 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - write_hi = " 0 1 0 0 1 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 128; - readsize = 256; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "fuse" - size = 1; - min_write_delay = 9000; - max_write_delay = 20000; - pwroff_after_write = yes; - read = "0 1 0 1 0 0 0 0 x x x x x x x x", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 i i i i i", - "x x x x x x x x x x x x x x x x"; - ; - memory "lock" - size = 1; - min_write_delay = 9000; - max_write_delay = 20000; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", - "x x x x x x x x x x x x x o o x"; - - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", - "x x x x x x x x x x x x x x x x"; - ; + id = "4433"; + desc = "AT90S4433"; + stk500_devcode = 0x51; + avr910_devcode = 0x30; + signature = 0x1e 0x92 0x03; + chip_erase_delay = 20000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 0; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 15; + chiperasepolltimeout = 0; + programfusepulsewidth = 2; + programfusepolltimeout = 0; + programlockpulsewidth = 0; + programlockpolltimeout = 1; + + memory "eeprom" + size = 256; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0x00; + readback_p2 = 0xff; + read = " 1 0 1 0 0 0 0 0 x x x x x x x x", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0 x x x x x x x x", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 128; + readsize = 256; + ; + memory "flash" + size = 4096; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write_lo = " 0 1 0 0 0 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + write_hi = " 0 1 0 0 1 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 128; + readsize = 256; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "fuse" + size = 1; + min_write_delay = 9000; + max_write_delay = 20000; + pwroff_after_write = yes; + read = "0 1 0 1 0 0 0 0 x x x x x x x x", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 i i i i i", + "x x x x x x x x x x x x x x x x"; + ; + memory "lock" + size = 1; + min_write_delay = 9000; + max_write_delay = 20000; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", + "x x x x x x x x x x x x x o o x"; + + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", + "x x x x x x x x x x x x x x x x"; + ; ; #------------------------------------------------------------ @@ -2114,82 +2114,82 @@ part #------------------------------------------------------------ part - id = "4434"; + id = "4434"; ##### WARNING: No XML file for device 'AT90S4434'! ##### - desc = "AT90S4434"; - stk500_devcode = 0x52; - avr910_devcode = 0x6c; - signature = 0x1e 0x92 0x02; - chip_erase_delay = 20000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - memory "eeprom" - size = 256; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0x00; - readback_p2 = 0xff; - read = " 1 0 1 0 0 0 0 0 x x x x x x x x", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0 x x x x x x x x", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - ; - memory "flash" - size = 4096; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write_lo = " 0 1 0 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - write_hi = " 0 1 0 0 1 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "fuse" - size = 1; - min_write_delay = 9000; - max_write_delay = 20000; - read = "0 1 0 1 0 0 0 0 x x x x x x x x", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 i i i i i", - "x x x x x x x x x x x x x x x x"; - ; - memory "lock" - size = 1; - min_write_delay = 9000; - max_write_delay = 20000; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", - "x x x x x x x x x x x x x o o x"; - - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", - "x x x x x x x x x x x x x x x x"; - ; + desc = "AT90S4434"; + stk500_devcode = 0x52; + avr910_devcode = 0x6c; + signature = 0x1e 0x92 0x02; + chip_erase_delay = 20000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + memory "eeprom" + size = 256; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0x00; + readback_p2 = 0xff; + read = " 1 0 1 0 0 0 0 0 x x x x x x x x", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0 x x x x x x x x", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + ; + memory "flash" + size = 4096; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write_lo = " 0 1 0 0 0 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + write_hi = " 0 1 0 0 1 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "fuse" + size = 1; + min_write_delay = 9000; + max_write_delay = 20000; + read = "0 1 0 1 0 0 0 0 x x x x x x x x", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 i i i i i", + "x x x x x x x x x x x x x x x x"; + ; + memory "lock" + size = 1; + min_write_delay = 9000; + max_write_delay = 20000; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", + "x x x x x x x x x x x x x o o x"; + + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", + "x x x x x x x x x x x x x x x x"; + ; ; #------------------------------------------------------------ @@ -2197,113 +2197,113 @@ part #------------------------------------------------------------ part - id = "8515"; - desc = "AT90S8515"; - stk500_devcode = 0x60; - avr910_devcode = 0x38; - signature = 0x1e 0x93 0x01; - chip_erase_delay = 20000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = + id = "8515"; + desc = "AT90S8515"; + stk500_devcode = 0x60; + avr910_devcode = 0x38; + signature = 0x1e 0x93 0x01; + chip_erase_delay = 20000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 0; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - resetdelay = 15; - chiperasepulsewidth = 15; - chiperasepolltimeout = 0; - programfusepulsewidth = 2; - programfusepolltimeout = 0; - programlockpulsewidth = 0; - programlockpolltimeout = 1; - - memory "eeprom" - size = 512; - min_write_delay = 4000; - max_write_delay = 9000; - readback_p1 = 0x80; - readback_p2 = 0x7f; - read = " 1 0 1 0 0 0 0 0 x x x x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0 x x x x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 128; - readsize = 256; - ; - memory "flash" - size = 8192; - min_write_delay = 4000; - max_write_delay = 9000; - readback_p1 = 0x7f; - readback_p2 = 0x7f; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write_lo = " 0 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - write_hi = " 0 1 0 0 1 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 128; - readsize = 256; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "fuse" - size = 1; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 0; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + resetdelay = 15; + chiperasepulsewidth = 15; + chiperasepolltimeout = 0; + programfusepulsewidth = 2; + programfusepolltimeout = 0; + programlockpulsewidth = 0; + programlockpolltimeout = 1; + + memory "eeprom" + size = 512; + min_write_delay = 4000; + max_write_delay = 9000; + readback_p1 = 0x80; + readback_p2 = 0x7f; + read = " 1 0 1 0 0 0 0 0 x x x x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0 x x x x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 128; + readsize = 256; + ; + memory "flash" + size = 8192; + min_write_delay = 4000; + max_write_delay = 9000; + readback_p1 = 0x7f; + readback_p2 = 0x7f; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write_lo = " 0 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + write_hi = " 0 1 0 0 1 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 128; + readsize = 256; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "fuse" + size = 1; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", "x x x x x x x x x x x x x x x x"; - min_write_delay = 9000; - max_write_delay = 9000; - ; + min_write_delay = 9000; + max_write_delay = 9000; + ; ; #------------------------------------------------------------ @@ -2311,120 +2311,120 @@ part #------------------------------------------------------------ part - id = "8535"; - desc = "AT90S8535"; - stk500_devcode = 0x61; - avr910_devcode = 0x68; - signature = 0x1e 0x93 0x03; - chip_erase_delay = 20000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 0; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 15; - chiperasepolltimeout = 0; - programfusepulsewidth = 2; - programfusepolltimeout = 0; - programlockpulsewidth = 0; - programlockpolltimeout = 1; - - memory "eeprom" - size = 512; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0x00; - readback_p2 = 0xff; - read = " 1 0 1 0 0 0 0 0 x x x x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0 x x x x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 128; - readsize = 256; - ; - memory "flash" - size = 8192; - min_write_delay = 9000; - max_write_delay = 20000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write_lo = " 0 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - write_hi = " 0 1 0 0 1 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 128; - readsize = 256; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "fuse" - size = 1; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", + id = "8535"; + desc = "AT90S8535"; + stk500_devcode = 0x61; + avr910_devcode = 0x68; + signature = 0x1e 0x93 0x03; + chip_erase_delay = 20000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 0; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 15; + chiperasepolltimeout = 0; + programfusepulsewidth = 2; + programfusepolltimeout = 0; + programlockpulsewidth = 0; + programlockpolltimeout = 1; + + memory "eeprom" + size = 512; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0x00; + readback_p2 = 0xff; + read = " 1 0 1 0 0 0 0 0 x x x x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0 x x x x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 128; + readsize = 256; + ; + memory "flash" + size = 8192; + min_write_delay = 9000; + max_write_delay = 20000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write_lo = " 0 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + write_hi = " 0 1 0 0 1 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 128; + readsize = 256; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "fuse" + size = 1; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", "x x x x x x x x x x x x x x x o"; - write = "1 0 1 0 1 1 0 0 1 0 1 1 1 1 1 i", + write = "1 0 1 0 1 1 0 0 1 0 1 1 1 1 1 i", "x x x x x x x x x x x x x x x x"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", + min_write_delay = 9000; + max_write_delay = 9000; + ; + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", "x x x x x x x x o o x x x x x x"; - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", "x x x x x x x x x x x x x x x x"; - min_write_delay = 9000; - max_write_delay = 9000; - ; + min_write_delay = 9000; + max_write_delay = 9000; + ; ; #------------------------------------------------------------ @@ -2432,138 +2432,138 @@ part #------------------------------------------------------------ part - id = "m103"; - desc = "ATMEGA103"; - stk500_devcode = 0xB1; - avr910_devcode = 0x41; - signature = 0x1e 0x97 0x01; - chip_erase_delay = 112000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x8E, 0x9E, 0x2E, 0x3E, 0xAE, 0xBE, - 0x4E, 0x5E, 0xCE, 0xDE, 0x6E, 0x7E, 0xEE, 0xDE, - 0x66, 0x76, 0xE6, 0xF6, 0x6A, 0x7A, 0xEA, 0x7A, - 0x7F, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 0; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 15; - chiperasepolltimeout = 0; - programfusepulsewidth = 2; - programfusepolltimeout = 0; - programlockpulsewidth = 0; - programlockpolltimeout = 10; - - memory "eeprom" - size = 4096; - min_write_delay = 4000; - max_write_delay = 9000; - readback_p1 = 0x80; - readback_p2 = 0x7f; + id = "m103"; + desc = "ATMEGA103"; + stk500_devcode = 0xB1; + avr910_devcode = 0x41; + signature = 0x1e 0x97 0x01; + chip_erase_delay = 112000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x8E, 0x9E, 0x2E, 0x3E, 0xAE, 0xBE, + 0x4E, 0x5E, 0xCE, 0xDE, 0x6E, 0x7E, 0xEE, 0xDE, + 0x66, 0x76, 0xE6, 0xF6, 0x6A, 0x7A, 0xEA, 0x7A, + 0x7F, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 0; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 15; + chiperasepolltimeout = 0; + programfusepulsewidth = 2; + programfusepolltimeout = 0; + programlockpulsewidth = 0; + programlockpolltimeout = 10; + + memory "eeprom" + size = 4096; + min_write_delay = 4000; + max_write_delay = 9000; + readback_p1 = 0x80; + readback_p2 = 0x7f; read = " 1 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 64; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 131072; - page_size = 256; - num_pages = 512; - min_write_delay = 22000; - max_write_delay = 56000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x11; - delay = 70; - blocksize = 256; - readsize = 256; - ; - - memory "fuse" - size = 1; - read = "0 1 0 1 0 0 0 0 x x x x x x x x", - "x x x x x x x x x x o x o 1 o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 1 i 1 i i", - "x x x x x x x x x x x x x x x x"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", - "x x x x x x x x x x x x x o o x"; - - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", - "x x x x x x x x x x x x x x x x"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 64; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 131072; + page_size = 256; + num_pages = 512; + min_write_delay = 22000; + max_write_delay = 56000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x11; + delay = 70; + blocksize = 256; + readsize = 256; + ; + + memory "fuse" + size = 1; + read = "0 1 0 1 0 0 0 0 x x x x x x x x", + "x x x x x x x x x x o x o 1 o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 1 i 1 i i", + "x x x x x x x x x x x x x x x x"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", + "x x x x x x x x x x x x x o o x"; + + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 i i 1", + "x x x x x x x x x x x x x x x x"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; @@ -2572,177 +2572,177 @@ part #------------------------------------------------------------ part - id = "m64"; - desc = "ATMEGA64"; - has_jtag = yes; - stk500_devcode = 0xA0; - avr910_devcode = 0x45; - signature = 0x1e 0x96 0x02; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 6; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x22; - spmcr = 0x68; - allowfullpagebitstream = yes; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 2048; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = " 1 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 20; - blocksize = 64; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 65536; - page_size = 256; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 6; - blocksize = 128; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 4; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + id = "m64"; + desc = "ATMEGA64"; + has_jtag = yes; + stk500_devcode = 0xA0; + avr910_devcode = 0x45; + signature = 0x1e 0x96 0x02; + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 6; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x22; + spmcr = 0x68; + allowfullpagebitstream = yes; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 2048; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = " 1 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 20; + blocksize = 64; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 65536; + page_size = 256; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 6; + blocksize = 128; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 4; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; @@ -2753,177 +2753,177 @@ part #------------------------------------------------------------ part - id = "m128"; - desc = "ATMEGA128"; - has_jtag = yes; - stk500_devcode = 0xB2; - avr910_devcode = 0x43; - signature = 0x1e 0x97 0x02; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 6; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x22; - spmcr = 0x68; - rampz = 0x3b; - allowfullpagebitstream = yes; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 4096; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = " 1 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 12; - blocksize = 64; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 131072; - page_size = 256; - num_pages = 512; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 6; - blocksize = 128; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 4; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + id = "m128"; + desc = "ATMEGA128"; + has_jtag = yes; + stk500_devcode = 0xB2; + avr910_devcode = 0x43; + signature = 0x1e 0x97 0x02; + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 6; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x22; + spmcr = 0x68; + rampz = 0x3b; + allowfullpagebitstream = yes; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 4096; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = " 1 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 12; + blocksize = 64; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 131072; + page_size = 256; + num_pages = 512; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 6; + blocksize = 128; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 4; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -2931,189 +2931,189 @@ part #------------------------------------------------------------ part - id = "c128"; - desc = "AT90CAN128"; - has_jtag = yes; - stk500_devcode = 0xB3; + id = "c128"; + desc = "AT90CAN128"; + has_jtag = yes; + stk500_devcode = 0xB3; # avr910_devcode = 0x43; - signature = 0x1e 0x97 0x81; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 6; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - eecr = 0x3f; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 4096; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + signature = 0x1e 0x97 0x81; + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 6; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + eecr = 0x3f; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 4096; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 0 x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 0 x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 0 x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 0 x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x a11 a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 131072; - page_size = 256; - num_pages = 512; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 20; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 131072; + page_size = 256; + num_pages = 512; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -3121,189 +3121,189 @@ part #------------------------------------------------------------ part - id = "c64"; - desc = "AT90CAN64"; - has_jtag = yes; - stk500_devcode = 0xB3; + id = "c64"; + desc = "AT90CAN64"; + has_jtag = yes; + stk500_devcode = 0xB3; # avr910_devcode = 0x43; - signature = 0x1e 0x96 0x81; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 6; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - eecr = 0x3f; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 2048; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + signature = 0x1e 0x96 0x81; + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 6; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + eecr = 0x3f; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 2048; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 0 x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 0 x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 0 x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 0 x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 65536; - page_size = 256; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 20; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 65536; + page_size = 256; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -3311,189 +3311,189 @@ part #------------------------------------------------------------ part - id = "c32"; - desc = "AT90CAN32"; - has_jtag = yes; - stk500_devcode = 0xB3; + id = "c32"; + desc = "AT90CAN32"; + has_jtag = yes; + stk500_devcode = 0xB3; # avr910_devcode = 0x43; - signature = 0x1e 0x95 0x81; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 6; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - eecr = 0x3f; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 1024; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + signature = 0x1e 0x95 0x81; + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 6; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + eecr = 0x3f; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 1024; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 0 x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 0 x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 0 x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 0 x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 32768; - page_size = 256; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 20; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 32768; + page_size = 256; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; @@ -3502,174 +3502,174 @@ part #------------------------------------------------------------ part - id = "m16"; - desc = "ATMEGA16"; - has_jtag = yes; - stk500_devcode = 0x82; - avr910_devcode = 0x74; - signature = 0x1e 0x94 0x03; - pagel = 0xd7; - bs2 = 0xa0; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = + id = "m16"; + desc = "ATMEGA16"; + has_jtag = yes; + stk500_devcode = 0x82; + avr910_devcode = 0x74; + signature = 0x1e 0x94 0x03; + pagel = 0xd7; + bs2 = 0xa0; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 100; - latchcycles = 6; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - resetdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - allowfullpagebitstream = yes; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 512; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + hventerstabdelay = 100; + progmodedelay = 100; + latchcycles = 6; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + resetdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + allowfullpagebitstream = yes; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 512; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x a9 a8", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x04; - delay = 10; - blocksize = 128; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 16384; - page_size = 128; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 6; - blocksize = 128; - readsize = 256; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "calibration" - size = 4; - - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; + mode = 0x04; + delay = 10; + blocksize = 128; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 16384; + page_size = 128; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 6; + blocksize = 128; + readsize = 256; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "calibration" + size = 4; + + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; ; @@ -3680,187 +3680,187 @@ part # close to ATmega16 part - id = "m164p"; - desc = "ATMEGA164P"; - has_jtag = yes; - stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one - avr910_devcode = 0x74; - signature = 0x1e 0x94 0x0a; - pagel = 0xd7; - bs2 = 0xa0; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 512; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + id = "m164p"; + desc = "ATMEGA164P"; + has_jtag = yes; + stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one + avr910_devcode = 0x74; + signature = 0x1e 0x94 0x0a; + pagel = 0xd7; + bs2 = 0xa0; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 512; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x a9 a8", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 128; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 16384; - page_size = 128; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 6; - blocksize = 128; - readsize = 256; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x 1 1 1 1 1 i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 128; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 16384; + page_size = 128; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 6; + blocksize = 128; + readsize = 256; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x 1 1 1 1 1 i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; @@ -3871,187 +3871,187 @@ part # similar to ATmega164P part - id = "m324p"; - desc = "ATMEGA324P"; - has_jtag = yes; - stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one - avr910_devcode = 0x74; - signature = 0x1e 0x95 0x08; - pagel = 0xd7; - bs2 = 0xa0; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 1024; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + id = "m324p"; + desc = "ATMEGA324P"; + has_jtag = yes; + stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one + avr910_devcode = 0x74; + signature = 0x1e 0x95 0x08; + pagel = 0xd7; + bs2 = 0xa0; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 1024; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x a10 a9 a8", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 128; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 32768; - page_size = 128; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x 1 1 1 1 1 i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 128; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 32768; + page_size = 128; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x 1 1 1 1 1 i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; @@ -4062,187 +4062,187 @@ part # similar to ATmega164 part - id = "m644"; - desc = "ATMEGA644"; - has_jtag = yes; - stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one - avr910_devcode = 0x74; - signature = 0x1e 0x96 0x09; - pagel = 0xd7; - bs2 = 0xa0; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 6; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 2048; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + id = "m644"; + desc = "ATMEGA644"; + has_jtag = yes; + stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one + avr910_devcode = 0x74; + signature = 0x1e 0x96 0x09; + pagel = 0xd7; + bs2 = 0xa0; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 6; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 2048; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x a11 a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 128; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 65536; - page_size = 256; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x 1 1 1 1 1 i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 128; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 65536; + page_size = 256; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x 1 1 1 1 1 i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -4252,187 +4252,187 @@ part # similar to ATmega164p part - id = "m644p"; - desc = "ATMEGA644P"; - has_jtag = yes; - stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one - avr910_devcode = 0x74; - signature = 0x1e 0x96 0x0a; - pagel = 0xd7; - bs2 = 0xa0; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 6; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 2048; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + id = "m644p"; + desc = "ATMEGA644P"; + has_jtag = yes; + stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one + avr910_devcode = 0x74; + signature = 0x1e 0x96 0x0a; + pagel = 0xd7; + bs2 = 0xa0; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 6; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 2048; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x a11 a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 128; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 65536; - page_size = 256; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x 1 1 1 1 1 i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 128; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 65536; + page_size = 256; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x 1 1 1 1 1 i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; @@ -4444,187 +4444,187 @@ part # similar to ATmega164p part - id = "m1284p"; - desc = "ATMEGA1284P"; - has_jtag = yes; - stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one - avr910_devcode = 0x74; - signature = 0x1e 0x97 0x05; - pagel = 0xd7; - bs2 = 0xa0; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 6; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 4096; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + id = "m1284p"; + desc = "ATMEGA1284P"; + has_jtag = yes; + stk500_devcode = 0x82; # no STK500v1 support, use the ATmega16 one + avr910_devcode = 0x74; + signature = 0x1e 0x97 0x05; + pagel = 0xd7; + bs2 = 0xa0; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 6; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 4096; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x a11 a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 128; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 131072; - page_size = 256; - num_pages = 512; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 10; - blocksize = 256; - readsize = 256; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x 1 1 1 1 1 i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 128; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 131072; + page_size = 256; + num_pages = 512; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 10; + blocksize = 256; + readsize = 256; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x 1 1 1 1 1 i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; @@ -4634,193 +4634,193 @@ part #------------------------------------------------------------ part - id = "m162"; - desc = "ATMEGA162"; - has_jtag = yes; - stk500_devcode = 0x83; - avr910_devcode = 0x63; - signature = 0x1e 0x94 0x04; - chip_erase_delay = 9000; - pagel = 0xd7; - bs2 = 0xa0; - - idr = 0x04; - spmcr = 0x57; - allowfullpagebitstream = yes; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - memory "flash" - paged = yes; - size = 16384; - page_size = 128; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 128; - readsize = 256; - - ; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 6; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 512; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; - - read = " 1 0 1 0 0 0 0 0", - " 0 0 x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " 0 0 x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + id = "m162"; + desc = "ATMEGA162"; + has_jtag = yes; + stk500_devcode = 0x83; + avr910_devcode = 0x63; + signature = 0x1e 0x94 0x04; + chip_erase_delay = 9000; + pagel = 0xd7; + bs2 = 0xa0; + + idr = 0x04; + spmcr = 0x57; + allowfullpagebitstream = yes; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + memory "flash" + paged = yes; + size = 16384; + page_size = 128; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + mode = 0x41; + delay = 10; + blocksize = 128; + readsize = 256; + + ; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 6; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 512; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; + + read = " 1 0 1 0 0 0 0 0", + " 0 0 x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " 0 0 x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x a9 a8", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 4; - readsize = 256; - ; + mode = 0x41; + delay = 20; + blocksize = 4; + readsize = 256; + ; - memory "lfuse" - size = 1; - min_write_delay = 16000; - max_write_delay = 16000; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; + memory "lfuse" + size = 1; + min_write_delay = 16000; + max_write_delay = 16000; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; - memory "hfuse" - size = 1; - min_write_delay = 16000; - max_write_delay = 16000; + memory "hfuse" + size = 1; + min_write_delay = 16000; + max_write_delay = 16000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; - memory "efuse" - size = 1; - min_write_delay = 16000; - max_write_delay = 16000; + memory "efuse" + size = 1; + min_write_delay = 16000; + max_write_delay = 16000; - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x 1 1 1 1 1 i i i"; - ; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x 1 1 1 1 1 i i i"; + ; - memory "lock" - size = 1; - min_write_delay = 16000; - max_write_delay = 16000; + memory "lock" + size = 1; + min_write_delay = 16000; + max_write_delay = 16000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; - memory "signature" - size = 3; + memory "signature" + size = 3; - read = "0 0 1 1 0 0 0 0 0 0 x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + read = "0 0 1 1 0 0 0 0 0 0 x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; - memory "calibration" - size = 1; + memory "calibration" + size = 1; - read = "0 0 1 1 1 0 0 0 0 0 x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + read = "0 0 1 1 1 0 0 0 0 0 x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; @@ -4830,157 +4830,157 @@ part #------------------------------------------------------------ part - id = "m163"; - desc = "ATMEGA163"; - stk500_devcode = 0x81; - avr910_devcode = 0x64; - signature = 0x1e 0x94 0x02; - chip_erase_delay = 32000; - pagel = 0xd7; - bs2 = 0xa0; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 0; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 30; - programfusepulsewidth = 0; - programfusepolltimeout = 2; - programlockpulsewidth = 0; - programlockpolltimeout = 2; + id = "m163"; + desc = "ATMEGA163"; + stk500_devcode = 0x81; + avr910_devcode = 0x64; + signature = 0x1e 0x94 0x02; + chip_erase_delay = 32000; + pagel = 0xd7; + bs2 = 0xa0; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 0; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 30; + programfusepulsewidth = 0; + programfusepolltimeout = 2; + programlockpulsewidth = 0; + programlockpolltimeout = 2; memory "eeprom" - size = 512; - min_write_delay = 4000; - max_write_delay = 4000; - readback_p1 = 0xff; - readback_p2 = 0xff; + size = 512; + min_write_delay = 4000; + max_write_delay = 4000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - mode = 0x41; - delay = 20; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 16384; - page_size = 128; - num_pages = 128; - min_write_delay = 16000; - max_write_delay = 16000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x11; - delay = 20; - blocksize = 128; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o x x o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i 1 1 i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x x x x x 1 o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x 1 1 1 1 1 i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x 0 x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + mode = 0x41; + delay = 20; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 16384; + page_size = 128; + num_pages = 128; + min_write_delay = 16000; + max_write_delay = 16000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x11; + delay = 20; + blocksize = 128; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o x x o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i 1 1 i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x x x x x 1 o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x 1 1 1 1 1 i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x 0 x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -4988,179 +4988,179 @@ part #------------------------------------------------------------ part - id = "m169"; - desc = "ATMEGA169"; - has_jtag = yes; - stk500_devcode = 0x85; - avr910_devcode = 0x78; - signature = 0x1e 0x94 0x05; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; + id = "m169"; + desc = "ATMEGA169"; + has_jtag = yes; + stk500_devcode = 0x85; + avr910_devcode = 0x78; + signature = 0x1e 0x94 0x05; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 512; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 512; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x a8", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 16384; - page_size = 128; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 128; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - ; - - memory "lock" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 20; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 16384; + page_size = 128; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 128; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + ; + + memory "lock" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -5168,182 +5168,182 @@ part #------------------------------------------------------------ part - id = "m329"; - desc = "ATMEGA329"; - has_jtag = yes; + id = "m329"; + desc = "ATMEGA329"; + has_jtag = yes; # stk500_devcode = 0x85; # no STK500 support, only STK500v2 # avr910_devcode = 0x?; # try the ATmega169 one: - avr910_devcode = 0x75; - signature = 0x1e 0x95 0x03; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; + avr910_devcode = 0x75; + signature = 0x1e 0x95 0x03; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 1024; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 1024; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x a9 a8", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 32768; - page_size = 128; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "efuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 20; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 32768; + page_size = 128; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "efuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -5352,182 +5352,182 @@ part # Identical to ATmega329 except of the signature part - id = "m329p"; - desc = "ATMEGA329P"; - has_jtag = yes; + id = "m329p"; + desc = "ATMEGA329P"; + has_jtag = yes; # stk500_devcode = 0x85; # no STK500 support, only STK500v2 # avr910_devcode = 0x?; # try the ATmega169 one: - avr910_devcode = 0x75; - signature = 0x1e 0x95 0x0b; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; + avr910_devcode = 0x75; + signature = 0x1e 0x95 0x0b; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 1024; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 1024; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x a9 a8", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 32768; - page_size = 128; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "efuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 20; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 32768; + page_size = 128; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "efuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -5537,182 +5537,182 @@ part # identical to ATmega329 part - id = "m3290"; - desc = "ATMEGA3290"; - has_jtag = yes; + id = "m3290"; + desc = "ATMEGA3290"; + has_jtag = yes; # stk500_devcode = 0x85; # no STK500 support, only STK500v2 # avr910_devcode = 0x?; # try the ATmega169 one: - avr910_devcode = 0x75; - signature = 0x1e 0x95 0x04; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; + avr910_devcode = 0x75; + signature = 0x1e 0x95 0x04; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 1024; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 1024; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x a9 a8", " a7 a6 a5 a4 a3 a3 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 32768; - page_size = 128; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "efuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 20; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 32768; + page_size = 128; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "efuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -5722,182 +5722,182 @@ part # identical to ATmega3290 except of the signature part - id = "m3290p"; - desc = "ATMEGA3290P"; - has_jtag = yes; + id = "m3290p"; + desc = "ATMEGA3290P"; + has_jtag = yes; # stk500_devcode = 0x85; # no STK500 support, only STK500v2 # avr910_devcode = 0x?; # try the ATmega169 one: - avr910_devcode = 0x75; - signature = 0x1e 0x95 0x0c; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; + avr910_devcode = 0x75; + signature = 0x1e 0x95 0x0c; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 1024; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 1024; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x a9 a8", " a7 a6 a5 a4 a3 a3 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 32768; - page_size = 128; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "efuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 20; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 32768; + page_size = 128; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "efuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -5905,182 +5905,182 @@ part #------------------------------------------------------------ part - id = "m649"; - desc = "ATMEGA649"; - has_jtag = yes; + id = "m649"; + desc = "ATMEGA649"; + has_jtag = yes; # stk500_devcode = 0x85; # no STK500 support, only STK500v2 # avr910_devcode = 0x?; # try the ATmega169 one: - avr910_devcode = 0x75; - signature = 0x1e 0x96 0x03; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; + avr910_devcode = 0x75; + signature = 0x1e 0x96 0x03; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 2048; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 2048; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 65536; - page_size = 256; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "efuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 20; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 65536; + page_size = 256; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "efuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -6090,192 +6090,192 @@ part # identical to ATmega649 part - id = "m6490"; - desc = "ATMEGA6490"; - has_jtag = yes; + id = "m6490"; + desc = "ATMEGA6490"; + has_jtag = yes; # stk500_devcode = 0x85; # no STK500 support, only STK500v2 # avr910_devcode = 0x?; # try the ATmega169 one: - avr910_devcode = 0x75; - signature = 0x1e 0x96 0x04; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; + avr910_devcode = 0x75; + signature = 0x1e 0x96 0x04; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 2048; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 2048; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 65536; - page_size = 256; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "efuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 20; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 65536; + page_size = 256; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "efuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -6283,174 +6283,174 @@ part #------------------------------------------------------------ part - id = "m32"; - desc = "ATMEGA32"; - has_jtag = yes; - stk500_devcode = 0x91; - avr910_devcode = 0x72; - signature = 0x1e 0x95 0x02; - chip_erase_delay = 9000; - pagel = 0xd7; - bs2 = 0xa0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 6; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - allowfullpagebitstream = yes; + id = "m32"; + desc = "ATMEGA32"; + has_jtag = yes; + stk500_devcode = 0x91; + avr910_devcode = 0x72; + signature = 0x1e 0x95 0x02; + chip_erase_delay = 9000; + pagel = 0xd7; + bs2 = 0xa0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 6; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + allowfullpagebitstream = yes; memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 1024; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = " 1 0 1 0 0 0 0 0", - " 0 0 x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " 0 0 x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 1024; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = " 1 0 1 0 0 0 0 0", + " 0 0 x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " 0 0 x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x a9 a8", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x04; - delay = 10; - blocksize = 64; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 32768; - page_size = 128; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 6; - blocksize = 64; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 4; - read = "0 0 1 1 1 0 0 0 0 0 x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; + mode = 0x04; + delay = 10; + blocksize = 64; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 32768; + page_size = 128; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 6; + blocksize = 64; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 4; + read = "0 0 1 1 1 0 0 0 0 0 x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -6458,138 +6458,138 @@ part #------------------------------------------------------------ part - id = "m161"; - desc = "ATMEGA161"; - stk500_devcode = 0x80; - avr910_devcode = 0x60; - signature = 0x1e 0x94 0x01; - chip_erase_delay = 28000; - pagel = 0xd7; - bs2 = 0xa0; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 0; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 30; - programfusepulsewidth = 0; - programfusepolltimeout = 2; - programlockpulsewidth = 0; - programlockpolltimeout = 2; + id = "m161"; + desc = "ATMEGA161"; + stk500_devcode = 0x80; + avr910_devcode = 0x60; + signature = 0x1e 0x94 0x01; + chip_erase_delay = 28000; + pagel = 0xd7; + bs2 = 0xa0; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 0; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 30; + programfusepulsewidth = 0; + programfusepolltimeout = 2; + programlockpulsewidth = 0; + programlockpolltimeout = 2; memory "eeprom" - size = 512; - min_write_delay = 3400; - max_write_delay = 3400; - readback_p1 = 0xff; - readback_p2 = 0xff; + size = 512; + min_write_delay = 3400; + max_write_delay = 3400; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " x x x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 5; - blocksize = 128; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 16384; - page_size = 128; - num_pages = 128; - min_write_delay = 14000; - max_write_delay = 14000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 16; - blocksize = 128; - readsize = 256; - ; - - memory "fuse" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 0 0 0 0 x x x x x x x x", - "x x x x x x x x x o x o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 x x x x x", - "x x x x x x x x 1 i 1 i i i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + " x x x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 5; + blocksize = 128; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 16384; + page_size = 128; + num_pages = 128; + min_write_delay = 14000; + max_write_delay = 14000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 16; + blocksize = 128; + readsize = 256; + ; + + memory "fuse" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 0 0 0 0 x x x x x x x x", + "x x x x x x x x x o x o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 x x x x x", + "x x x x x x x x 1 i 1 i i i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; @@ -6598,158 +6598,158 @@ part #------------------------------------------------------------ part - id = "m8"; - desc = "ATMEGA8"; - stk500_devcode = 0x70; - avr910_devcode = 0x76; - signature = 0x1e 0x93 0x07; - pagel = 0xd7; - bs2 = 0xc2; - chip_erase_delay = 10000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = + id = "m8"; + desc = "ATMEGA8"; + stk500_devcode = 0x70; + avr910_devcode = 0x76; + signature = 0x1e 0x93 0x07; + pagel = 0xd7; + bs2 = 0xc2; + chip_erase_delay = 10000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 2; - resetdelayus = 0; - hvleavestabdelay = 15; - resetdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - size = 512; - page_size = 4; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 2; + resetdelayus = 0; + hvleavestabdelay = 15; + resetdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + size = 512; + page_size = 4; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 20; - blocksize = 128; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 8192; - page_size = 64; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 0 x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 0 x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 10; - blocksize = 64; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "calibration" - size = 4; - read = "0 0 1 1 1 0 0 0 0 0 x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + " 0 0 x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 20; + blocksize = 128; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 8192; + page_size = 64; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 0 x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 0 x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 10; + blocksize = 64; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "calibration" + size = 4; + read = "0 0 1 1 1 0 0 0 0 0 x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; @@ -6759,154 +6759,154 @@ part #------------------------------------------------------------ part - id = "m8515"; - desc = "ATMEGA8515"; - stk500_devcode = 0x63; - avr910_devcode = 0x3A; - signature = 0x1e 0x93 0x06; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 6; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - size = 512; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + id = "m8515"; + desc = "ATMEGA8515"; + stk500_devcode = 0x63; + avr910_devcode = 0x3A; + signature = 0x1e 0x93 0x06; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 6; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + size = 512; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 10; - blocksize = 128; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 8192; - page_size = 64; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 0 x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 0 x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 6; - blocksize = 64; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "calibration" - size = 4; - read = "0 0 1 1 1 0 0 0 0 0 x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + " 0 0 x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 10; + blocksize = 128; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 8192; + page_size = 64; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 0 x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 0 x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 6; + blocksize = 64; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "calibration" + size = 4; + read = "0 0 1 1 1 0 0 0 0 0 x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; @@ -6917,156 +6917,156 @@ part #------------------------------------------------------------ part - id = "m8535"; - desc = "ATMEGA8535"; - stk500_devcode = 0x64; - avr910_devcode = 0x69; - signature = 0x1e 0x93 0x08; - pagel = 0xd7; - bs2 = 0xa0; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 6; - togglevtg = 0; - poweroffdelay = 0; - resetdelayms = 0; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - size = 512; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; + id = "m8535"; + desc = "ATMEGA8535"; + stk500_devcode = 0x64; + avr910_devcode = 0x69; + signature = 0x1e 0x93 0x08; + pagel = 0xd7; + bs2 = 0xa0; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 6; + togglevtg = 0; + poweroffdelay = 0; + resetdelayms = 0; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + size = 512; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 x x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - mode = 0x04; - delay = 10; - blocksize = 128; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 8192; - page_size = 64; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 0 x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 0 x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 6; - blocksize = 64; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 2000; - max_write_delay = 2000; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "calibration" - size = 4; - read = "0 0 1 1 1 0 0 0 0 0 x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + " 0 0 x x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + mode = 0x04; + delay = 10; + blocksize = 128; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 8192; + page_size = 64; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 0 x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 0 x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 6; + blocksize = 64; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 2000; + max_write_delay = 2000; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "calibration" + size = 4; + read = "0 0 1 1 1 0 0 0 0 0 x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; @@ -7075,153 +7075,153 @@ part #------------------------------------------------------------ part - id = "t26"; - desc = "ATTINY26"; - stk500_devcode = 0x21; - avr910_devcode = 0x5e; - signature = 0x1e 0x91 0x09; - pagel = 0xb3; - bs2 = 0xb2; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0xC4, 0xE4, 0xC4, 0xE4, 0xCC, 0xEC, 0xCC, 0xEC, - 0xD4, 0xF4, 0xD4, 0xF4, 0xDC, 0xFC, 0xDC, 0xFC, - 0xC8, 0xE8, 0xD8, 0xF8, 0x4C, 0x6C, 0x5C, 0x7C, - 0xEC, 0xBC, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 2; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - size = 128; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 x x x x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 x x x x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - mode = 0x04; - delay = 10; - blocksize = 64; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 2048; - page_size = 32; - num_pages = 64; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x x x a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x x x a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 x x x x", - " x x x x x x x x"; - - mode = 0x21; - delay = 6; - blocksize = 16; - readsize = 256; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", - "x x x x x x x x x x x x x x o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 1 i i", - "x x x x x x x x x x x x x x x x"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x x x x i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x x x x o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 4; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; + id = "t26"; + desc = "ATTINY26"; + stk500_devcode = 0x21; + avr910_devcode = 0x5e; + signature = 0x1e 0x91 0x09; + pagel = 0xb3; + bs2 = 0xb2; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0xC4, 0xE4, 0xC4, 0xE4, 0xCC, 0xEC, 0xCC, 0xEC, + 0xD4, 0xF4, 0xD4, 0xF4, 0xDC, 0xFC, 0xDC, 0xFC, + 0xC8, 0xE8, 0xD8, 0xF8, 0x4C, 0x6C, 0x5C, 0x7C, + 0xEC, 0xBC, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 2; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + size = 128; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 x x x x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 x x x x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + mode = 0x04; + delay = 10; + blocksize = 64; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 2048; + page_size = 32; + num_pages = 64; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x x x a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x x x a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 x x x x", + " x x x x x x x x"; + + mode = 0x21; + delay = 6; + blocksize = 16; + readsize = 256; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", + "x x x x x x x x x x x x x x o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 1 i i", + "x x x x x x x x x x x x x x x x"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x x x x i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x x x x o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 4; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; ; @@ -7232,185 +7232,185 @@ part # Close to ATtiny26 part - id = "t261"; - desc = "ATTINY261"; - has_debugwire = yes; - flash_instr = 0xB4, 0x00, 0x10; - eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, - 0xBC, 0x00, 0xB4, 0x00, 0xBA, 0x0D, 0xBB, 0xBC, - 0x99, 0xE1, 0xBB, 0xAC; + id = "t261"; + desc = "ATTINY261"; + has_debugwire = yes; + flash_instr = 0xB4, 0x00, 0x10; + eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, + 0xBC, 0x00, 0xB4, 0x00, 0xBA, 0x0D, 0xBB, 0xBC, + 0x99, 0xE1, 0xBB, 0xAC; # stk500_devcode = 0x21; # avr910_devcode = 0x5e; - signature = 0x1e 0x91 0x0c; - pagel = 0xb3; - bs2 = 0xb2; - chip_erase_delay = 4000; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0xC4, 0xE4, 0xC4, 0xE4, 0xCC, 0xEC, 0xCC, 0xEC, - 0xD4, 0xF4, 0xD4, 0xF4, 0xDC, 0xFC, 0xDC, 0xFC, - 0xC8, 0xE8, 0xD8, 0xF8, 0x4C, 0x6C, 0x5C, 0x7C, - 0xEC, 0xBC, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 2; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - paged = no; - size = 128; - page_size = 4; - num_pages = 32; - min_write_delay = 4000; - max_write_delay = 4000; - readback_p1 = 0xff; - readback_p2 = 0xff; - - read = "1 0 1 0 0 0 0 0 x x x x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 x x x x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + signature = 0x1e 0x91 0x0c; + pagel = 0xb3; + bs2 = 0xb2; + chip_erase_delay = 4000; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0xC4, 0xE4, 0xC4, 0xE4, 0xCC, 0xEC, 0xCC, 0xEC, + 0xD4, 0xF4, 0xD4, 0xF4, 0xDC, 0xFC, 0xDC, 0xFC, + 0xC8, 0xE8, 0xD8, 0xF8, 0x4C, 0x6C, 0x5C, 0x7C, + 0xEC, 0xBC, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 2; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + paged = no; + size = 128; + page_size = 4; + num_pages = 32; + min_write_delay = 4000; + max_write_delay = 4000; + readback_p1 = 0xff; + readback_p2 = 0xff; + + read = "1 0 1 0 0 0 0 0 x x x x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 x x x x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " x a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 2048; - page_size = 32; - num_pages = 64; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x x x a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x x x a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x x x x a9 a8", - " a7 a6 a5 a4 x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 32; - readsize = 256; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", - "x x x x x x x x x x x x x x o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 1 i i", - "x x x x x x x x x x x x x x x x"; - min_write_delay = 4500; - max_write_delay = 4500; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 4500; - max_write_delay = 4500; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 4500; - max_write_delay = 4500; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x x x x x x x x o"; - min_write_delay = 4500; - max_write_delay = 4500; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 2048; + page_size = 32; + num_pages = 64; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x x x a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x x x a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x x x x a9 a8", + " a7 a6 a5 a4 x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 32; + readsize = 256; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", + "x x x x x x x x x x x x x x o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 1 i i", + "x x x x x x x x x x x x x x x x"; + min_write_delay = 4500; + max_write_delay = 4500; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 4500; + max_write_delay = 4500; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 4500; + max_write_delay = 4500; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x x x x x x x x o"; + min_write_delay = 4500; + max_write_delay = 4500; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; @@ -7421,185 +7421,185 @@ part # Close to ATtiny261 part - id = "t461"; - desc = "ATTINY461"; - has_debugwire = yes; - flash_instr = 0xB4, 0x00, 0x10; - eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, - 0xBC, 0x00, 0xB4, 0x00, 0xBA, 0x0D, 0xBB, 0xBC, - 0x99, 0xE1, 0xBB, 0xAC; + id = "t461"; + desc = "ATTINY461"; + has_debugwire = yes; + flash_instr = 0xB4, 0x00, 0x10; + eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, + 0xBC, 0x00, 0xB4, 0x00, 0xBA, 0x0D, 0xBB, 0xBC, + 0x99, 0xE1, 0xBB, 0xAC; # stk500_devcode = 0x21; # avr910_devcode = 0x5e; - signature = 0x1e 0x92 0x08; - pagel = 0xb3; - bs2 = 0xb2; - chip_erase_delay = 4000; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0xC4, 0xE4, 0xC4, 0xE4, 0xCC, 0xEC, 0xCC, 0xEC, - 0xD4, 0xF4, 0xD4, 0xF4, 0xDC, 0xFC, 0xDC, 0xFC, - 0xC8, 0xE8, 0xD8, 0xF8, 0x4C, 0x6C, 0x5C, 0x7C, - 0xEC, 0xBC, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 2; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - paged = no; - size = 256; - page_size = 4; - num_pages = 64; - min_write_delay = 4000; - max_write_delay = 4000; - readback_p1 = 0xff; - readback_p2 = 0xff; - - read = " 1 0 1 0 0 0 0 0 x x x x x x x x", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0 x x x x x x x x", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + signature = 0x1e 0x92 0x08; + pagel = 0xb3; + bs2 = 0xb2; + chip_erase_delay = 4000; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0xC4, 0xE4, 0xC4, 0xE4, 0xCC, 0xEC, 0xCC, 0xEC, + 0xD4, 0xF4, 0xD4, 0xF4, 0xDC, 0xFC, 0xDC, 0xFC, + 0xC8, 0xE8, 0xD8, 0xF8, 0x4C, 0x6C, 0x5C, 0x7C, + 0xEC, 0xBC, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 2; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + paged = no; + size = 256; + page_size = 4; + num_pages = 64; + min_write_delay = 4000; + max_write_delay = 4000; + readback_p1 = 0xff; + readback_p2 = 0xff; + + read = " 1 0 1 0 0 0 0 0 x x x x x x x x", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0 x x x x x x x x", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 4096; - page_size = 64; - num_pages = 64; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 64; - readsize = 256; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", - "x x x x x x x x x x x x x x o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 1 i i", - "x x x x x x x x x x x x x x x x"; - min_write_delay = 4500; - max_write_delay = 4500; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 4500; - max_write_delay = 4500; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 4500; - max_write_delay = 4500; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x x x x x x x x o"; - min_write_delay = 4500; - max_write_delay = 4500; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 4096; + page_size = 64; + num_pages = 64; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 64; + readsize = 256; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", + "x x x x x x x x x x x x x x o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 1 i i", + "x x x x x x x x x x x x x x x x"; + min_write_delay = 4500; + max_write_delay = 4500; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 4500; + max_write_delay = 4500; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 4500; + max_write_delay = 4500; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x x x x x x x x o"; + min_write_delay = 4500; + max_write_delay = 4500; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; @@ -7610,185 +7610,185 @@ part # Close to ATtiny461 part - id = "t861"; - desc = "ATTINY861"; - has_debugwire = yes; - flash_instr = 0xB4, 0x00, 0x10; - eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, - 0xBC, 0x00, 0xB4, 0x00, 0xBA, 0x0D, 0xBB, 0xBC, - 0x99, 0xE1, 0xBB, 0xAC; + id = "t861"; + desc = "ATTINY861"; + has_debugwire = yes; + flash_instr = 0xB4, 0x00, 0x10; + eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, + 0xBC, 0x00, 0xB4, 0x00, 0xBA, 0x0D, 0xBB, 0xBC, + 0x99, 0xE1, 0xBB, 0xAC; # stk500_devcode = 0x21; # avr910_devcode = 0x5e; - signature = 0x1e 0x93 0x0d; - pagel = 0xb3; - bs2 = 0xb2; - chip_erase_delay = 4000; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 0; - - pp_controlstack = - 0xC4, 0xE4, 0xC4, 0xE4, 0xCC, 0xEC, 0xCC, 0xEC, - 0xD4, 0xF4, 0xD4, 0xF4, 0xDC, 0xFC, 0xDC, 0xFC, - 0xC8, 0xE8, 0xD8, 0xF8, 0x4C, 0x6C, 0x5C, 0x7C, - 0xEC, 0xBC, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 2; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - paged = no; - size = 512; - num_pages = 128; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4000; - readback_p1 = 0xff; - readback_p2 = 0xff; - - read = " 1 0 1 0 0 0 0 0 x x x x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0 x x x x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + signature = 0x1e 0x93 0x0d; + pagel = 0xb3; + bs2 = 0xb2; + chip_erase_delay = 4000; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 0; + + pp_controlstack = + 0xC4, 0xE4, 0xC4, 0xE4, 0xCC, 0xEC, 0xCC, 0xEC, + 0xD4, 0xF4, 0xD4, 0xF4, 0xDC, 0xFC, 0xDC, 0xFC, + 0xC8, 0xE8, 0xD8, 0xF8, 0x4C, 0x6C, 0x5C, 0x7C, + 0xEC, 0xBC, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 2; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + paged = no; + size = 512; + num_pages = 128; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4000; + readback_p1 = 0xff; + readback_p2 = 0xff; + + read = " 1 0 1 0 0 0 0 0 x x x x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0 x x x x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x a8", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 8192; - page_size = 64; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - - read_lo = " 0 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 64; - readsize = 256; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 x x x x x x x x", - "x x x x x x x x x x x x x x o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 1 1 1 i i", - "x x x x x x x x x x x x x x x x"; - min_write_delay = 4500; - max_write_delay = 4500; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 4500; - max_write_delay = 4500; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 4500; - max_write_delay = 4500; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x x x x x x x x o"; - min_write_delay = 4500; - max_write_delay = 4500; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 8192; + page_size = 64; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + + read_lo = " 0 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 64; + readsize = 256; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 x x x x x x x x", + "x x x x x x x x x x x x x x o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 1 1 1 i i", + "x x x x x x x x x x x x x x x x"; + min_write_delay = 4500; + max_write_delay = 4500; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 4500; + max_write_delay = 4500; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 4500; + max_write_delay = 4500; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x x x x x x x x o"; + min_write_delay = 4500; + max_write_delay = 4500; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; @@ -7798,185 +7798,185 @@ part #------------------------------------------------------------ part - id = "m48"; - desc = "ATMEGA48"; - has_debugwire = yes; - flash_instr = 0xB6, 0x01, 0x11; - eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, - 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, - 0x99, 0xF9, 0xBB, 0xAF; - stk500_devcode = 0x59; + id = "m48"; + desc = "ATMEGA48"; + has_debugwire = yes; + flash_instr = 0xB6, 0x01, 0x11; + eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, + 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, + 0x99, 0xF9, 0xBB, 0xAF; + stk500_devcode = 0x59; # avr910_devcode = 0x; - signature = 0x1e 0x92 0x05; - pagel = 0xd7; - bs2 = 0xc2; - chip_erase_delay = 45000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = + signature = 0x1e 0x92 0x05; + pagel = 0xd7; + bs2 = 0xc2; + chip_erase_delay = 45000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - resetdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - paged = no; - page_size = 4; - size = 256; - min_write_delay = 3600; - max_write_delay = 3600; - readback_p1 = 0xff; - readback_p2 = 0xff; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + resetdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + paged = no; + page_size = 4; + size = 256; + min_write_delay = 3600; + max_write_delay = 3600; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 0 x x x x x", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 0 x x x x x", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 0 x x x x x", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 5; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 4096; - page_size = 64; - num_pages = 64; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 64; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "efuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x x x x x x x x o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - ; - - memory "lock" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 5; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 4096; + page_size = 64; + num_pages = 64; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 64; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "efuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x x x x x x x x o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + ; + + memory "lock" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; @@ -7985,185 +7985,185 @@ part #------------------------------------------------------------ part - id = "m88"; - desc = "ATMEGA88"; - has_debugwire = yes; - flash_instr = 0xB6, 0x01, 0x11; - eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, - 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, - 0x99, 0xF9, 0xBB, 0xAF; - stk500_devcode = 0x73; + id = "m88"; + desc = "ATMEGA88"; + has_debugwire = yes; + flash_instr = 0xB6, 0x01, 0x11; + eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, + 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, + 0x99, 0xF9, 0xBB, 0xAF; + stk500_devcode = 0x73; # avr910_devcode = 0x; - signature = 0x1e 0x93 0x0a; - pagel = 0xd7; - bs2 = 0xc2; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = + signature = 0x1e 0x93 0x0a; + pagel = 0xd7; + bs2 = 0xc2; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - resetdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - paged = no; - page_size = 4; - size = 512; - min_write_delay = 3600; - max_write_delay = 3600; - readback_p1 = 0xff; - readback_p2 = 0xff; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + resetdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + paged = no; + page_size = 4; + size = 512; + min_write_delay = 3600; + max_write_delay = 3600; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 0 x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 0 x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 0 x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 0 x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x a8", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 5; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 8192; - page_size = 64; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 64; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "efuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x x x x x x o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 5; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 8192; + page_size = 64; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 64; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "efuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x x x x x x o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -8171,187 +8171,187 @@ part #------------------------------------------------------------ part - id = "m168"; - desc = "ATMEGA168"; - has_debugwire = yes; - flash_instr = 0xB6, 0x01, 0x11; - eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, - 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, - 0x99, 0xF9, 0xBB, 0xAF; - stk500_devcode = 0x86; - # avr910_devcode = 0x; - signature = 0x1e 0x94 0x06; - pagel = 0xd7; - bs2 = 0xc2; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = + id = "m168"; + desc = "ATMEGA168"; + has_debugwire = yes; + flash_instr = 0xB6, 0x01, 0x11; + eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, + 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, + 0x99, 0xF9, 0xBB, 0xAF; + stk500_devcode = 0x86; + # avr910_devcode = 0x; + signature = 0x1e 0x94 0x06; + pagel = 0xd7; + bs2 = 0xc2; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - resetdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - paged = no; - page_size = 4; - size = 512; - min_write_delay = 3600; - max_write_delay = 3600; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = " 1 0 1 0 0 0 0 0", - " 0 0 0 x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " 0 0 0 x x x x a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + resetdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + paged = no; + page_size = 4; + size = 512; + min_write_delay = 3600; + max_write_delay = 3600; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = " 1 0 1 0 0 0 0 0", + " 0 0 0 x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " 0 0 0 x x x x a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x a8", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 5; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 16384; - page_size = 128; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 128; - readsize = 256; - - ; - - memory "lfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "efuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x x x x x x o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - ; - - memory "lock" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 5; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 16384; + page_size = 128; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 128; + readsize = 256; + + ; + + memory "lfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "efuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x x x x x x o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + ; + + memory "lock" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -8359,185 +8359,185 @@ part #------------------------------------------------------------ part - id = "t88"; - desc = "attiny88"; - has_debugwire = yes; - flash_instr = 0xB6, 0x01, 0x11; - eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, - 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, - 0x99, 0xF9, 0xBB, 0xAF; - stk500_devcode = 0x73; + id = "t88"; + desc = "attiny88"; + has_debugwire = yes; + flash_instr = 0xB6, 0x01, 0x11; + eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, + 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, + 0x99, 0xF9, 0xBB, 0xAF; + stk500_devcode = 0x73; # avr910_devcode = 0x; - signature = 0x1e 0x93 0x11; - pagel = 0xd7; - bs2 = 0xc2; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = + signature = 0x1e 0x93 0x11; + pagel = 0xd7; + bs2 = 0xc2; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - resetdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - paged = no; - page_size = 4; - size = 64; - min_write_delay = 3600; - max_write_delay = 3600; - readback_p1 = 0xff; - readback_p2 = 0xff; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + resetdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + paged = no; + page_size = 4; + size = 64; + min_write_delay = 3600; + max_write_delay = 3600; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 0 x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 0 x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 0 x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; - loadpage_lo = " 1 1 0 0 0 0 0 1", + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " x a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 5; - blocksize = 4; - readsize = 64; - ; - memory "flash" - paged = yes; - size = 8192; - page_size = 64; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 64; - readsize = 256; - ; - - memory "lfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "hfuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; - - memory "efuse" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x x x x x x o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - ; - - memory "lock" - size = 1; - min_write_delay = 4500; - max_write_delay = 4500; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 5; + blocksize = 4; + readsize = 64; + ; + memory "flash" + paged = yes; + size = 8192; + page_size = 64; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 64; + readsize = 256; + ; + + memory "lfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "hfuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + ; + + memory "efuse" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x x x x x x o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + ; + + memory "lock" + size = 1; + min_write_delay = 4500; + max_write_delay = 4500; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -8545,100 +8545,100 @@ part #------------------------------------------------------------ part - id = "m328p"; - desc = "ATMEGA328P"; - has_debugwire = yes; - flash_instr = 0xB6, 0x01, 0x11; - eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, + id = "m328p"; + desc = "ATMEGA328P"; + has_debugwire = yes; + flash_instr = 0xB6, 0x01, 0x11; + eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, 0x99, 0xF9, 0xBB, 0xAF; - stk500_devcode = 0x86; - # avr910_devcode = 0x; - signature = 0x1e 0x95 0x0F; - pagel = 0xd7; - bs2 = 0xc2; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + stk500_devcode = 0x86; + # avr910_devcode = 0x; + signature = 0x1e 0x95 0x0F; + pagel = 0xd7; + bs2 = 0xc2; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", "x x x x x x x x x x x x x x x x"; - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", "x x x x x x x x x x x x x x x x"; - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - resetdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - paged = no; - page_size = 4; - size = 1024; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + resetdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + paged = no; + page_size = 4; + size = 1024; min_write_delay = 3600; max_write_delay = 3600; - readback_p1 = 0xff; - readback_p2 = 0xff; + readback_p1 = 0xff; + readback_p2 = 0xff; read = " 1 0 1 0 0 0 0 0", - " 0 0 0 x x x a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + " 0 0 0 x x x a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; write = " 1 1 0 0 0 0 0 0", - " 0 0 0 x x x a9 a8", + " 0 0 0 x x x a9 a8", " a7 a6 a5 a4 a3 a2 a1 a0", " i i i i i i i i"; loadpage_lo = " 1 1 0 0 0 0 0 1", - " 0 0 0 0 0 0 0 0", - " 0 0 0 0 0 0 a1 a0", - " i i i i i i i i"; + " 0 0 0 0 0 0 0 0", + " 0 0 0 0 0 0 a1 a0", + " i i i i i i i i"; writepage = " 1 1 0 0 0 0 1 0", - " 0 0 x x x x a9 a8", - " a7 a6 a5 a4 a3 a2 0 0", - " x x x x x x x x"; - - mode = 0x41; - delay = 5; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 32768; - page_size = 128; - num_pages = 256; + " 0 0 x x x x a9 a8", + " a7 a6 a5 a4 a3 a2 0 0", + " x x x x x x x x"; + + mode = 0x41; + delay = 5; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 32768; + page_size = 128; + num_pages = 256; min_write_delay = 4500; max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; + readback_p1 = 0xff; + readback_p2 = 0xff; read_lo = " 0 0 1 0 0 0 0 0", " 0 0 a13 a12 a11 a10 a9 a8", " a7 a6 a5 a4 a3 a2 a1 a0", @@ -8650,82 +8650,82 @@ part " o o o o o o o o"; loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 0 x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; + " 0 0 0 x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; writepage = " 0 1 0 0 1 1 0 0", - " 0 0 a13 a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; + " 0 0 a13 a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; - mode = 0x41; - delay = 6; - blocksize = 128; - readsize = 256; + mode = 0x41; + delay = 6; + blocksize = 128; + readsize = 256; - ; + ; - memory "lfuse" + memory "lfuse" size = 1; min_write_delay = 4500; max_write_delay = 4500; read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; + "x x x x x x x x o o o o o o o o"; write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; + "x x x x x x x x i i i i i i i i"; + ; - memory "hfuse" + memory "hfuse" size = 1; min_write_delay = 4500; max_write_delay = 4500; read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; + "x x x x x x x x o o o o o o o o"; write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - ; + "x x x x x x x x i i i i i i i i"; + ; - memory "efuse" + memory "efuse" size = 1; min_write_delay = 4500; max_write_delay = 4500; read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x x x x x x o o o"; + "x x x x x x x x x x x x x o o o"; write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - ; + "x x x x x x x x x x x x x i i i"; + ; - memory "lock" + memory "lock" size = 1; min_write_delay = 4500; max_write_delay = 4500; read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; + "x x x x x x x x x x o o o o o o"; write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - ; + "x x x x x x x x 1 1 i i i i i i"; + ; - memory "calibration" + memory "calibration" size = 1; read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; - memory "signature" + memory "signature" size = 3; read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -8733,186 +8733,186 @@ part #------------------------------------------------------------ part - id = "t2313"; - desc = "ATtiny2313"; - has_debugwire = yes; - flash_instr = 0xB2, 0x0F, 0x1F; - eeprom_instr = 0xBB, 0xFE, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, - 0xBA, 0x0F, 0xB2, 0x0F, 0xBA, 0x0D, 0xBB, 0xBC, - 0x99, 0xE1, 0xBB, 0xAC; - stk500_devcode = 0x23; + id = "t2313"; + desc = "ATtiny2313"; + has_debugwire = yes; + flash_instr = 0xB2, 0x0F, 0x1F; + eeprom_instr = 0xBB, 0xFE, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, + 0xBA, 0x0F, 0xB2, 0x0F, 0xBA, 0x0D, 0xBB, 0xBC, + 0x99, 0xE1, 0xBB, 0xAC; + stk500_devcode = 0x23; ## Use the ATtiny26 devcode: - avr910_devcode = 0x5e; - signature = 0x1e 0x91 0x0a; - pagel = 0xD4; - bs2 = 0xD6; - reset = io; - chip_erase_delay = 9000; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0E, 0x1E, 0x2E, 0x3E, 0x2E, 0x3E, - 0x4E, 0x5E, 0x4E, 0x5E, 0x6E, 0x7E, 0x6E, 0x7E, - 0x26, 0x36, 0x66, 0x76, 0x2A, 0x3A, 0x6A, 0x7A, - 0x2E, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - size = 128; - paged = no; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + avr910_devcode = 0x5e; + signature = 0x1e 0x91 0x0a; + pagel = 0xD4; + bs2 = 0xD6; + reset = io; + chip_erase_delay = 9000; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0E, 0x1E, 0x2E, 0x3E, 0x2E, 0x3E, + 0x4E, 0x5E, 0x4E, 0x5E, 0x6E, 0x7E, 0x6E, 0x7E, + 0x26, 0x36, 0x66, 0x76, 0x2A, 0x3A, 0x6A, 0x7A, + 0x2E, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + size = 128; + paged = no; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " x a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 6; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 2048; - page_size = 32; - num_pages = 64; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; + mode = 0x41; + delay = 6; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 2048; + page_size = 32; + num_pages = 64; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; # The information in the data sheet of April/2004 is wrong, this works: - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x x a3 a2 a1 a0", - " i i i i i i i i"; + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x x a3 a2 a1 a0", + " i i i i i i i i"; # The information in the data sheet of April/2004 is wrong, this works: - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x x a3 a2 a1 a0", - " i i i i i i i i"; + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x x a3 a2 a1 a0", + " i i i i i i i i"; # The information in the data sheet of April/2004 is wrong, this works: - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 32; - readsize = 256; - ; + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 32; + readsize = 256; + ; # ATtiny2313 has Signature Bytes: 0x1E 0x91 0x0A. - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; # The Tiny2313 has calibration data for both 4 MHz and 8 MHz. # The information in the data sheet of April/2004 is wrong, this works: - memory "calibration" - size = 2; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 a0 o o o o o o o o"; - ; + memory "calibration" + size = 2; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -8920,181 +8920,181 @@ part #------------------------------------------------------------ part - id = "pwm2"; - desc = "AT90PWM2"; - has_debugwire = yes; - flash_instr = 0xB6, 0x01, 0x11; - eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, - 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, - 0x99, 0xF9, 0xBB, 0xAF; - stk500_devcode = 0x65; + id = "pwm2"; + desc = "AT90PWM2"; + has_debugwire = yes; + flash_instr = 0xB6, 0x01, 0x11; + eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, + 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, + 0x99, 0xF9, 0xBB, 0xAF; + stk500_devcode = 0x65; ## avr910_devcode = ?; - signature = 0x1e 0x93 0x81; - pagel = 0xD8; - bs2 = 0xE2; - reset = io; - chip_erase_delay = 9000; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - size = 512; - paged = no; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + signature = 0x1e 0x93 0x81; + pagel = 0xD8; + bs2 = 0xE2; + reset = io; + chip_erase_delay = 9000; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + size = 512; + paged = no; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 6; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 8192; - page_size = 64; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 64; - readsize = 256; - ; + mode = 0x41; + delay = 6; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 8192; + page_size = 64; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 64; + readsize = 256; + ; # AT90PWM2 has Signature Bytes: 0x1E 0x93 0x81. - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -9104,181 +9104,181 @@ part # Completely identical to AT90PWM2 (including the signature!) part - id = "pwm3"; - desc = "AT90PWM3"; - has_debugwire = yes; - flash_instr = 0xB6, 0x01, 0x11; - eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, - 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, - 0x99, 0xF9, 0xBB, 0xAF; - stk500_devcode = 0x65; + id = "pwm3"; + desc = "AT90PWM3"; + has_debugwire = yes; + flash_instr = 0xB6, 0x01, 0x11; + eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, + 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, + 0x99, 0xF9, 0xBB, 0xAF; + stk500_devcode = 0x65; ## avr910_devcode = ?; - signature = 0x1e 0x93 0x81; - pagel = 0xD8; - bs2 = 0xE2; - reset = io; - chip_erase_delay = 9000; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - size = 512; - paged = no; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + signature = 0x1e 0x93 0x81; + pagel = 0xD8; + bs2 = 0xE2; + reset = io; + chip_erase_delay = 9000; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + size = 512; + paged = no; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 6; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 8192; - page_size = 64; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 64; - readsize = 256; - ; + mode = 0x41; + delay = 6; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 8192; + page_size = 64; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 64; + readsize = 256; + ; # AT90PWM2 has Signature Bytes: 0x1E 0x93 0x81. - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -9287,180 +9287,180 @@ part # Same as AT90PWM2 but different signature. part - id = "pwm2b"; - desc = "AT90PWM2B"; - has_debugwire = yes; - flash_instr = 0xB6, 0x01, 0x11; - eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, - 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, - 0x99, 0xF9, 0xBB, 0xAF; - stk500_devcode = 0x65; + id = "pwm2b"; + desc = "AT90PWM2B"; + has_debugwire = yes; + flash_instr = 0xB6, 0x01, 0x11; + eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, + 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, + 0x99, 0xF9, 0xBB, 0xAF; + stk500_devcode = 0x65; ## avr910_devcode = ?; - signature = 0x1e 0x93 0x83; - pagel = 0xD8; - bs2 = 0xE2; - reset = io; - chip_erase_delay = 9000; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - size = 512; - paged = no; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + signature = 0x1e 0x93 0x83; + pagel = 0xD8; + bs2 = 0xE2; + reset = io; + chip_erase_delay = 9000; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + size = 512; + paged = no; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 6; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 8192; - page_size = 64; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 64; - readsize = 256; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 6; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 8192; + page_size = 64; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 64; + readsize = 256; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -9470,180 +9470,180 @@ part # Completely identical to AT90PWM2B (including the signature!) part - id = "pwm3b"; - desc = "AT90PWM3B"; - has_debugwire = yes; - flash_instr = 0xB6, 0x01, 0x11; - eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, - 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, - 0x99, 0xF9, 0xBB, 0xAF; - stk500_devcode = 0x65; + id = "pwm3b"; + desc = "AT90PWM3B"; + has_debugwire = yes; + flash_instr = 0xB6, 0x01, 0x11; + eeprom_instr = 0xBD, 0xF2, 0xBD, 0xE1, 0xBB, 0xCF, 0xB4, 0x00, + 0xBE, 0x01, 0xB6, 0x01, 0xBC, 0x00, 0xBB, 0xBF, + 0x99, 0xF9, 0xBB, 0xAF; + stk500_devcode = 0x65; ## avr910_devcode = ?; - signature = 0x1e 0x93 0x83; - pagel = 0xD8; - bs2 = 0xE2; - reset = io; - chip_erase_delay = 9000; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - size = 512; - paged = no; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + signature = 0x1e 0x93 0x83; + pagel = 0xD8; + bs2 = 0xE2; + reset = io; + chip_erase_delay = 9000; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + size = 512; + paged = no; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 6; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 8192; - page_size = 64; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 64; - readsize = 256; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + mode = 0x41; + delay = 6; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 8192; + page_size = 64; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 64; + readsize = 256; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -9651,179 +9651,179 @@ part #------------------------------------------------------------ part - id = "t25"; - desc = "ATtiny25"; - has_debugwire = yes; - flash_instr = 0xB4, 0x02, 0x12; - eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, - 0xBC, 0x02, 0xB4, 0x02, 0xBA, 0x0D, 0xBB, 0xBC, - 0x99, 0xE1, 0xBB, 0xAC; + id = "t25"; + desc = "ATtiny25"; + has_debugwire = yes; + flash_instr = 0xB4, 0x02, 0x12; + eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, + 0xBC, 0x02, 0xB4, 0x02, 0xBA, 0x0D, 0xBB, 0xBC, + 0x99, 0xE1, 0xBB, 0xAC; ## no STK500 devcode in XML file, use the ATtiny45 one - stk500_devcode = 0x14; + stk500_devcode = 0x14; ## avr910_devcode = ?; ## Try the AT90S2313 devcode: - avr910_devcode = 0x20; - signature = 0x1e 0x91 0x08; - reset = io; - chip_erase_delay = 4500; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - hvsp_controlstack = - 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66, - 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, - 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, - 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; - hventerstabdelay = 100; - hvspcmdexedelay = 0; - synchcycles = 6; - latchcycles = 1; - togglevtg = 1; - poweroffdelay = 25; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 100; - resetdelay = 25; - chiperasepolltimeout = 40; - chiperasetime = 0; - programfusepolltimeout = 25; - programlockpolltimeout = 25; - - memory "eeprom" - size = 128; - paged = no; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + avr910_devcode = 0x20; + signature = 0x1e 0x91 0x08; + reset = io; + chip_erase_delay = 4500; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + hvsp_controlstack = + 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66, + 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, + 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, + 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; + hventerstabdelay = 100; + hvspcmdexedelay = 0; + synchcycles = 6; + latchcycles = 1; + togglevtg = 1; + poweroffdelay = 25; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 100; + resetdelay = 25; + chiperasepolltimeout = 40; + chiperasetime = 0; + programfusepolltimeout = 25; + programlockpolltimeout = 25; + + memory "eeprom" + size = 128; + paged = no; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " x a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 6; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 2048; - page_size = 32; - num_pages = 64; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x x a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x x a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 32; - readsize = 256; - ; + mode = 0x41; + delay = 6; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 2048; + page_size = 32; + num_pages = 64; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x x a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x x a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 32; + readsize = 256; + ; # ATtiny25 has Signature Bytes: 0x1E 0x91 0x08. - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 2; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 a0 o o o o o o o o"; - ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 2; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -9831,178 +9831,178 @@ part #------------------------------------------------------------ part - id = "t45"; - desc = "ATtiny45"; - has_debugwire = yes; - flash_instr = 0xB4, 0x02, 0x12; - eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, - 0xBC, 0x02, 0xB4, 0x02, 0xBA, 0x0D, 0xBB, 0xBC, - 0x99, 0xE1, 0xBB, 0xAC; - stk500_devcode = 0x14; + id = "t45"; + desc = "ATtiny45"; + has_debugwire = yes; + flash_instr = 0xB4, 0x02, 0x12; + eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, + 0xBC, 0x02, 0xB4, 0x02, 0xBA, 0x0D, 0xBB, 0xBC, + 0x99, 0xE1, 0xBB, 0xAC; + stk500_devcode = 0x14; ## avr910_devcode = ?; ## Try the AT90S2313 devcode: - avr910_devcode = 0x20; - signature = 0x1e 0x92 0x06; - reset = io; - chip_erase_delay = 4500; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - hvsp_controlstack = + avr910_devcode = 0x20; + signature = 0x1e 0x92 0x06; + reset = io; + chip_erase_delay = 4500; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + hvsp_controlstack = 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66, - 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, - 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, - 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - hvspcmdexedelay = 0; - synchcycles = 6; - latchcycles = 1; - togglevtg = 1; - poweroffdelay = 25; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 100; - resetdelay = 25; - chiperasepolltimeout = 40; - chiperasetime = 0; - programfusepolltimeout = 25; - programlockpolltimeout = 25; - - memory "eeprom" - size = 256; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, + 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, + 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + hvspcmdexedelay = 0; + synchcycles = 6; + latchcycles = 1; + togglevtg = 1; + poweroffdelay = 25; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 100; + resetdelay = 25; + chiperasepolltimeout = 40; + chiperasetime = 0; + programfusepolltimeout = 25; + programlockpolltimeout = 25; + + memory "eeprom" + size = 256; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 6; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 4096; - page_size = 64; - num_pages = 64; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 32; - readsize = 256; - ; + mode = 0x41; + delay = 6; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 4096; + page_size = 64; + num_pages = 64; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 32; + readsize = 256; + ; # ATtiny45 has Signature Bytes: 0x1E 0x92 0x08. (Data sheet 2586C-AVR-06/05 (doc2586.pdf) indicates otherwise!) - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 2; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 a0 o o o o o o o o"; - ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 2; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -10010,179 +10010,179 @@ part #------------------------------------------------------------ part - id = "t85"; - desc = "ATtiny85"; - has_debugwire = yes; - flash_instr = 0xB4, 0x02, 0x12; - eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, - 0xBC, 0x02, 0xB4, 0x02, 0xBA, 0x0D, 0xBB, 0xBC, - 0x99, 0xE1, 0xBB, 0xAC; + id = "t85"; + desc = "ATtiny85"; + has_debugwire = yes; + flash_instr = 0xB4, 0x02, 0x12; + eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, + 0xBC, 0x02, 0xB4, 0x02, 0xBA, 0x0D, 0xBB, 0xBC, + 0x99, 0xE1, 0xBB, 0xAC; ## no STK500 devcode in XML file, use the ATtiny45 one - stk500_devcode = 0x14; + stk500_devcode = 0x14; ## avr910_devcode = ?; ## Try the AT90S2313 devcode: - avr910_devcode = 0x20; - signature = 0x1e 0x93 0x0b; - reset = io; - chip_erase_delay = 4500; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - hvsp_controlstack = - 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66, - 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, - 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, - 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; - hventerstabdelay = 100; - hvspcmdexedelay = 0; - synchcycles = 6; - latchcycles = 1; - togglevtg = 1; - poweroffdelay = 25; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 100; - resetdelay = 25; - chiperasepolltimeout = 40; - chiperasetime = 0; - programfusepolltimeout = 25; - programlockpolltimeout = 25; - - memory "eeprom" - size = 512; - paged = no; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8", - "a8 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + avr910_devcode = 0x20; + signature = 0x1e 0x93 0x0b; + reset = io; + chip_erase_delay = 4500; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + hvsp_controlstack = + 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66, + 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, + 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, + 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x00; + hventerstabdelay = 100; + hvspcmdexedelay = 0; + synchcycles = 6; + latchcycles = 1; + togglevtg = 1; + poweroffdelay = 25; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 100; + resetdelay = 25; + chiperasepolltimeout = 40; + chiperasetime = 0; + programfusepolltimeout = 25; + programlockpolltimeout = 25; + + memory "eeprom" + size = 512; + paged = no; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8", + "a8 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x a8", " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 6; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 8192; - page_size = 64; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 32; - readsize = 256; - ; + mode = 0x41; + delay = 6; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 8192; + page_size = 64; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 32; + readsize = 256; + ; # ATtiny85 has Signature Bytes: 0x1E 0x93 0x08. - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 2; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 a0 o o o o o o o o"; - ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 2; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -10191,187 +10191,187 @@ part # Almost same as ATmega1280, except for different memory sizes part - id = "m640"; - desc = "ATMEGA640"; - signature = 0x1e 0x96 0x08; - has_jtag = yes; + id = "m640"; + desc = "ATMEGA640"; + signature = 0x1e 0x96 0x08; + has_jtag = yes; # stk500_devcode = 0xB2; # avr910_devcode = 0x43; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 4096; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 4096; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x a11 a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 65536; - page_size = 256; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 10; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 65536; + page_size = 256; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 10; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -10379,187 +10379,187 @@ part #------------------------------------------------------------ part - id = "m1280"; - desc = "ATMEGA1280"; - signature = 0x1e 0x97 0x03; - has_jtag = yes; + id = "m1280"; + desc = "ATMEGA1280"; + signature = 0x1e 0x97 0x03; + has_jtag = yes; # stk500_devcode = 0xB2; # avr910_devcode = 0x43; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 4096; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 4096; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x a11 a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 131072; - page_size = 256; - num_pages = 512; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 10; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 131072; + page_size = 256; + num_pages = 512; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 10; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -10568,187 +10568,187 @@ part # Identical to ATmega1280 part - id = "m1281"; - desc = "ATMEGA1281"; - signature = 0x1e 0x97 0x04; - has_jtag = yes; + id = "m1281"; + desc = "ATMEGA1281"; + signature = 0x1e 0x97 0x04; + has_jtag = yes; # stk500_devcode = 0xB2; # avr910_devcode = 0x43; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 4096; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 4096; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x a11 a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 131072; - page_size = 256; - num_pages = 512; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 10; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 131072; + page_size = 256; + num_pages = 512; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 10; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -10756,192 +10756,192 @@ part #------------------------------------------------------------ part - id = "m2560"; - desc = "ATMEGA2560"; - signature = 0x1e 0x98 0x01; - has_jtag = yes; + id = "m2560"; + desc = "ATMEGA2560"; + signature = 0x1e 0x98 0x01; + has_jtag = yes; # stk500_devcode = 0xB2; # avr910_devcode = 0x43; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 4096; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 4096; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x a11 a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 262144; - page_size = 256; - num_pages = 1024; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - load_ext_addr = " 0 1 0 0 1 1 0 1", - " 0 0 0 0 0 0 0 0", - " 0 0 0 0 0 0 0 a16", - " 0 0 0 0 0 0 0 0"; - - mode = 0x41; - delay = 10; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 262144; + page_size = 256; + num_pages = 1024; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + load_ext_addr = " 0 1 0 0 1 1 0 1", + " 0 0 0 0 0 0 0 0", + " 0 0 0 0 0 0 0 a16", + " 0 0 0 0 0 0 0 0"; + + mode = 0x41; + delay = 10; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -10949,192 +10949,192 @@ part #------------------------------------------------------------ part - id = "m2561"; - desc = "ATMEGA2561"; - signature = 0x1e 0x98 0x02; - has_jtag = yes; + id = "m2561"; + desc = "ATMEGA2561"; + signature = 0x1e 0x98 0x02; + has_jtag = yes; # stk500_devcode = 0xB2; # avr910_devcode = 0x43; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 4096; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 4096; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x a11 a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 262144; - page_size = 256; - num_pages = 1024; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - load_ext_addr = " 0 1 0 0 1 1 0 1", - " 0 0 0 0 0 0 0 0", - " 0 0 0 0 0 0 0 a16", - " 0 0 0 0 0 0 0 0"; - - mode = 0x41; - delay = 10; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 262144; + page_size = 256; + num_pages = 1024; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + load_ext_addr = " 0 1 0 0 1 1 0 1", + " 0 0 0 0 0 0 0 0", + " 0 0 0 0 0 0 0 a16", + " 0 0 0 0 0 0 0 0"; + + mode = 0x41; + delay = 10; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -11143,187 +11143,187 @@ part # Identical to ATmega2561 but half the ROM part - id = "m128rfa1"; - desc = "ATMEGA128RFA1"; - signature = 0x1e 0xa7 0x01; - has_jtag = yes; + id = "m128rfa1"; + desc = "ATMEGA128RFA1"; + signature = 0x1e 0xa7 0x01; + has_jtag = yes; # stk500_devcode = 0xB2; # avr910_devcode = 0x43; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xE2; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 4096; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xE2; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 4096; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x a11 a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 131072; - page_size = 256; - num_pages = 512; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 10; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 131072; + page_size = 256; + num_pages = 512; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 10; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -11331,181 +11331,181 @@ part #------------------------------------------------------------ part - id = "t24"; - desc = "ATtiny24"; - has_debugwire = yes; - flash_instr = 0xB4, 0x07, 0x17; - eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, - 0xBC, 0x07, 0xB4, 0x07, 0xBA, 0x0D, 0xBB, 0xBC, - 0x99, 0xE1, 0xBB, 0xAC; + id = "t24"; + desc = "ATtiny24"; + has_debugwire = yes; + flash_instr = 0xB4, 0x07, 0x17; + eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, + 0xBC, 0x07, 0xB4, 0x07, 0xBA, 0x0D, 0xBB, 0xBC, + 0x99, 0xE1, 0xBB, 0xAC; ## no STK500 devcode in XML file, use the ATtiny45 one - stk500_devcode = 0x14; + stk500_devcode = 0x14; ## avr910_devcode = ?; ## Try the AT90S2313 devcode: - avr910_devcode = 0x20; - signature = 0x1e 0x91 0x0b; - reset = io; - chip_erase_delay = 4500; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - hvsp_controlstack = - 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66, - 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, - 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, - 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x0F; - hventerstabdelay = 100; - hvspcmdexedelay = 0; - synchcycles = 6; - latchcycles = 1; - togglevtg = 1; - poweroffdelay = 25; - resetdelayms = 0; - resetdelayus = 70; - hvleavestabdelay = 100; - resetdelay = 25; - chiperasepolltimeout = 40; - chiperasetime = 0; - programfusepolltimeout = 25; - programlockpolltimeout = 25; - - memory "eeprom" - size = 128; - paged = no; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x", - "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + avr910_devcode = 0x20; + signature = 0x1e 0x91 0x0b; + reset = io; + chip_erase_delay = 4500; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + hvsp_controlstack = + 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66, + 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, + 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, + 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x0F; + hventerstabdelay = 100; + hvspcmdexedelay = 0; + synchcycles = 6; + latchcycles = 1; + togglevtg = 1; + poweroffdelay = 25; + resetdelayms = 0; + resetdelayus = 70; + hvleavestabdelay = 100; + resetdelay = 25; + chiperasepolltimeout = 40; + chiperasetime = 0; + programfusepolltimeout = 25; + programlockpolltimeout = 25; + + memory "eeprom" + size = 128; + paged = no; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x", + "x a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " x a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 6; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 2048; - page_size = 32; - num_pages = 64; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x x a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x x a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 32; - readsize = 256; - ; + mode = 0x41; + delay = 6; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 2048; + page_size = 32; + num_pages = 64; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x x a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x x a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 32; + readsize = 256; + ; # ATtiny24 has Signature Bytes: 0x1E 0x91 0x0B. - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x x x x x x x i i"; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 a0 o o o o o o o o"; - ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x x x x x x x i i"; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -11513,181 +11513,181 @@ part #------------------------------------------------------------ part - id = "t44"; - desc = "ATtiny44"; - has_debugwire = yes; - flash_instr = 0xB4, 0x07, 0x17; - eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, - 0xBC, 0x07, 0xB4, 0x07, 0xBA, 0x0D, 0xBB, 0xBC, - 0x99, 0xE1, 0xBB, 0xAC; + id = "t44"; + desc = "ATtiny44"; + has_debugwire = yes; + flash_instr = 0xB4, 0x07, 0x17; + eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, + 0xBC, 0x07, 0xB4, 0x07, 0xBA, 0x0D, 0xBB, 0xBC, + 0x99, 0xE1, 0xBB, 0xAC; ## no STK500 devcode in XML file, use the ATtiny45 one - stk500_devcode = 0x14; + stk500_devcode = 0x14; ## avr910_devcode = ?; ## Try the AT90S2313 devcode: - avr910_devcode = 0x20; - signature = 0x1e 0x92 0x07; - reset = io; - chip_erase_delay = 4500; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - hvsp_controlstack = - 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66, - 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, - 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, - 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x0F; - hventerstabdelay = 100; - hvspcmdexedelay = 0; - synchcycles = 6; - latchcycles = 1; - togglevtg = 1; - poweroffdelay = 25; - resetdelayms = 0; - resetdelayus = 70; - hvleavestabdelay = 100; - resetdelay = 25; - chiperasepolltimeout = 40; - chiperasetime = 0; - programfusepolltimeout = 25; - programlockpolltimeout = 25; - - memory "eeprom" - size = 256; - paged = no; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x", - "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + avr910_devcode = 0x20; + signature = 0x1e 0x92 0x07; + reset = io; + chip_erase_delay = 4500; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + hvsp_controlstack = + 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66, + 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, + 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, + 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x0F; + hventerstabdelay = 100; + hvspcmdexedelay = 0; + synchcycles = 6; + latchcycles = 1; + togglevtg = 1; + poweroffdelay = 25; + resetdelayms = 0; + resetdelayus = 70; + hvleavestabdelay = 100; + resetdelay = 25; + chiperasepolltimeout = 40; + chiperasetime = 0; + programfusepolltimeout = 25; + programlockpolltimeout = 25; + + memory "eeprom" + size = 256; + paged = no; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 x x x x x", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 x x x x x", + "a7 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " x a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 6; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 4096; - page_size = 64; - num_pages = 64; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 32; - readsize = 256; - ; + mode = 0x41; + delay = 6; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 4096; + page_size = 64; + num_pages = 64; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 32; + readsize = 256; + ; # ATtiny44 has Signature Bytes: 0x1E 0x92 0x07. - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x x x x x x x i i"; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 a0 o o o o o o o o"; - ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x x x x x x x i i"; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -11695,182 +11695,182 @@ part #------------------------------------------------------------ part - id = "t84"; - desc = "ATtiny84"; - has_debugwire = yes; - flash_instr = 0xB4, 0x07, 0x17; - eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, - 0xBC, 0x07, 0xB4, 0x07, 0xBA, 0x0D, 0xBB, 0xBC, - 0x99, 0xE1, 0xBB, 0xAC; + id = "t84"; + desc = "ATtiny84"; + has_debugwire = yes; + flash_instr = 0xB4, 0x07, 0x17; + eeprom_instr = 0xBB, 0xFF, 0xBB, 0xEE, 0xBB, 0xCC, 0xB2, 0x0D, + 0xBC, 0x07, 0xB4, 0x07, 0xBA, 0x0D, 0xBB, 0xBC, + 0x99, 0xE1, 0xBB, 0xAC; ## no STK500 devcode in XML file, use the ATtiny45 one - stk500_devcode = 0x14; + stk500_devcode = 0x14; ## avr910_devcode = ?; ## Try the AT90S2313 devcode: - avr910_devcode = 0x20; - signature = 0x1e 0x93 0x0c; - reset = io; - chip_erase_delay = 4500; - - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - hvsp_controlstack = - 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66, - 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, - 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, - 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x0F; - hventerstabdelay = 100; - hvspcmdexedelay = 0; - synchcycles = 6; - latchcycles = 1; - togglevtg = 1; - poweroffdelay = 25; - resetdelayms = 0; - resetdelayus = 70; - hvleavestabdelay = 100; - resetdelay = 25; - chiperasepolltimeout = 40; - chiperasetime = 0; - programfusepolltimeout = 25; - programlockpolltimeout = 25; - - memory "eeprom" - size = 512; - paged = no; - page_size = 4; - min_write_delay = 4000; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8", - "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; - - write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8", - "a8 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + avr910_devcode = 0x20; + signature = 0x1e 0x93 0x0c; + reset = io; + chip_erase_delay = 4500; + + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + hvsp_controlstack = + 0x4C, 0x0C, 0x1C, 0x2C, 0x3C, 0x64, 0x74, 0x66, + 0x68, 0x78, 0x68, 0x68, 0x7A, 0x6A, 0x68, 0x78, + 0x78, 0x7D, 0x6D, 0x0C, 0x80, 0x40, 0x20, 0x10, + 0x11, 0x08, 0x04, 0x02, 0x03, 0x08, 0x04, 0x0F; + hventerstabdelay = 100; + hvspcmdexedelay = 0; + synchcycles = 6; + latchcycles = 1; + togglevtg = 1; + poweroffdelay = 25; + resetdelayms = 0; + resetdelayus = 70; + hvleavestabdelay = 100; + resetdelay = 25; + chiperasepolltimeout = 40; + chiperasetime = 0; + programfusepolltimeout = 25; + programlockpolltimeout = 25; + + memory "eeprom" + size = 512; + paged = no; + page_size = 4; + min_write_delay = 4000; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = "1 0 1 0 0 0 0 0 0 0 0 x x x x a8", + "a7 a6 a5 a4 a3 a2 a1 a0 o o o o o o o o"; + + write = "1 1 0 0 0 0 0 0 0 0 0 x x x x a8", + "a8 a6 a5 a4 a3 a2 a1 a0 i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x x x x", " x a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 6; - blocksize = 4; - readsize = 256; - ; - memory "flash" - paged = yes; - size = 8192; - page_size = 64; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 x x x x x", - " x x x a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 32; - readsize = 256; - ; + mode = 0x41; + delay = 6; + blocksize = 4; + readsize = 256; + ; + memory "flash" + paged = yes; + size = 8192; + page_size = 64; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 x x x x x", + " x x x a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 32; + readsize = 256; + ; # ATtiny84 has Signature Bytes: 0x1E 0x93 0x0C. - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; - - memory "lock" - size = 1; - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x x x x x x x i i"; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x x x x i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 a0 o o o o o o o o"; - ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; + + memory "lock" + size = 1; + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x x x x x x x i i"; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x x x x i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -11878,187 +11878,187 @@ part #------------------------------------------------------------ part - id = "m32u4"; - desc = "ATmega32U4"; - signature = 0x1e 0x95 0x87; - has_jtag = yes; + id = "m32u4"; + desc = "ATmega32U4"; + signature = 0x1e 0x95 0x87; + has_jtag = yes; # stk500_devcode = 0xB2; # avr910_devcode = 0x43; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 1024; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 1024; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 32768; - page_size = 128; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 128; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 32768; + page_size = 128; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 128; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -12066,187 +12066,187 @@ part #------------------------------------------------------------ part - id = "usb646"; - desc = "AT90USB646"; - signature = 0x1e 0x96 0x82; - has_jtag = yes; + id = "usb646"; + desc = "AT90USB646"; + signature = 0x1e 0x96 0x82; + has_jtag = yes; # stk500_devcode = 0xB2; # avr910_devcode = 0x43; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 2048; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 2048; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 65536; - page_size = 256; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 65536; + page_size = 256; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -12255,187 +12255,187 @@ part # identical to AT90USB646 part - id = "usb647"; - desc = "AT90USB647"; - signature = 0x1e 0x96 0x82; - has_jtag = yes; + id = "usb647"; + desc = "AT90USB647"; + signature = 0x1e 0x96 0x82; + has_jtag = yes; # stk500_devcode = 0xB2; # avr910_devcode = 0x43; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 2048; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x x a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 2048; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x x a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 65536; - page_size = 256; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 65536; + page_size = 256; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -12443,187 +12443,187 @@ part #------------------------------------------------------------ part - id = "usb1286"; - desc = "AT90USB1286"; - signature = 0x1e 0x97 0x82; - has_jtag = yes; + id = "usb1286"; + desc = "AT90USB1286"; + signature = 0x1e 0x97 0x82; + has_jtag = yes; # stk500_devcode = 0xB2; # avr910_devcode = 0x43; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 4096; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 4096; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 131072; - page_size = 256; - num_pages = 512; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 131072; + page_size = 256; + num_pages = 512; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -12632,187 +12632,187 @@ part # identical to AT90USB1286 part - id = "usb1287"; - desc = "AT90USB1287"; - signature = 0x1e 0x97 0x82; - has_jtag = yes; + id = "usb1287"; + desc = "AT90USB1287"; + signature = 0x1e 0x97 0x82; + has_jtag = yes; # stk500_devcode = 0xB2; # avr910_devcode = 0x43; - chip_erase_delay = 9000; - pagel = 0xD7; - bs2 = 0xA0; - reset = dedicated; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "x x x x x x x x x x x x x x x x"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - rampz = 0x3b; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 4096; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " x x x x a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + chip_erase_delay = 9000; + pagel = 0xD7; + bs2 = 0xA0; + reset = dedicated; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "x x x x x x x x x x x x x x x x"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + rampz = 0x3b; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 4096; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " x x x x a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 a2 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", + writepage = " 1 1 0 0 0 0 1 0", " 0 0 x x x a10 a9 a8", " a7 a6 a5 a4 a3 0 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 10; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 131072; - page_size = 256; - num_pages = 512; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 x x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 256; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x x x x x i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 x x x x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 x x x x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 10; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 131072; + page_size = 256; + num_pages = 512; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 x x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 256; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x x x x x i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 x x x x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 x x x x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; @@ -12821,179 +12821,179 @@ part #------------------------------------------------------------ part - id = "usb162"; - desc = "AT90USB162"; - has_jtag = no; - has_debugwire = yes; - signature = 0x1e 0x94 0x82; - chip_erase_delay = 9000; - reset = io; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - pagel = 0xD7; - bs2 = 0xC6; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 512; - num_pages = 128; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + id = "usb162"; + desc = "AT90USB162"; + has_jtag = no; + has_debugwire = yes; + signature = 0x1e 0x94 0x82; + chip_erase_delay = 9000; + reset = io; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + pagel = 0xD7; + bs2 = 0xC6; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 512; + num_pages = 128; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 0 0", + writepage = " 1 1 0 0 0 0 1 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 16384; - page_size = 128; - num_pages = 128; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 128; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 20; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 16384; + page_size = 128; + num_pages = 128; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 128; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -13005,179 +13005,179 @@ part # num_pages = 64; part - id = "usb82"; - desc = "AT90USB82"; - has_jtag = no; - has_debugwire = yes; - signature = 0x1e 0x93 0x82; - chip_erase_delay = 9000; - reset = io; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "x x x x x x x x x x x x x x x x"; - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", - "x x x x x x x x x x x x x x x x"; - pagel = 0xD7; - bs2 = 0xC6; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 512; - num_pages = 128; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0x00; - readback_p2 = 0x00; - read = " 1 0 1 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", + id = "usb82"; + desc = "AT90USB82"; + has_jtag = no; + has_debugwire = yes; + signature = 0x1e 0x93 0x82; + chip_erase_delay = 9000; + reset = io; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "x x x x x x x x x x x x x x x x"; + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 x x x x x", + "x x x x x x x x x x x x x x x x"; + pagel = 0xD7; + bs2 = 0xC6; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 512; + num_pages = 128; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0x00; + readback_p2 = 0x00; + read = " 1 0 1 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", " 0 0 0 0 0 0 0 0", " 0 0 0 0 0 0 a1 a0", " i i i i i i i i"; - writepage = " 1 1 0 0 0 0 1 0", - " 0 0 0 0 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 0 0", + writepage = " 1 1 0 0 0 0 1 0", + " 0 0 0 0 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 0 0", " x x x x x x x x"; - mode = 0x41; - delay = 20; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 8192; - page_size = 128; - num_pages = 64; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0x00; - readback_p2 = 0x00; - read_lo = " 0 0 1 0 0 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " x x x x x x x x", - " x x a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - "a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 x x x x x x", - " x x x x x x x x"; - - mode = 0x41; - delay = 6; - blocksize = 128; - readsize = 256; - ; - - memory "lfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "x x x x x x x x i i i i i i i i"; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "x x x x x x x x o o o o o o o o"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", - "x x x x x x x x 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "calibration" - size = 1; - read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", - "x x x x x x a1 a0 o o o o o o o o"; - ; + mode = 0x41; + delay = 20; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 8192; + page_size = 128; + num_pages = 64; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0x00; + readback_p2 = 0x00; + read_lo = " 0 0 1 0 0 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " x x x x x x x x", + " x x a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + "a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 x x x x x x", + " x x x x x x x x"; + + mode = 0x41; + delay = 6; + blocksize = 128; + readsize = 256; + ; + + memory "lfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "x x x x x x x x i i i i i i i i"; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "x x x x x x x x o o o o o o o o"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 x x x x x", + "x x x x x x x x 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "calibration" + size = 1; + read = "0 0 1 1 1 0 0 0 0 0 0 x x x x x", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 x x x x x", + "x x x x x x a1 a0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -13185,188 +13185,188 @@ part #------------------------------------------------------------ part - id = "m325"; - desc = "ATMEGA325"; - signature = 0x1e 0x95 0x05; - has_jtag = yes; + id = "m325"; + desc = "ATMEGA325"; + signature = 0x1e 0x95 0x05; + has_jtag = yes; # stk500_devcode = 0x??; # No STK500v1 support? # avr910_devcode = 0x??; # Try the ATmega16 one - avr910_devcode = 0x74; - pagel = 0xd7; - bs2 = 0xa0; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 1024; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = " 1 0 1 0 0 0 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", - " 0 0 0 0 0 0 0 0", - " 0 0 0 0 0 0 a1 a0", - " i i i i i i i i"; - - writepage = " 1 1 0 0 0 0 1 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 a3 a2 0 0", - " x x x x x x x x"; - - mode = 0x41; - delay = 10; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 32768; - page_size = 128; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 0 0 0 0 0", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 0 0 0 0 0", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " x x x x x x x x"; - - mode = 0x41; - delay = 10; - blocksize = 128; - readsize = 256; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 0 0 0 0 0", - "0 0 0 0 0 0 0 0 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "0 0 0 0 0 0 0 0 i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "0 0 0 0 0 0 0 0 i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "0 0 0 0 0 0 0 0 1 1 1 1 1 i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - - read = "0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + avr910_devcode = 0x74; + pagel = 0xd7; + bs2 = 0xa0; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 1024; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = " 1 0 1 0 0 0 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", + " 0 0 0 0 0 0 0 0", + " 0 0 0 0 0 0 a1 a0", + " i i i i i i i i"; + + writepage = " 1 1 0 0 0 0 1 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 a3 a2 0 0", + " x x x x x x x x"; + + mode = 0x41; + delay = 10; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 32768; + page_size = 128; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 0 0 0 0 0", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 0 0 0 0 0", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " x x x x x x x x"; + + mode = 0x41; + delay = 10; + blocksize = 128; + readsize = 256; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 0 0 0 0 0", + "0 0 0 0 0 0 0 0 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "0 0 0 0 0 0 0 0 i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "0 0 0 0 0 0 0 0 i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "0 0 0 0 0 0 0 0 1 1 1 1 1 i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + + read = "0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -13374,188 +13374,188 @@ part #------------------------------------------------------------ part - id = "m645"; - desc = "ATMEGA645"; - signature = 0x1E 0x96 0x05; - has_jtag = yes; + id = "m645"; + desc = "ATMEGA645"; + signature = 0x1E 0x96 0x05; + has_jtag = yes; # stk500_devcode = 0x??; # No STK500v1 support? # avr910_devcode = 0x??; # Try the ATmega16 one - avr910_devcode = 0x74; - pagel = 0xd7; - bs2 = 0xa0; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 2048; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = " 1 0 1 0 0 0 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", - " 0 0 0 0 0 0 0 0", - " 0 0 0 0 0 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 1 1 0 0 0 0 1 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 a4 a3 0 0 0", - " x x x x x x x x"; - - mode = 0x41; - delay = 10; - blocksize = 8; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 65536; - page_size = 256; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 0 0 0 0 0", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 0 0 0 0 0", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " 0 0 0 0 0 0 0 0"; - - mode = 0x41; - delay = 10; - blocksize = 128; - readsize = 256; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 0 0 0 0 0", - "0 0 0 0 0 0 0 0 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "0 0 0 0 0 0 0 0 i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "0 0 0 0 0 0 0 0 i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "0 0 0 0 0 0 0 0 1 1 1 1 1 i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - - read = "0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + avr910_devcode = 0x74; + pagel = 0xd7; + bs2 = 0xa0; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 2048; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = " 1 0 1 0 0 0 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", + " 0 0 0 0 0 0 0 0", + " 0 0 0 0 0 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 1 1 0 0 0 0 1 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 a4 a3 0 0 0", + " x x x x x x x x"; + + mode = 0x41; + delay = 10; + blocksize = 8; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 65536; + page_size = 256; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 0 0 0 0 0", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 0 0 0 0 0", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " 0 0 0 0 0 0 0 0"; + + mode = 0x41; + delay = 10; + blocksize = 128; + readsize = 256; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 0 0 0 0 0", + "0 0 0 0 0 0 0 0 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "0 0 0 0 0 0 0 0 i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "0 0 0 0 0 0 0 0 i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "0 0 0 0 0 0 0 0 1 1 1 1 1 i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + + read = "0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -13563,188 +13563,188 @@ part #------------------------------------------------------------ part - id = "m3250"; - desc = "ATMEGA3250"; - signature = 0x1E 0x95 0x06; - has_jtag = yes; + id = "m3250"; + desc = "ATMEGA3250"; + signature = 0x1E 0x95 0x06; + has_jtag = yes; # stk500_devcode = 0x??; # No STK500v1 support? # avr910_devcode = 0x??; # Try the ATmega16 one - avr910_devcode = 0x74; - pagel = 0xd7; - bs2 = 0xa0; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 4; /* for parallel programming */ - size = 1024; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = " 1 0 1 0 0 0 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", - " 0 0 0 0 0 0 0 0", - " 0 0 0 0 0 0 a1 a0", - " i i i i i i i i"; - - writepage = " 1 1 0 0 0 0 1 0", - " 0 0 0 0 0 0 a9 a8", - " a7 a6 a5 a4 a3 a2 0 0", - " x x x x x x x x"; - - mode = 0x41; - delay = 10; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 32768; - page_size = 128; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 0 0 0 0 0", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 0 0 0 0 0", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " 0 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " x x x x x x x x"; - - mode = 0x41; - delay = 10; - blocksize = 128; - readsize = 256; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 0 0 0 0 0", - "0 0 0 0 0 0 0 0 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "0 0 0 0 0 0 0 0 i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "0 0 0 0 0 0 0 0 i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "0 0 0 0 0 0 0 0 1 1 1 1 1 i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - - read = "0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + avr910_devcode = 0x74; + pagel = 0xd7; + bs2 = 0xa0; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 4; /* for parallel programming */ + size = 1024; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = " 1 0 1 0 0 0 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", + " 0 0 0 0 0 0 0 0", + " 0 0 0 0 0 0 a1 a0", + " i i i i i i i i"; + + writepage = " 1 1 0 0 0 0 1 0", + " 0 0 0 0 0 0 a9 a8", + " a7 a6 a5 a4 a3 a2 0 0", + " x x x x x x x x"; + + mode = 0x41; + delay = 10; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 32768; + page_size = 128; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 0 0 0 0 0", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 0 0 0 0 0", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " 0 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " x x x x x x x x"; + + mode = 0x41; + delay = 10; + blocksize = 128; + readsize = 256; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 0 0 0 0 0", + "0 0 0 0 0 0 0 0 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "0 0 0 0 0 0 0 0 i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "0 0 0 0 0 0 0 0 i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "0 0 0 0 0 0 0 0 1 1 1 1 1 i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + + read = "0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -13752,188 +13752,188 @@ part #------------------------------------------------------------ part - id = "m6450"; - desc = "ATMEGA6450"; - signature = 0x1E 0x96 0x06; - has_jtag = yes; + id = "m6450"; + desc = "ATMEGA6450"; + signature = 0x1E 0x96 0x06; + has_jtag = yes; # stk500_devcode = 0x??; # No STK500v1 support? # avr910_devcode = 0x??; # Try the ATmega16 one - avr910_devcode = 0x74; - pagel = 0xd7; - bs2 = 0xa0; - chip_erase_delay = 9000; - pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", - "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; - - chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; - - timeout = 200; - stabdelay = 100; - cmdexedelay = 25; - synchloops = 32; - bytedelay = 0; - pollindex = 3; - pollvalue = 0x53; - predelay = 1; - postdelay = 1; - pollmethod = 1; - - pp_controlstack = - 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, - 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, - 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, - 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; - hventerstabdelay = 100; - progmodedelay = 0; - latchcycles = 5; - togglevtg = 1; - poweroffdelay = 15; - resetdelayms = 1; - resetdelayus = 0; - hvleavestabdelay = 15; - chiperasepulsewidth = 0; - chiperasepolltimeout = 10; - programfusepulsewidth = 0; - programfusepolltimeout = 5; - programlockpulsewidth = 0; - programlockpolltimeout = 5; - - idr = 0x31; - spmcr = 0x57; - allowfullpagebitstream = no; - - memory "eeprom" - paged = no; /* leave this "no" */ - page_size = 8; /* for parallel programming */ - size = 2048; - min_write_delay = 9000; - max_write_delay = 9000; - readback_p1 = 0xff; - readback_p2 = 0xff; - read = " 1 0 1 0 0 0 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - write = " 1 1 0 0 0 0 0 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_lo = " 1 1 0 0 0 0 0 1", - " 0 0 0 0 0 0 0 0", - " 0 0 0 0 0 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 1 1 0 0 0 0 1 0", - " 0 0 0 0 0 a10 a9 a8", - " a7 a6 a5 a4 a3 0 0 0", - " x x x x x x x x"; - - mode = 0x41; - delay = 10; - blocksize = 4; - readsize = 256; - ; - - memory "flash" - paged = yes; - size = 65536; - page_size = 256; - num_pages = 256; - min_write_delay = 4500; - max_write_delay = 4500; - readback_p1 = 0xff; - readback_p2 = 0xff; - read_lo = " 0 0 1 0 0 0 0 0", - " a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - read_hi = " 0 0 1 0 1 0 0 0", - " a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " o o o o o o o o"; - - loadpage_lo = " 0 1 0 0 0 0 0 0", - " 0 0 0 0 0 0 0 0", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - loadpage_hi = " 0 1 0 0 1 0 0 0", - " 0 0 0 0 0 0 0 0", - " a7 a6 a5 a4 a3 a2 a1 a0", - " i i i i i i i i"; - - writepage = " 0 1 0 0 1 1 0 0", - " a15 a14 a13 a12 a11 a10 a9 a8", - " a7 a6 a5 a4 a3 a2 a1 a0", - " 0 0 0 0 0 0 0 0"; - - mode = 0x41; - delay = 10; - blocksize = 128; - readsize = 256; - ; - - memory "lock" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", - "x x x x x x x x x x o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 1 1 0 0 0 0 0", - "0 0 0 0 0 0 0 0 1 1 i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "lfuse" - size = 1; - read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", - "0 0 0 0 0 0 0 0 i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "hfuse" - size = 1; - read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", - "0 0 0 0 0 0 0 0 i i i i i i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "efuse" - size = 1; - - read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - - write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", - "0 0 0 0 0 0 0 0 1 1 1 1 1 i i i"; - min_write_delay = 9000; - max_write_delay = 9000; - ; - - memory "signature" - size = 3; - read = "0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 a1 a0 o o o o o o o o"; - ; - - memory "calibration" - size = 1; - - read = "0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0", - "0 0 0 0 0 0 0 0 o o o o o o o o"; - ; + avr910_devcode = 0x74; + pagel = 0xd7; + bs2 = 0xa0; + chip_erase_delay = 9000; + pgm_enable = "1 0 1 0 1 1 0 0 0 1 0 1 0 0 1 1", + "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; + + chip_erase = "1 0 1 0 1 1 0 0 1 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0"; + + timeout = 200; + stabdelay = 100; + cmdexedelay = 25; + synchloops = 32; + bytedelay = 0; + pollindex = 3; + pollvalue = 0x53; + predelay = 1; + postdelay = 1; + pollmethod = 1; + + pp_controlstack = + 0x0E, 0x1E, 0x0F, 0x1F, 0x2E, 0x3E, 0x2F, 0x3F, + 0x4E, 0x5E, 0x4F, 0x5F, 0x6E, 0x7E, 0x6F, 0x7F, + 0x66, 0x76, 0x67, 0x77, 0x6A, 0x7A, 0x6B, 0x7B, + 0xBE, 0xFD, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00; + hventerstabdelay = 100; + progmodedelay = 0; + latchcycles = 5; + togglevtg = 1; + poweroffdelay = 15; + resetdelayms = 1; + resetdelayus = 0; + hvleavestabdelay = 15; + chiperasepulsewidth = 0; + chiperasepolltimeout = 10; + programfusepulsewidth = 0; + programfusepolltimeout = 5; + programlockpulsewidth = 0; + programlockpolltimeout = 5; + + idr = 0x31; + spmcr = 0x57; + allowfullpagebitstream = no; + + memory "eeprom" + paged = no; /* leave this "no" */ + page_size = 8; /* for parallel programming */ + size = 2048; + min_write_delay = 9000; + max_write_delay = 9000; + readback_p1 = 0xff; + readback_p2 = 0xff; + read = " 1 0 1 0 0 0 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + write = " 1 1 0 0 0 0 0 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_lo = " 1 1 0 0 0 0 0 1", + " 0 0 0 0 0 0 0 0", + " 0 0 0 0 0 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 1 1 0 0 0 0 1 0", + " 0 0 0 0 0 a10 a9 a8", + " a7 a6 a5 a4 a3 0 0 0", + " x x x x x x x x"; + + mode = 0x41; + delay = 10; + blocksize = 4; + readsize = 256; + ; + + memory "flash" + paged = yes; + size = 65536; + page_size = 256; + num_pages = 256; + min_write_delay = 4500; + max_write_delay = 4500; + readback_p1 = 0xff; + readback_p2 = 0xff; + read_lo = " 0 0 1 0 0 0 0 0", + " a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + read_hi = " 0 0 1 0 1 0 0 0", + " a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " o o o o o o o o"; + + loadpage_lo = " 0 1 0 0 0 0 0 0", + " 0 0 0 0 0 0 0 0", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + loadpage_hi = " 0 1 0 0 1 0 0 0", + " 0 0 0 0 0 0 0 0", + " a7 a6 a5 a4 a3 a2 a1 a0", + " i i i i i i i i"; + + writepage = " 0 1 0 0 1 1 0 0", + " a15 a14 a13 a12 a11 a10 a9 a8", + " a7 a6 a5 a4 a3 a2 a1 a0", + " 0 0 0 0 0 0 0 0"; + + mode = 0x41; + delay = 10; + blocksize = 128; + readsize = 256; + ; + + memory "lock" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 0 0 0 0", + "x x x x x x x x x x o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 1 1 0 0 0 0 0", + "0 0 0 0 0 0 0 0 1 1 i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "lfuse" + size = 1; + read = "0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 0 0 0", + "0 0 0 0 0 0 0 0 i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "hfuse" + size = 1; + read = "0 1 0 1 1 0 0 0 0 0 0 0 1 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 1 0 0 0", + "0 0 0 0 0 0 0 0 i i i i i i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "efuse" + size = 1; + + read = "0 1 0 1 0 0 0 0 0 0 0 0 1 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + + write = "1 0 1 0 1 1 0 0 1 0 1 0 0 1 0 0", + "0 0 0 0 0 0 0 0 1 1 1 1 1 i i i"; + min_write_delay = 9000; + max_write_delay = 9000; + ; + + memory "signature" + size = 3; + read = "0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 a1 a0 o o o o o o o o"; + ; + + memory "calibration" + size = 1; + + read = "0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0", + "0 0 0 0 0 0 0 0 o o o o o o o o"; + ; ; #------------------------------------------------------------ @@ -13941,96 +13941,96 @@ part #------------------------------------------------------------ part - id = "x64a1"; - desc = "ATXMEGA64A1"; - signature = 0x1e 0x96 0x4e; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x0800; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00010000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00001000; - offset = 0x0080f000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00001000; - offset = 0x00810000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00011000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x64a1"; + desc = "ATXMEGA64A1"; + signature = 0x1e 0x96 0x4e; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x0800; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00010000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00001000; + offset = 0x0080f000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00001000; + offset = 0x00810000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00011000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -14038,96 +14038,96 @@ part #------------------------------------------------------------ part - id = "x128a1"; - desc = "ATXMEGA128A1"; - signature = 0x1e 0x97 0x4c; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x0800; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00020000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00002000; - offset = 0x0081e000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00002000; - offset = 0x00820000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00022000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x128a1"; + desc = "ATXMEGA128A1"; + signature = 0x1e 0x97 0x4c; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x0800; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00020000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00002000; + offset = 0x0081e000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00002000; + offset = 0x00820000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00022000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -14135,96 +14135,96 @@ part #------------------------------------------------------------ part - id = "x128a1d"; - desc = "ATXMEGA128A1REVD"; - signature = 0x1e 0x97 0x41; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x0800; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00020000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00002000; - offset = 0x0081e000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00002000; - offset = 0x00820000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00022000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x128a1d"; + desc = "ATXMEGA128A1REVD"; + signature = 0x1e 0x97 0x41; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x0800; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00020000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00002000; + offset = 0x0081e000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00002000; + offset = 0x00820000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00022000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -14232,96 +14232,96 @@ part #------------------------------------------------------------ part - id = "x192a1"; - desc = "ATXMEGA192A1"; - signature = 0x1e 0x97 0x4e; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x0800; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00030000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00002000; - offset = 0x0082e000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00002000; - offset = 0x00830000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00032000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x192a1"; + desc = "ATXMEGA192A1"; + signature = 0x1e 0x97 0x4e; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x0800; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00030000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00002000; + offset = 0x0082e000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00002000; + offset = 0x00830000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00032000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -14329,96 +14329,96 @@ part #------------------------------------------------------------ part - id = "x256a1"; - desc = "ATXMEGA256A1"; - signature = 0x1e 0x98 0x46; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x1000; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00040000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00002000; - offset = 0x0083e000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00002000; - offset = 0x00840000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00042000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x256a1"; + desc = "ATXMEGA256A1"; + signature = 0x1e 0x98 0x46; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x1000; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00040000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00002000; + offset = 0x0083e000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00002000; + offset = 0x00840000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00042000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -14426,96 +14426,96 @@ part #------------------------------------------------------------ part - id = "x64a3"; - desc = "ATXMEGA64A3"; - signature = 0x1e 0x96 0x42; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x0800; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00010000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00001000; - offset = 0x0080f000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00001000; - offset = 0x00810000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00011000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x64a3"; + desc = "ATXMEGA64A3"; + signature = 0x1e 0x96 0x42; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x0800; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00010000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00001000; + offset = 0x0080f000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00001000; + offset = 0x00810000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00011000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -14523,96 +14523,96 @@ part #------------------------------------------------------------ part - id = "x128a3"; - desc = "ATXMEGA128A3"; - signature = 0x1e 0x97 0x42; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x0800; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00020000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00002000; - offset = 0x0081e000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00002000; - offset = 0x00820000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00022000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x128a3"; + desc = "ATXMEGA128A3"; + signature = 0x1e 0x97 0x42; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x0800; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00020000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00002000; + offset = 0x0081e000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00002000; + offset = 0x00820000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00022000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -14620,96 +14620,96 @@ part #------------------------------------------------------------ part - id = "x192a3"; - desc = "ATXMEGA192A3"; - signature = 0x1e 0x97 0x44; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x0800; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00030000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00002000; - offset = 0x0082e000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00002000; - offset = 0x00830000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00032000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x192a3"; + desc = "ATXMEGA192A3"; + signature = 0x1e 0x97 0x44; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x0800; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00030000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00002000; + offset = 0x0082e000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00002000; + offset = 0x00830000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00032000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -14717,96 +14717,96 @@ part #------------------------------------------------------------ part - id = "x256a3"; - desc = "ATXMEGA256A3"; - signature = 0x1e 0x98 0x42; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x1000; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00040000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00002000; - offset = 0x0083e000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00002000; - offset = 0x00840000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00042000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x256a3"; + desc = "ATXMEGA256A3"; + signature = 0x1e 0x98 0x42; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x1000; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00040000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00002000; + offset = 0x0083e000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00002000; + offset = 0x00840000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00042000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -14814,96 +14814,96 @@ part #------------------------------------------------------------ part - id = "x256a3b"; - desc = "ATXMEGA256A3B"; - signature = 0x1e 0x98 0x43; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x1000; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00040000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00002000; - offset = 0x0083e000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00002000; - offset = 0x00840000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00042000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x256a3b"; + desc = "ATXMEGA256A3B"; + signature = 0x1e 0x98 0x43; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x1000; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00040000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00002000; + offset = 0x0083e000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00002000; + offset = 0x00840000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00042000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -14911,96 +14911,96 @@ part #------------------------------------------------------------ part - id = "x16a4"; - desc = "ATXMEGA16A4"; - signature = 0x1e 0x94 0x41; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x0400; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00004000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00001000; - offset = 0x00803000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00001000; - offset = 0x00804000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00005000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x16a4"; + desc = "ATXMEGA16A4"; + signature = 0x1e 0x94 0x41; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x0400; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00004000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00001000; + offset = 0x00803000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00001000; + offset = 0x00804000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00005000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -15008,96 +15008,96 @@ part #------------------------------------------------------------ part - id = "x32a4"; - desc = "ATXMEGA32A4"; - signature = 0x1e 0x95 0x41; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x0400; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00008000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00001000; - offset = 0x00807000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00001000; - offset = 0x00808000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00009000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x32a4"; + desc = "ATXMEGA32A4"; + signature = 0x1e 0x95 0x41; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x0400; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00008000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00001000; + offset = 0x00807000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00001000; + offset = 0x00808000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00009000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -15105,96 +15105,96 @@ part #------------------------------------------------------------ part - id = "x64a4"; - desc = "ATXMEGA64A4"; - signature = 0x1e 0x96 0x46; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x0800; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00010000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00001000; - offset = 0x0080f000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00001000; - offset = 0x00810000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00011000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x64a4"; + desc = "ATXMEGA64A4"; + signature = 0x1e 0x96 0x46; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x0800; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00010000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00001000; + offset = 0x0080f000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00001000; + offset = 0x00810000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00011000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; #------------------------------------------------------------ @@ -15202,96 +15202,96 @@ part #------------------------------------------------------------ part - id = "x128a4"; - desc = "ATXMEGA128A4"; - signature = 0x1e 0x97 0x46; - has_jtag = yes; - has_pdi = yes; - nvm_base = 0x01c0; - - memory "eeprom" - size = 0x0800; - offset = 0x08c0000; - page_size = 0x20; - readsize = 0x100; - ; - - memory "application" - size = 0x00020000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "apptable" - size = 0x00002000; - offset = 0x0081e000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "boot" - size = 0x00002000; - offset = 0x00820000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "flash" - size = 0x00022000; - offset = 0x0800000; - page_size = 0x100; - readsize = 0x100; - ; - - memory "prodsig" - size = 0x200; - offset = 0x8e0200; - page_size = 0x100; - readsize = 0x100; - ; - - memory "usersig" - size = 0x200; - offset = 0x8e0400; - page_size = 0x100; - readsize = 0x100; - ; - - memory "signature" - size = 3; - offset = 0x1000090; - ; - - memory "fuse0" - size = 1; - offset = 0x8f0020; - ; - - memory "fuse1" - size = 1; - offset = 0x8f0021; - ; - - memory "fuse2" - size = 1; - offset = 0x8f0022; - ; - - memory "fuse4" - size = 1; - offset = 0x8f0024; - ; - - memory "fuse5" - size = 1; - offset = 0x8f0025; - ; - - memory "lock" - size = 1; - offset = 0x8f0027; - ; + id = "x128a4"; + desc = "ATXMEGA128A4"; + signature = 0x1e 0x97 0x46; + has_jtag = yes; + has_pdi = yes; + nvm_base = 0x01c0; + + memory "eeprom" + size = 0x0800; + offset = 0x08c0000; + page_size = 0x20; + readsize = 0x100; + ; + + memory "application" + size = 0x00020000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "apptable" + size = 0x00002000; + offset = 0x0081e000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "boot" + size = 0x00002000; + offset = 0x00820000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "flash" + size = 0x00022000; + offset = 0x0800000; + page_size = 0x100; + readsize = 0x100; + ; + + memory "prodsig" + size = 0x200; + offset = 0x8e0200; + page_size = 0x100; + readsize = 0x100; + ; + + memory "usersig" + size = 0x200; + offset = 0x8e0400; + page_size = 0x100; + readsize = 0x100; + ; + + memory "signature" + size = 3; + offset = 0x1000090; + ; + + memory "fuse0" + size = 1; + offset = 0x8f0020; + ; + + memory "fuse1" + size = 1; + offset = 0x8f0021; + ; + + memory "fuse2" + size = 1; + offset = 0x8f0022; + ; + + memory "fuse4" + size = 1; + offset = 0x8f0024; + ; + + memory "fuse5" + size = 1; + offset = 0x8f0025; + ; + + memory "lock" + size = 1; + offset = 0x8f0027; + ; ; @@ -15300,20 +15300,20 @@ part #------------------------------------------------------------ part - id = "ucr2"; - desc = "32UC3A0512"; - signature = 0xED 0xC0 0x3F; - has_jtag = yes; - is_avr32 = yes; - - memory "flash" - paged = yes; - page_size = 512; # bytes - readsize = 512; # bytes - num_pages = 1024; # could be set dynamicly - size = 0x00080000; # could be set dynamicly - offset = 0x80000000; - ; + id = "ucr2"; + desc = "32UC3A0512"; + signature = 0xED 0xC0 0x3F; + has_jtag = yes; + is_avr32 = yes; + + memory "flash" + paged = yes; + page_size = 512; # bytes + readsize = 512; # bytes + num_pages = 1024; # could be set dynamicly + size = 0x00080000; # could be set dynamicly + offset = 0x80000000; + ; ; #------------------------------------------------------------ @@ -15321,38 +15321,38 @@ part #------------------------------------------------------------ part - id = "t4"; - desc = "ATtiny4"; - signature = 0x1e 0x8f 0x0a; - has_tpi = yes; - - memory "flash" - size = 512; - offset = 0x4000; - page_size = 16; - blocksize = 128; - ; - - memory "signature" - size = 3; - offset = 0x3fc0; - ; - - memory "fuse" - size = 1; - offset = 0x3f40; - blocksize = 4; - ; - - memory "calibration" - size = 1; - offset = 0x3f80; - ; - - memory "lockbits" - size = 1; - offset = 0x3f00; - ; + id = "t4"; + desc = "ATtiny4"; + signature = 0x1e 0x8f 0x0a; + has_tpi = yes; + + memory "flash" + size = 512; + offset = 0x4000; + page_size = 16; + blocksize = 128; + ; + + memory "signature" + size = 3; + offset = 0x3fc0; + ; + + memory "fuse" + size = 1; + offset = 0x3f40; + blocksize = 4; + ; + + memory "calibration" + size = 1; + offset = 0x3f80; + ; + + memory "lockbits" + size = 1; + offset = 0x3f00; + ; ; @@ -15361,38 +15361,38 @@ part #------------------------------------------------------------ part - id = "t5"; - desc = "ATtiny5"; - signature = 0x1e 0x8f 0x09; - has_tpi = yes; - - memory "flash" - size = 512; - offset = 0x4000; - page_size = 16; - blocksize = 128; - ; - - memory "signature" - size = 3; - offset = 0x3fc0; - ; - - memory "fuse" - size = 1; - offset = 0x3f40; - blocksize = 4; - ; - - memory "calibration" - size = 1; - offset = 0x3f80; - ; - - memory "lockbits" - size = 1; - offset = 0x3f00; - ; + id = "t5"; + desc = "ATtiny5"; + signature = 0x1e 0x8f 0x09; + has_tpi = yes; + + memory "flash" + size = 512; + offset = 0x4000; + page_size = 16; + blocksize = 128; + ; + + memory "signature" + size = 3; + offset = 0x3fc0; + ; + + memory "fuse" + size = 1; + offset = 0x3f40; + blocksize = 4; + ; + + memory "calibration" + size = 1; + offset = 0x3f80; + ; + + memory "lockbits" + size = 1; + offset = 0x3f00; + ; ; @@ -15401,38 +15401,38 @@ part #------------------------------------------------------------ part - id = "t8"; - desc = "ATtiny9"; - signature = 0x1e 0x90 0x08; - has_tpi = yes; - - memory "flash" - size = 1024; - offset = 0x4000; - page_size = 16; - blocksize = 128; - ; - - memory "signature" - size = 3; - offset = 0x3fc0; - ; - - memory "fuse" - size = 1; - offset = 0x3f40; - blocksize = 4; - ; - - memory "calibration" - size = 1; - offset = 0x3f80; - ; - - memory "lockbits" - size = 1; - offset = 0x3f00; - ; + id = "t8"; + desc = "ATtiny9"; + signature = 0x1e 0x90 0x08; + has_tpi = yes; + + memory "flash" + size = 1024; + offset = 0x4000; + page_size = 16; + blocksize = 128; + ; + + memory "signature" + size = 3; + offset = 0x3fc0; + ; + + memory "fuse" + size = 1; + offset = 0x3f40; + blocksize = 4; + ; + + memory "calibration" + size = 1; + offset = 0x3f80; + ; + + memory "lockbits" + size = 1; + offset = 0x3f00; + ; ; @@ -15441,38 +15441,38 @@ part #------------------------------------------------------------ part - id = "t10"; - desc = "ATtiny10"; - signature = 0x1e 0x90 0x03; - has_tpi = yes; - - memory "flash" - size = 1024; - offset = 0x4000; - page_size = 16; - blocksize = 128; - ; - - memory "signature" - size = 3; - offset = 0x3fc0; - ; - - memory "fuse" - size = 1; - offset = 0x3f40; - blocksize = 4; - ; - - memory "calibration" - size = 1; - offset = 0x3f80; - ; - - memory "lockbits" - size = 1; - offset = 0x3f00; - ; + id = "t10"; + desc = "ATtiny10"; + signature = 0x1e 0x90 0x03; + has_tpi = yes; + + memory "flash" + size = 1024; + offset = 0x4000; + page_size = 16; + blocksize = 128; + ; + + memory "signature" + size = 3; + offset = 0x3fc0; + ; + + memory "fuse" + size = 1; + offset = 0x3f40; + blocksize = 4; + ; + + memory "calibration" + size = 1; + offset = 0x3f80; + ; + + memory "lockbits" + size = 1; + offset = 0x3f00; + ; ; diff --git a/buildroot/tests/BIGTREE_BTT002 b/buildroot/tests/BIGTREE_BTT002 index 7288c5ef5260..5398d30feae9 100755 --- a/buildroot/tests/BIGTREE_BTT002 +++ b/buildroot/tests/BIGTREE_BTT002 @@ -12,8 +12,8 @@ set -e restore_configs opt_set MOTHERBOARD BOARD_BTT_BTT002_V1_0 \ SERIAL_PORT 1 \ - X_DRIVER_TYPE TMC2209 \ - Y_DRIVER_TYPE TMC2130 + X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2130 +opt_enable SENSORLESS_HOMING X_STALL_SENSITIVITY Y_STALL_SENSITIVITY SPI_ENDSTOPS exec_test $1 $2 "BigTreeTech BTT002 Default Configuration plus TMC steppers" "$3" # diff --git a/buildroot/tests/BIGTREE_GTR_V1_0 b/buildroot/tests/BIGTREE_GTR_V1_0 index d6eccaff07dc..e74b9ab5d140 100755 --- a/buildroot/tests/BIGTREE_GTR_V1_0 +++ b/buildroot/tests/BIGTREE_GTR_V1_0 @@ -16,7 +16,8 @@ opt_set E0_AUTO_FAN_PIN PC10 E1_AUTO_FAN_PIN PC11 E2_AUTO_FAN_PIN PC12 NEOPIXEL_ FIL_RUNOUT6_PIN 8 FIL_RUNOUT7_PIN 9 FIL_RUNOUT8_PIN 10 FIL_RUNOUT4_STATE HIGH FIL_RUNOUT8_STATE HIGH \ FILAMENT_RUNOUT_SCRIPT '"M600 T%c"' opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER BLTOUCH NEOPIXEL_LED Z_SAFE_HOMING NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE \ - FILAMENT_RUNOUT_SENSOR FIL_RUNOUT4_PULLUP FIL_RUNOUT8_PULLUP FILAMENT_CHANGE_RESUME_ON_INSERT PAUSE_REHEAT_FAST_RESUME + FILAMENT_RUNOUT_SENSOR FIL_RUNOUT4_PULLUP FIL_RUNOUT8_PULLUP FILAMENT_CHANGE_RESUME_ON_INSERT PAUSE_REHEAT_FAST_RESUME \ + LCD_BED_TRAMMING BED_TRAMMING_USE_PROBE exec_test $1 $2 "BigTreeTech GTR | 8 Extruders | Auto-Fan | Mixed TMC Drivers | Runout Sensors w/ distinct states" "$3" restore_configs @@ -25,12 +26,13 @@ opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT -1 \ Z_DRIVER_TYPE A4988 Z2_DRIVER_TYPE A4988 Z3_DRIVER_TYPE A4988 Z4_DRIVER_TYPE A4988 \ DEFAULT_Kp_LIST '{ 22.2, 20.0, 21.0, 19.0, 18.0 }' DEFAULT_Ki_LIST '{ 1.08 }' DEFAULT_Kd_LIST '{ 114.0, 112.0, 110.0, 108.0 }' opt_enable TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_MIGRATION_FEATURE TOOLCHANGE_FS_SLOW_FIRST_PRIME TOOLCHANGE_FS_PRIME_FIRST_USED \ - PID_PARAMS_PER_HOTEND Z_MULTI_ENDSTOPS + REPRAP_DISCOUNT_SMART_CONTROLLER PID_PARAMS_PER_HOTEND Z_MULTI_ENDSTOPS exec_test $1 $2 "BigTreeTech GTR | 6 Extruders | Quad Z + Endstops" "$3" restore_configs opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT -1 \ EXTRUDERS 3 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 \ + SERVO1_PIN PE9 SERVO2_PIN PE11 \ SERVO_DELAY '{ 300, 300, 300 }' \ SWITCHING_TOOLHEAD_X_POS '{ 215, 0 ,0 }' \ MPC_HEATER_POWER '{ 40.0f, 40.0f, 40.0f }' \ @@ -39,7 +41,7 @@ opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT -1 \ MPC_AMBIENT_XFER_COEFF '{ 0.068f, 0.068f, 0.068f }' \ MPC_AMBIENT_XFER_COEFF_FAN255 '{ 0.097f, 0.097f, 0.097f }' \ FILAMENT_HEAT_CAPACITY_PERMM '{ 5.6e-3f, 3.6e-3f, 5.6e-3f }' -opt_enable SWITCHING_TOOLHEAD TOOL_SENSOR MPCTEMP MPC_EDIT_MENU MPC_AUTOTUNE_MENU +opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SWITCHING_TOOLHEAD TOOL_SENSOR MPCTEMP MPC_EDIT_MENU MPC_AUTOTUNE_MENU opt_disable PIDTEMP exec_test $1 $2 "BigTreeTech GTR | MPC | Switching Toolhead | Tool Sensors" "$3" diff --git a/buildroot/tests/DUE b/buildroot/tests/DUE index a2f3fda7a7ac..2d2800679b8a 100755 --- a/buildroot/tests/DUE +++ b/buildroot/tests/DUE @@ -12,7 +12,8 @@ opt_set MOTHERBOARD BOARD_RAMPS4DUE_EFB \ TEMP_SENSOR_0 -2 TEMP_SENSOR_BED 2 \ GRID_MAX_POINTS_X 16 \ E0_AUTO_FAN_PIN 8 FANMUX0_PIN 53 EXTRUDER_AUTO_FAN_SPEED 100 \ - TEMP_SENSOR_CHAMBER 3 TEMP_CHAMBER_PIN 6 HEATER_CHAMBER_PIN 45 + TEMP_SENSOR_CHAMBER 3 TEMP_CHAMBER_PIN 6 HEATER_CHAMBER_PIN 45 \ + TRAMMING_POINT_XY '{{20,20},{20,20},{20,20},{20,20},{20,20}}' TRAMMING_POINT_NAME_5 '"Point 5"' opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS GCODE_MACROS \ FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING \ ASSISTED_TRAMMING REPORT_TRAMMING_MM ASSISTED_TRAMMING_WAIT_POSITION \ @@ -46,6 +47,6 @@ exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN, # Test SWITCHING_EXTRUDER # restore_configs -opt_set MOTHERBOARD BOARD_RAMPS4DUE_EEF LCD_LANGUAGE fi EXTRUDERS 2 NUM_SERVOS 1 +opt_set MOTHERBOARD BOARD_RAMPS4DUE_EEF LCD_LANGUAGE fi EXTRUDERS 2 TEMP_SENSOR_BED 0 NUM_SERVOS 1 opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER BEEP_ON_FEEDRATE_CHANGE POWER_LOSS_RECOVERY exec_test $1 $2 "RAMPS4DUE_EEF with SWITCHING_EXTRUDER, POWER_LOSS_RECOVERY" "$3" diff --git a/buildroot/tests/DUE_archim b/buildroot/tests/DUE_archim index f1711a8f3d70..8f9e6cbb81c7 100755 --- a/buildroot/tests/DUE_archim +++ b/buildroot/tests/DUE_archim @@ -16,6 +16,7 @@ exec_test $1 $2 "Archim 1 base configuration" "$3" # Test Archim 2 # use_example_configs UltiMachine/Archim2 +opt_enable USB_FLASH_DRIVE_SUPPORT exec_test $1 $2 "Archim 2 base configuration" "$3" restore_configs diff --git a/buildroot/tests/FYSETC_F6 b/buildroot/tests/FYSETC_F6 index 91b1f899ffea..c2572a71f222 100755 --- a/buildroot/tests/FYSETC_F6 +++ b/buildroot/tests/FYSETC_F6 @@ -7,13 +7,20 @@ set -e # -# Build with the default configurations +# Build with the default config plus DGUS_LCD_UI FYSETC # restore_configs opt_set MOTHERBOARD BOARD_FYSETC_F6_13 LCD_SERIAL_PORT 1 opt_enable DGUS_LCD_UI_FYSETC exec_test $1 $2 "FYSETC F6 1.3 with DGUS" "$3" +# +# Delta Config (FLSUN AC because it's complex) +# +use_example_configs delta/FLSUN/auto_calibrate +opt_set MOTHERBOARD BOARD_FYSETC_F6_13 +exec_test $1 $2 "DELTA / FLSUN Auto-Calibrate" "$3" + # # Delta Config (generic) + UBL + ALLEN_KEY + EEPROM_SETTINGS + OLED_PANEL_TINYBOY2 # @@ -21,8 +28,8 @@ use_example_configs delta/generic opt_set MOTHERBOARD BOARD_FYSETC_F6_13 LCD_LANGUAGE ko_KR opt_enable RESTORE_LEVELING_AFTER_G28 EEPROM_SETTINGS EEPROM_CHITCHAT \ Z_PROBE_ALLEN_KEY AUTO_BED_LEVELING_UBL UBL_MESH_WIZARD \ - OLED_PANEL_TINYBOY2 MESH_EDIT_GFX_OVERLAY DELTA_CALIBRATION_MENU -exec_test $1 $2 "DELTA, FYSETC F6 1.3, UBL, Allen Key, EEPROM, OLED_PANEL_TINYBOY2..." "$3" + OLED_PANEL_TINYBOY2 MESH_EDIT_GFX_OVERLAY DELTA_CALIBRATION_MENU BABYSTEPPING +exec_test $1 $2 "DELTA | UBL | Allen Key | EEPROM | OLED_PANEL_TINYBOY2..." "$3" # # Test mixed TMC config diff --git a/buildroot/tests/FYSETC_S6 b/buildroot/tests/FYSETC_S6 index 6d67800d77ec..9043b7b6e383 100755 --- a/buildroot/tests/FYSETC_S6 +++ b/buildroot/tests/FYSETC_S6 @@ -14,11 +14,14 @@ opt_set Y_DRIVER_TYPE TMC2209 Z_DRIVER_TYPE TMC2130 exec_test $1 $2 "FYSETC S6 Example" "$3" # -# Build with the default configurations with FYSETC TFT81050 +# Build with FTDI Eve Touch UI and some features # restore_configs -opt_set MOTHERBOARD BOARD_FYSETC_S6_V2_0 SERIAL_PORT 1 -opt_enable TOUCH_UI_FTDI_EVE LCD_FYSETC_TFT81050 S6_TFT_PINMAP +opt_set MOTHERBOARD BOARD_FYSETC_S6_V2_0 SERIAL_PORT 1 X_DRIVER_TYPE TMC2130 +opt_enable TOUCH_UI_FTDI_EVE LCD_FYSETC_TFT81050 S6_TFT_PINMAP LCD_LANGUAGE_2 SDSUPPORT CUSTOM_MENU_MAIN \ + FIX_MOUNTED_PROBE AUTO_BED_LEVELING_UBL Z_SAFE_HOMING \ + EEPROM_SETTINGS PRINTCOUNTER CALIBRATION_GCODE LIN_ADVANCE \ + FILAMENT_RUNOUT_SENSOR ADVANCED_PAUSE_FEATURE NOZZLE_PARK_FEATURE exec_test $1 $2 "FYSETC S6 2 with LCD FYSETC TFT81050" "$3" # cleanup diff --git a/buildroot/tests/LPC1768 b/buildroot/tests/LPC1768 index 535e776a3892..0373c761d454 100755 --- a/buildroot/tests/LPC1768 +++ b/buildroot/tests/LPC1768 @@ -27,14 +27,14 @@ exec_test $1 $2 "ReARM EFB VIKI2, SDSUPPORT, 2 Serial ports (USB CDC + UART0), N restore_configs opt_set MOTHERBOARD BOARD_MKS_SBASE \ EXTRUDERS 2 TEMP_SENSOR_1 1 \ - NUM_SERVOS 2 SERVO_DELAY '{ 300, 300 }' + NUM_SERVOS 2 SERVO_DELAY '{ 300, 300 }' SWITCHING_NOZZLE_SERVO_ANGLES '{ { 0, 90 }, { 90, 0 } }' opt_enable SWITCHING_NOZZLE SWITCHING_NOZZLE_E1_SERVO_NR EDITABLE_SERVO_ANGLES SERVO_DETACH_GCODE \ ULTIMAKERCONTROLLER REALTIME_REPORTING_COMMANDS FULL_REPORT_TO_HOST_FEATURE exec_test $1 $2 "MKS SBASE with SWITCHING_NOZZLE, Grbl Realtime Report" "$3" restore_configs opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EEB \ - EXTRUDERS 2 TEMP_SENSOR_1 -1 TEMP_SENSOR_BED 5 \ + EXTRUDERS 2 TEMP_SENSOR_1 -4 TEMP_SENSOR_BED 5 \ GRID_MAX_POINTS_X 16 \ NOZZLE_TO_PROBE_OFFSET '{ 0, 0, 0 }' \ NOZZLE_CLEAN_MIN_TEMP 170 \ @@ -47,7 +47,7 @@ opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER ADAPTIVE_FAN_SLOWING NO BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE \ - HOST_KEEPALIVE_FEATURE HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT \ + HOST_KEEPALIVE_FEATURE HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_STATUS_NOTIFICATIONS \ LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES \ SDSUPPORT SDCARD_SORT_ALPHA AUTO_REPORT_SD_STATUS EMERGENCY_PARSER SOFT_RESET_ON_KILL SOFT_RESET_VIA_SERIAL exec_test $1 $2 "Re-ARM with NOZZLE_AS_PROBE and many features." "$3" diff --git a/buildroot/tests/LPC1769 b/buildroot/tests/LPC1769 index dae65b6a3509..6b8c92ad47ac 100755 --- a/buildroot/tests/LPC1769 +++ b/buildroot/tests/LPC1769 @@ -14,7 +14,7 @@ exec_test $1 $2 "Azteeg X5GT Example Configuration" "$3" restore_configs opt_set MOTHERBOARD BOARD_SMOOTHIEBOARD \ - EXTRUDERS 2 TEMP_SENSOR_0 -5 TEMP_SENSOR_1 -1 TEMP_SENSOR_BED 5 TEMP_0_CS_PIN P1_29 \ + EXTRUDERS 2 TEMP_SENSOR_0 -5 TEMP_SENSOR_1 -4 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 } }" @@ -43,6 +43,7 @@ exec_test $1 $2 "Smoothieboard with TFTGLCD_PANEL_SPI and many features" "$3" restore_configs use_example_configs delta/generic opt_set MOTHERBOARD BOARD_COHESION3D_REMIX \ + TEMP_SENSOR_0 1 \ X_DRIVER_TYPE TMC2130 Y_DRIVER_TYPE TMC2130 Z_DRIVER_TYPE TMC2130 I_DRIVER_TYPE TB6560 \ DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 400, 500, 80 }' \ DEFAULT_MAX_FEEDRATE '{ 300, 300, 5, 25, 300 }' \ diff --git a/buildroot/tests/NUCLEO_F767ZI b/buildroot/tests/NUCLEO_F767ZI index 9e2324660695..870c7ade3bfa 100755 --- a/buildroot/tests/NUCLEO_F767ZI +++ b/buildroot/tests/NUCLEO_F767ZI @@ -11,7 +11,7 @@ set -e # restore_configs opt_set MOTHERBOARD BOARD_NUCLEO_F767ZI SERIAL_PORT -1 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2208 -opt_enable BLTOUCH Z_SAFE_HOMING SPEAKER SOFTWARE_DRIVER_ENABLE +opt_enable BLTOUCH Z_SAFE_HOMING REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SPEAKER SOFTWARE_DRIVER_ENABLE exec_test $1 $2 "Mixed timer usage" "$3" # clean up diff --git a/buildroot/tests/Opulo_Lumen_REV3 b/buildroot/tests/Opulo_Lumen_REV3 index ddd8e1f3c9aa..f12f69011e78 100755 --- a/buildroot/tests/Opulo_Lumen_REV3 +++ b/buildroot/tests/Opulo_Lumen_REV3 @@ -7,6 +7,7 @@ set -e use_example_configs Opulo/Lumen_REV3 +opt_disable TMC_DEBUG exec_test $1 $2 "Opulo Lumen REV3 Pick-and-Place" "$3" # cleanup diff --git a/buildroot/tests/SAMD21_minitronics20 b/buildroot/tests/SAMD21_minitronics20 index 018d6a70fe00..037c7514ed97 100755 --- a/buildroot/tests/SAMD21_minitronics20 +++ b/buildroot/tests/SAMD21_minitronics20 @@ -25,8 +25,7 @@ opt_enable ENDSTOP_INTERRUPTS_FEATURE BLTOUCH Z_MIN_PROBE_REPEATABILITY_TEST \ LONG_FILENAME_HOST_SUPPORT CUSTOM_FIRMWARE_UPLOAD M20_TIMESTAMP_SUPPORT \ SCROLL_LONG_FILENAMES BABYSTEPPING DOUBLECLICK_FOR_Z_BABYSTEPPING \ MOVE_Z_WHEN_IDLE BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ - LIN_ADVANCE ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE MONITOR_DRIVER_STATUS SENSORLESS_HOMING \ - SQUARE_WAVE_STEPPING EXPERIMENTAL_SCURVE + LIN_ADVANCE ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE MONITOR_DRIVER_STATUS exec_test $1 $2 "Minitronics 2.0 with assorted features" "$3" # clean up diff --git a/buildroot/tests/SAMD51_grandcentral_m4 b/buildroot/tests/SAMD51_grandcentral_m4 index 3a5ac8e70cc9..d224152a0f64 100755 --- a/buildroot/tests/SAMD51_grandcentral_m4 +++ b/buildroot/tests/SAMD51_grandcentral_m4 @@ -25,8 +25,9 @@ opt_enable ENDSTOP_INTERRUPTS_FEATURE S_CURVE_ACCELERATION BLTOUCH Z_MIN_PROBE_R LONG_FILENAME_HOST_SUPPORT CUSTOM_FIRMWARE_UPLOAD M20_TIMESTAMP_SUPPORT \ SCROLL_LONG_FILENAMES BABYSTEPPING DOUBLECLICK_FOR_Z_BABYSTEPPING \ MOVE_Z_WHEN_IDLE BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ - LIN_ADVANCE ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE MONITOR_DRIVER_STATUS SENSORLESS_HOMING \ - SQUARE_WAVE_STEPPING TMC_DEBUG EXPERIMENTAL_SCURVE + LIN_ADVANCE ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE MONITOR_DRIVER_STATUS \ + SENSORLESS_HOMING X_STALL_SENSITIVITY Y_STALL_SENSITIVITY Z_STALL_SENSITIVITY Z2_STALL_SENSITIVITY \ + SQUARE_WAVE_STEPPING TMC_DEBUG exec_test $1 $2 "Grand Central M4 with assorted features" "$3" # clean up diff --git a/buildroot/tests/STM32F103RC_btt b/buildroot/tests/STM32F103RC_btt index 16419cbfa232..3f8d58630cbe 100755 --- a/buildroot/tests/STM32F103RC_btt +++ b/buildroot/tests/STM32F103RC_btt @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# Build tests for STM32F103RC BigTreeTech (SKR Mini E3) +# Build tests for STM32F103RC_btt (BigTreeTech SKR Mini E3) # # exit on first failure @@ -12,8 +12,8 @@ set -e restore_configs opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_E3_V1_0 SERIAL_PORT 1 SERIAL_PORT_2 -1 \ X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 Z_DRIVER_TYPE TMC2209 E0_DRIVER_TYPE TMC2209 -opt_enable PINS_DEBUGGING Z_IDLE_HEIGHT -exec_test $1 $2 "BigTreeTech SKR Mini E3 1.0 - Basic Config with TMC2209 HW Serial" "$3" +opt_enable CR10_STOCKDISPLAY PINS_DEBUGGING Z_IDLE_HEIGHT ADAPTIVE_STEP_SMOOTHING +exec_test $1 $2 "BigTreeTech SKR Mini E3 1.0 - TMC2209 HW Serial" "$3" # clean up restore_configs diff --git a/buildroot/tests/STM32F103RE b/buildroot/tests/STM32F103RE index 641f1fa56c80..111eb266441a 100755 --- a/buildroot/tests/STM32F103RE +++ b/buildroot/tests/STM32F103RE @@ -11,12 +11,12 @@ set -e # restore_configs opt_set MOTHERBOARD BOARD_STM32F103RE SERIAL_PORT -1 EXTRUDERS 2 \ - NOZZLE_CLEAN_START_POINT "{ { 10, 10, 3 }, { 10, 10, 3 } }" \ - NOZZLE_CLEAN_END_POINT "{ { 10, 20, 3 }, { 10, 20, 3 } }" -opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT \ + NOZZLE_CLEAN_START_POINT "{ { 10, 10, 3 } }" \ + NOZZLE_CLEAN_END_POINT "{ { 10, 20, 3 } }" +opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT SDSUPPORT \ PAREN_COMMENTS GCODE_MOTION_MODES SINGLENOZZLE TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_PARK \ BAUD_RATE_GCODE GCODE_MACROS NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE -exec_test $1 $2 "STM32F1R EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT PAREN_COMMENTS GCODE_MOTION_MODES" "$3" +exec_test $1 $2 "STM32F1R EEPROM_SETTINGS EEPROM_CHITCHAT SDSUPPORT PAREN_COMMENTS GCODE_MOTION_MODES" "$3" # cleanup restore_configs diff --git a/buildroot/tests/STM32F103RE_btt_USB b/buildroot/tests/STM32F103RE_btt_USB index 7b264ea28312..0bf5f616e4f3 100755 --- a/buildroot/tests/STM32F103RE_btt_USB +++ b/buildroot/tests/STM32F103RE_btt_USB @@ -11,11 +11,12 @@ set -e # restore_configs opt_set MOTHERBOARD BOARD_BTT_SKR_E3_DIP SERIAL_PORT 1 SERIAL_PORT_2 -1 +opt_enable SDSUPPORT EMERGENCY_PARSER 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 FAN_SOFT_PWM \ +opt_enable CR10_STOCKDISPLAY SDSUPPORT EMERGENCY_PARSER 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/STM32F103RE_creality b/buildroot/tests/STM32F103RE_creality index ad7bead6c358..9a2a7f9f2144 100755 --- a/buildroot/tests/STM32F103RE_creality +++ b/buildroot/tests/STM32F103RE_creality @@ -11,21 +11,26 @@ set -e # use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_enable MARLIN_DEV_MODE BUFFER_MONITORING BLTOUCH AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING -exec_test $1 $2 "Ender-3 v2 with CrealityUI" "$3" +exec_test $1 $2 "Ender-3 V2 - CrealityUI" "$3" use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_disable DWIN_CREALITY_LCD opt_enable DWIN_CREALITY_LCD_JYERSUI AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY -exec_test $1 $2 "Ender-3 v2 with JyersUI" "$3" +exec_test $1 $2 "Ender-3 V2 - JyersUI (ABL Bilinear/Manual)" "$3" + +use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" +opt_disable DWIN_CREALITY_LCD PIDTEMP +opt_enable DWIN_MARLINUI_LANDSCAPE AUTO_BED_LEVELING_UBL BLTOUCH Z_SAFE_HOMING MPCTEMP +exec_test $1 $2 "Ender-3 V2 - MarlinUI (UBL+BLTOUCH, MPCTEMP)" "$3" use_example_configs "Creality/Ender-3 S1/STM32F1" -opt_disable DWIN_CREALITY_LCD Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN AUTO_BED_LEVELING_BILINEAR CANCEL_OBJECTS FWRETRACT +opt_disable DWIN_CREALITY_LCD Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN AUTO_BED_LEVELING_BILINEAR CANCEL_OBJECTS FWRETRACT EVENT_GCODE_SD_ABORT opt_enable DWIN_LCD_PROUI INDIVIDUAL_AXIS_HOMING_SUBMENU SET_PROGRESS_MANUALLY SET_PROGRESS_PERCENT STATUS_MESSAGE_SCROLLING \ SOUND_MENU_ITEM PRINTCOUNTER NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE FILAMENT_RUNOUT_SENSOR \ BLTOUCH Z_SAFE_HOMING AUTO_BED_LEVELING_UBL MESH_EDIT_MENU \ LIMITED_MAX_FR_EDITING LIMITED_MAX_ACCEL_EDITING LIMITED_JERK_EDITING BAUD_RATE_GCODE -opt_set PREHEAT_3_LABEL '"CUSTOM"' PREHEAT_3_TEMP_HOTEND 240 PREHEAT_3_TEMP_BED 60 PREHEAT_3_FAN_SPEED 128 -exec_test $1 $2 "Ender-3 S1 with ProUI" "$3" +opt_set PREHEAT_3_LABEL '"CUSTOM"' PREHEAT_3_TEMP_HOTEND 240 PREHEAT_3_TEMP_BED 60 PREHEAT_3_FAN_SPEED 128 BOOTSCREEN_TIMEOUT 1100 +exec_test $1 $2 "Ender-3 S1 - ProUI (PIDTEMP)" "$3" restore_configs opt_set MOTHERBOARD BOARD_CREALITY_V452 SERIAL_PORT 1 @@ -34,12 +39,5 @@ opt_enable NOZZLE_AS_PROBE Z_SAFE_HOMING Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN FAN_ PROBE_ACTIVATION_SWITCH PROBE_TARE PROBE_TARE_ONLY_WHILE_INACTIVE exec_test $1 $2 "Creality V4.5.2 PROBE_ACTIVATION_SWITCH, Probe Tare" "$3" -restore_configs -opt_set MOTHERBOARD BOARD_CREALITY_V422 SERIAL_PORT 1 DGUS_LCD_UI IA_CREALITY -opt_enable NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE LCD_BED_TRAMMING CLASSIC_JERK BABYSTEPPING \ - AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY FAN_SOFT_PWM -opt_add NO_CREALITY_422_DRIVER_WARNING NO_AUTO_ASSIGN_WARNING -exec_test $1 $2 "Creality V4.2.2 with IA_CREALITY" "$3" - # clean up restore_configs diff --git a/buildroot/tests/STM32F103VE_longer_maple b/buildroot/tests/STM32F103VE_longer_maple index 4570a3214d17..9f594be61ac0 100755 --- a/buildroot/tests/STM32F103VE_longer_maple +++ b/buildroot/tests/STM32F103VE_longer_maple @@ -8,16 +8,16 @@ set -e use_example_configs Alfawise/U20 opt_enable BAUD_RATE_GCODE -exec_test $1 $2 "maple CLASSIC_UI U20 config" "$3" +exec_test $1 $2 "Maple - Alfawise U20 - CLASSIC_UI" "$3" use_example_configs Alfawise/U20 opt_enable BAUD_RATE_GCODE TFT_COLOR_UI opt_disable TFT_CLASSIC_UI CUSTOM_STATUS_SCREEN_IMAGE -exec_test $1 $2 "maple COLOR_UI U20 config" "$3" +exec_test $1 $2 "Maple - Alfawise U20 - COLOR_UI" "$3" use_example_configs Alfawise/U20-bltouch opt_enable BAUD_RATE_GCODE -exec_test $1 $2 "maple BLTouch U20 config" +exec_test $1 $2 "Maple - Alfawise U20 - BLTouch" # cleanup restore_configs diff --git a/buildroot/tests/STM32F401RC_creality b/buildroot/tests/STM32F401RC_creality index fbc5194d602c..61b8d2ef9ce0 100755 --- a/buildroot/tests/STM32F401RC_creality +++ b/buildroot/tests/STM32F401RC_creality @@ -7,8 +7,9 @@ set -e use_example_configs "Creality/Ender-3 V2/CrealityV422/MarlinUI" -opt_add SDCARD_EEPROM_EMULATION AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING +opt_enable AUTO_BED_LEVELING_BILINEAR Z_SAFE_HOMING opt_set MOTHERBOARD BOARD_CREALITY_V24S1_301F4 +opt_add SDCARD_EEPROM_EMULATION exec_test $1 $2 "Ender-3 v2 with MarlinUI" "$3" # clean up diff --git a/buildroot/tests/STM32G0B1RE_btt b/buildroot/tests/STM32G0B1RE_btt new file mode 100755 index 000000000000..35ccf0f93688 --- /dev/null +++ b/buildroot/tests/STM32G0B1RE_btt @@ -0,0 +1,16 @@ +#!/usr/bin/env bash +# +# Build tests for STM32G0B1RE_btt / Ender-3 with SKR Mini E3 V3.0 (STM32G0) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +use_example_configs "Creality/Ender-3/BigTreeTech SKR Mini E3 3.0" +exec_test $1 $2 "Creality/Ender-3/BigTreeTech SKR Mini E3 3.0" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/STM32H743VI_btt b/buildroot/tests/STM32H743VI_btt new file mode 100755 index 000000000000..48933e8c4642 --- /dev/null +++ b/buildroot/tests/STM32H743VI_btt @@ -0,0 +1,17 @@ +#!/usr/bin/env bash +# +# Build tests for STM32H743VI_btt +# Ender-5 Plus with SKR V3.0 (STM32H7) +# + +# exit on first failure +set -e + +# +# Build with the default configurations +# +use_example_configs "Creality/Ender-5 Plus/BigTreeTech SKR 3" +exec_test $1 $2 "Creality Ender-5 Plus with BigTreeTech SKR 3" "$3" + +# clean up +restore_configs diff --git a/buildroot/tests/at90usb1286_cdc b/buildroot/tests/at90usb1286_cdc index 01d752db8b4c..7dcf8d541ab5 100755 --- a/buildroot/tests/at90usb1286_cdc +++ b/buildroot/tests/at90usb1286_cdc @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# Build tests for AT90USB1286 ARMED +# Build tests for AT90USB1286 (CDC) # # exit on first failure diff --git a/buildroot/tests/at90usb1286_dfu b/buildroot/tests/at90usb1286_dfu index 75672a6a5150..a753097694c4 100755 --- a/buildroot/tests/at90usb1286_dfu +++ b/buildroot/tests/at90usb1286_dfu @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# Build tests for AT90USB1286 ARMED +# Build tests for AT90USB1286 (DFU) # # exit on first failure diff --git a/buildroot/tests/esp32 b/buildroot/tests/esp32 index a0f79107cf2f..2229b950c6ea 100755 --- a/buildroot/tests/esp32 +++ b/buildroot/tests/esp32 @@ -12,8 +12,8 @@ set -e restore_configs opt_set MOTHERBOARD BOARD_ESPRESSIF_ESP32 TX_BUFFER_SIZE 64 \ WIFI_SSID '"ssid"' WIFI_PWD '"password"' -opt_enable WIFISUPPORT WEBSUPPORT GCODE_MACROS BAUD_RATE_GCODE M115_GEOMETRY_REPORT REPETIER_GCODE_M360 -exec_test $1 $2 "ESP32 with WIFISUPPORT and WEBSUPPORT" "$3" +opt_enable WIFISUPPORT WEBSUPPORT OTASUPPORT GCODE_MACROS BAUD_RATE_GCODE M115_GEOMETRY_REPORT REPETIER_GCODE_M360 +exec_test $1 $2 "ESP32 with WIFISUPPORT and WEBSUPPORT and OTASUPPORT" "$3" # # Build with TMC drivers using hardware serial diff --git a/buildroot/tests/mega1280 b/buildroot/tests/mega1280 index 5bf37289ba61..8be9f613e0c2 100755 --- a/buildroot/tests/mega1280 +++ b/buildroot/tests/mega1280 @@ -41,6 +41,7 @@ opt_set MOTHERBOARD BOARD_ZRIB_V52 \ LCD_LANGUAGE pt REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 \ EXTRUDERS 2 TEMP_SENSOR_1 1 X2_DRIVER_TYPE A4988 opt_enable USE_XMAX_PLUG DUAL_X_CARRIAGE REPRAPWORLD_KEYPAD +opt_add DEBUG_DXC_MODE exec_test $1 $2 "ZRIB_V52 | DUAL_X_CARRIAGE" "$3" # diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index de305082ecda..a4a8734cfa67 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -30,9 +30,10 @@ opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATU REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LIGHTWEIGHT_UI STATUS_MESSAGE_SCROLLING SHOW_CUSTOM_BOOTSCREEN BOOT_MARLIN_LOGO_SMALL \ SDSUPPORT SDCARD_SORT_ALPHA USB_FLASH_DRIVE_SUPPORT AUTO_REPORT_SD_STATUS SCROLL_LONG_FILENAMES MEDIA_MENU_AT_TOP \ EEPROM_SETTINGS EEPROM_CHITCHAT GCODE_MACROS CUSTOM_MENU_MAIN FREEZE_FEATURE CANCEL_OBJECTS SOUND_MENU_ITEM \ - MULTI_NOZZLE_DUPLICATION CLASSIC_JERK LIN_ADVANCE ADVANCE_K_EXTRA QUICK_HOME \ + EMERGENCY_PARSER MULTI_NOZZLE_DUPLICATION CLASSIC_JERK LIN_ADVANCE ADVANCE_K_EXTRA QUICK_HOME \ SET_PROGRESS_MANUALLY SET_PROGRESS_PERCENT PRINT_PROGRESS_SHOW_DECIMALS SHOW_REMAINING_TIME \ ENCODER_NOISE_FILTER BABYSTEPPING BABYSTEP_XY NANODLP_Z_SYNC I2C_POSITION_ENCODERS M114_DETAIL +opt_disable ENCODER_RATE_MULTIPLIER exec_test $1 $2 "Azteeg X3 Pro | EXTRUDERS 5 | RRDFGSC | UBL | LIN_ADVANCE ..." "$3" # @@ -53,14 +54,13 @@ opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LIGHTWEIGHT_UI SHOW_CUS opt_disable SEGMENT_LEVELED_MOVES exec_test $1 $2 "Azteeg X3 Pro | EXTRUDERS 5 | RRDFGSC | UBL | LIN_ADVANCE | Sled Probe | Skew | JP-Kana | Babystep offsets ..." "$3" - # # 5 runout sensors with distinct states # restore_configs opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO NUM_SERVOS 1 \ - EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 \ - NUM_RUNOUT_SENSORS 5 FIL_RUNOUT2_PIN 44 FIL_RUNOUT3_PIN 45 FIL_RUNOUT4_PIN 46 FIL_RUNOUT5_PIN 47 \ + EXTRUDERS 4 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 FAN_KICKSTART_TIME 500 \ + NUM_RUNOUT_SENSORS 4 FIL_RUNOUT2_PIN 44 FIL_RUNOUT3_PIN 45 FIL_RUNOUT4_PIN 46 FIL_RUNOUT5_PIN 47 \ FIL_RUNOUT3_STATE HIGH FILAMENT_RUNOUT_SCRIPT '"M600 T%c"' opt_enable VIKI2 BOOT_MARLIN_LOGO_ANIMATED SDSUPPORT AUTO_REPORT_SD_STATUS \ Z_PROBE_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE \ @@ -68,21 +68,21 @@ opt_enable VIKI2 BOOT_MARLIN_LOGO_ANIMATED SDSUPPORT AUTO_REPORT_SD_STATUS \ NO_VOLUMETRICS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET JOYSTICK \ DIRECT_STEPPING DETECT_BROKEN_ENDSTOP \ FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE Z_SAFE_HOMING FIL_RUNOUT3_PULLUP -exec_test $1 $2 "Multiple runout sensors (x5) | Distinct runout states" "$3" +exec_test $1 $2 "Azteeg X3 Pro | EXTRUDERS 4 | VIKI2 | Servo Probe | Multiple runout sensors (x4)" "$3" # -# Mixing Extruder with 5 steppers, Greek +# Mixing Extruder with 5 steppers, Russian # restore_configs opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO MIXING_STEPPERS 5 LCD_LANGUAGE ru \ - NUM_RUNOUT_SENSORS E_STEPPERS REDUNDANT_PART_COOLING_FAN 1 \ + NUM_RUNOUT_SENSORS E_STEPPERS TEMP_SENSOR_BED 0 REDUNDANT_PART_COOLING_FAN 1 \ FIL_RUNOUT2_PIN 16 FIL_RUNOUT3_PIN 17 FIL_RUNOUT4_PIN 4 FIL_RUNOUT5_PIN 5 opt_enable MIXING_EXTRUDER GRADIENT_MIX GRADIENT_VTOOL CR10_STOCKDISPLAY \ USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE CONTROLLER_FAN_IGNORE_Z \ FILAMENT_RUNOUT_SENSOR ADVANCED_PAUSE_FEATURE NOZZLE_PARK_FEATURE INPUT_SHAPING_X INPUT_SHAPING_Y -opt_disable DISABLE_INACTIVE_EXTRUDER -exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Input Shaping | Greek" "$3" +opt_disable DISABLE_OTHER_EXTRUDERS +exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Input Shaping | Russian" "$3" # # Test SPEAKER with BOARD_BQ_ZUM_MEGA_3D and BQ_LCD_SMART_CONTROLLER @@ -126,7 +126,7 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Input Shaping #opt_set MOTHERBOARD BOARD_RIGIDBOARD_V2 #opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING DAC_MOTOR_CURRENT_DEFAULT #exec_test $1 $2 "Stuff" "$3" -# # +# # G3D_PANEL with SDCARD_SORT_ALPHA and STATUS_MESSAGE_SCROLLING # #restore_configs @@ -177,9 +177,9 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Input Shaping #opt_enable LCM1602 #exec_test $1 $2 "Stuff" "$3" -# # -# # Test Laser features with 12864 LCD -# # +# +# Test Laser features with 12864 LCD +# # restore_configs # opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 0 LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 TEMP_SENSOR_1 0 SERIAL_PORT_2 2 \ # DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 400 }' \ @@ -191,9 +191,9 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Input Shaping # LASER_FEATURE LASER_SAFETY_TIMEOUT_MS LASER_COOLANT_FLOW_METER AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_SYNCHRONOUS_M106_M107 # exec_test $1 $2 "MEGA2560 RAMPS | Laser Options | 12864 | Meatpack | Fan Sync | SERIAL_PORT_2 " "$3" -# # -# # Test Laser features with 44780 LCD -# # +# +# Test Laser features with 44780 LCD +# # restore_configs # opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 0 LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 TEMP_SENSOR_1 0 \ # DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 400 }' \ @@ -205,9 +205,9 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Input Shaping # LASER_FEATURE LASER_SAFETY_TIMEOUT_MS LASER_COOLANT_FLOW_METER AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN # exec_test $1 $2 "MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Laser Safety Timeout | Flowmeter | 44780 LCD " "$3" -# # -# # Test redundant temperature sensors + MAX TC + Backlight Timeout -# # +# +# Test redundant temperature sensors + MAX TC + Backlight Timeout +# # restore_configs # opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 1 \ # TEMP_SENSOR_0 -2 TEMP_SENSOR_REDUNDANT -2 \ @@ -218,9 +218,9 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Input Shaping # opt_disable PIDTEMP # exec_test $1 $2 "MEGA2560 RAMPS | Redundant temperature sensor | 2x MAX6675 | BL Timeout" "$3" -# # -# # Polargraph Config -# # +# +# Polargraph Config +# # use_example_configs Polargraph # exec_test $1 $2 "RUMBA | POLARGRAPH | RRD LCD" "$3" diff --git a/buildroot/tests/mks_robin_nano_v1v2_maple b/buildroot/tests/mks_robin_nano_v1v2_maple index ebd5466ce61c..e241c14b9fe6 100755 --- a/buildroot/tests/mks_robin_nano_v1v2_maple +++ b/buildroot/tests/mks_robin_nano_v1v2_maple @@ -40,11 +40,10 @@ exec_test $1 $2 "MKS Robin v2 nano LVGL SPI w/ WiFi" "$3" # (Robin v2 nano has no FSMC interface) # use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 -opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 -opt_enable BINARY_FILE_TRANSFER -exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI + BINARY_FILE_TRANSFER" "$3" +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 TFT_ROTATION TFT_ROTATE_90 +opt_disable TFT_INTERFACE_FSMC +opt_enable TFT_INTERFACE_SPI BINARY_FILE_TRANSFER +exec_test $1 $2 "MKS Robin v2 nano New Color UI 240x320 SPI + BINARY_FILE_TRANSFER" "$3" # # MKS Robin v2 nano LVGL SPI + TMC diff --git a/buildroot/tests/mks_robin_pro2 b/buildroot/tests/mks_robin_pro2 new file mode 100755 index 000000000000..391943743378 --- /dev/null +++ b/buildroot/tests/mks_robin_pro2 @@ -0,0 +1,20 @@ +#!/usr/bin/env bash +# +# Build tests for mks_robin_pro2 (STM32F407VE) +# + +# exit on first failure +set -e + +# +# Robin Pro v2 with LVGL TFT +# +restore_configs +opt_set MOTHERBOARD BOARD_MKS_ROBIN_PRO_V2 SERIAL_PORT 1 +opt_enable SDSUPPORT USB_FLASH_DRIVE_SUPPORT USE_OTG_USB_HOST MULTI_VOLUME \ + TFT_GENERIC TFT_INTERFACE_SPI TFT_RES_480x320 TFT_LVGL_UI TOUCH_SCREEN \ + BLTOUCH Z_SAFE_HOMING LCD_BED_TRAMMING BED_TRAMMING_USE_PROBE +exec_test $1 $2 "MKS Robin Pro v2 | TFT_LVGL_UI | SD/FD Multi-Volume" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/mks_tinybee b/buildroot/tests/mks_tinybee index 9dcc33ede7c5..591411280e5a 100755 --- a/buildroot/tests/mks_tinybee +++ b/buildroot/tests/mks_tinybee @@ -10,11 +10,9 @@ set -e # Build with ESP3D WiFi, OTA and custom WIFI commands support # restore_configs -opt_set MOTHERBOARD BOARD_MKS_TINYBEE TX_BUFFER_SIZE 64 \ - WIFI_SSID '"ssid"' WIFI_PWD '"password"' \ - SERIAL_PORT_2 -1 BAUDRATE_2 250000 -opt_enable ESP3D_WIFISUPPORT WEBSUPPORT OTASUPPORT WIFI_CUSTOM_COMMAND -exec_test $1 "$2" "MKS TinyBee with ESP3D_WIFISUPPORT" "$3" +opt_set MOTHERBOARD BOARD_MKS_TINYBEE TX_BUFFER_SIZE 64 SERIAL_PORT_2 -1 BAUDRATE_2 250000 +opt_enable ESP3D_WIFISUPPORT +exec_test $1 $2 "MKS TinyBee with ESP3D_WIFISUPPORT" "$3" # # Build with LCD, SD support and Speaker support @@ -25,8 +23,8 @@ opt_set MOTHERBOARD BOARD_MKS_TINYBEE \ LCD_INFO_SCREEN_STYLE 0 \ DISPLAY_CHARSET_HD44780 WESTERN \ NEOPIXEL_TYPE NEO_RGB -opt_enable FYSETC_MINI_12864_2_1 SDSUPPORT -opt_enable LED_CONTROL_MENU LED_USER_PRESET_STARTUP LED_COLOR_PRESETS NEOPIXEL_LED +opt_enable FYSETC_MINI_12864_2_1 SDSUPPORT NO_SD_AUTOSTART \ + NEOPIXEL_LED LED_CONTROL_MENU LED_USER_PRESET_STARTUP LED_COLOR_PRESETS exec_test $1 $2 "MKS TinyBee with NeoPixel LCD, SD and Speaker" "$3" # cleanup diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index 9a017c971fbb..e19d16362447 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -35,7 +35,7 @@ opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_P PSU_CONTROL LED_POWEROFF_TIMEOUT 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 ADVANCE_K_EXTRA \ - HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL + HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_STATUS_NOTIFICATIONS PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL opt_add DEBUG_POWER_LOSS_RECOVERY exec_test $1 $2 "RAMBO | EXTRUDERS 2 | CHAR LCD + SD | FIX Probe | ABL-Linear | Advanced Pause | PLR | LEDs ..." "$3" @@ -74,6 +74,14 @@ opt_set MOTHERBOARD BOARD_RAMBO EXTRUDERS 0 TEMP_SENSOR_BED 1 TEMP_SENSOR_PROBE opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER FIX_MOUNTED_PROBE Z_SAFE_HOMING exec_test $1 $2 "Rambo heated bed only" "$3" +# +# Rambo with MMU2 +# +restore_configs +opt_set MOTHERBOARD BOARD_RAMBO EXTRUDERS 5 MMU_MODEL PRUSA_MMU2 +opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE EMERGENCY_PARSER MMU2_DEBUG +exec_test $1 $2 "Rambo with PRUSA_MMU2 " "$3" + # # Build with the default configurations # @@ -122,10 +130,10 @@ opt_enable COREYX USE_XMAX_PLUG MIXING_EXTRUDER GRADIENT_MIX \ 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 \ + SD_ABORT_ON_ENDSTOP_HIT HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_STATUS_NOTIFICATIONS HOST_PAUSE_M76 ADVANCED_OK M114_DETAIL \ VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS EXTRA_FAN_SPEED FWRETRACT \ USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE CONTROLLER_FAN_USE_Z_ONLY -opt_disable DISABLE_INACTIVE_EXTRUDER +opt_disable DISABLE_OTHER_EXTRUDERS exec_test $1 $2 "Rambo | CoreXY, Gradient Mix | Endstop Int. | Home Y > X | FW Retract ..." "$3" # clean up diff --git a/buildroot/tests/rumba32 b/buildroot/tests/rumba32 index 833769d0b9ba..c3d7603e4e8d 100755 --- a/buildroot/tests/rumba32 +++ b/buildroot/tests/rumba32 @@ -13,7 +13,7 @@ opt_set MOTHERBOARD BOARD_RUMBA32_V1_0 SERIAL_PORT -1 \ opt_disable PIDTEMP opt_enable PIDTEMPBED FAN_SOFT_PWM opt_disable THERMAL_PROTECTION_BED -exec_test $1 $2 "RUMBA32 V1.0 with TMC2130, PID Bed, and bed thermal protection disabled" "$3" +exec_test $1 $2 "RUMBA32 V1.0 with TMC2130, PID Bed, no Bed Thermal Protection" "$3" # Build examples restore_configs diff --git a/buildroot/tests/teensy31 b/buildroot/tests/teensy31 index 7465a67fdde1..f3f0e29dcf46 100755 --- a/buildroot/tests/teensy31 +++ b/buildroot/tests/teensy31 @@ -33,5 +33,5 @@ opt_enable EEPROM_SETTINGS FILAMENT_WIDTH_SENSOR CALIBRATION_GCODE BAUD_RATE_GCO NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE PARK_HEAD_ON_PAUSE \ ARC_SUPPORT BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES \ PHOTO_GCODE PHOTO_POSITION PHOTO_SWITCH_POSITION PHOTO_SWITCH_MS PHOTO_DELAY_MS PHOTO_RETRACT_MM \ - HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT + HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_STATUS_NOTIFICATIONS exec_test $1 $2 "Teensy3.1 with many features" "$3" diff --git a/buildroot/tests/teensy35 b/buildroot/tests/teensy35 index 64ce4e65505a..d29ea5109288 100755 --- a/buildroot/tests/teensy35 +++ b/buildroot/tests/teensy35 @@ -20,14 +20,15 @@ opt_set MOTHERBOARD BOARD_TEENSY35_36 \ 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 REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LCD_INFO_MENU SDSUPPORT SDCARD_SORT_ALPHA \ +opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT SDCARD_SORT_ALPHA \ + LCD_INFO_MENU LCD_PRINTER_INFO_IS_BOOTSCREEN TURBO_BACK_MENU_ITEM PREHEAT_SHORTCUT_MENU_ITEM \ FILAMENT_WIDTH_SENSOR FILAMENT_LCD_DISPLAY CALIBRATION_GCODE BAUD_RATE_GCODE SOUND_MENU_ITEM \ FIX_MOUNTED_PROBE Z_SAFE_HOMING AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT M100_FREE_MEMORY_WATCHER \ ADVANCED_PAUSE_FEATURE ARC_SUPPORT BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES PARK_HEAD_ON_PAUSE \ PHOTO_GCODE PHOTO_POSITION PHOTO_SWITCH_POSITION PHOTO_SWITCH_MS PHOTO_DELAY_MS PHOTO_RETRACT_MM \ - HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT + HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_STATUS_NOTIFICATIONS exec_test $1 $2 "Teensy3.5 with many features" "$3" # @@ -67,7 +68,7 @@ exec_test $1 $2 "PARKING_EXTRUDER with LCD" "$3" restore_configs opt_set MOTHERBOARD BOARD_TEENSY35_36 MIXING_STEPPERS 2 opt_enable MIXING_EXTRUDER DIRECT_MIXING_IN_G1 GRADIENT_MIX GRADIENT_VTOOL REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER -opt_disable DISABLE_INACTIVE_EXTRUDER +opt_disable DISABLE_OTHER_EXTRUDERS exec_test $1 $2 "Mixing Extruder" "$3" # @@ -85,8 +86,9 @@ restore_configs opt_set MOTHERBOARD BOARD_TEENSY35_36 \ X_DRIVER_TYPE TMC5160 Y_DRIVER_TYPE TMC5160 \ X_MIN_ENDSTOP_INVERTING true Y_MIN_ENDSTOP_INVERTING true \ + X_CURRENT_HOME 750 Y_CURRENT_HOME 750 \ X_CS_PIN 46 Y_CS_PIN 47 -opt_enable COREXY USE_ZMIN_PLUG MONITOR_DRIVER_STATUS SENSORLESS_HOMING +opt_enable COREXY MONITOR_DRIVER_STATUS SENSORLESS_HOMING X_STALL_SENSITIVITY Y_STALL_SENSITIVITY exec_test $1 $2 "Teensy 3.5/3.6 COREXY" "$3" # diff --git a/buildroot/tests/teensy41 b/buildroot/tests/teensy41 index 56bd5043c736..bead97793b0e 100755 --- a/buildroot/tests/teensy41 +++ b/buildroot/tests/teensy41 @@ -28,7 +28,7 @@ opt_enable MAX31865_SENSOR_OHMS_0 MAX31865_CALIBRATION_OHMS_0 \ PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ ADVANCED_PAUSE_FEATURE ARC_SUPPORT BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES PARK_HEAD_ON_PAUSE \ PHOTO_GCODE PHOTO_POSITION PHOTO_SWITCH_POSITION PHOTO_SWITCH_MS PHOTO_DELAY_MS PHOTO_RETRACT_MM \ - HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT + HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_STATUS_NOTIFICATIONS opt_add EXTUI_EXAMPLE exec_test $1 $2 "Teensy4.1 with many features" "$3" @@ -71,7 +71,7 @@ exec_test $1 $2 "Ethernet, EEPROM, Magnetic Parking Extruder, No LCD" "$3" restore_configs opt_set MOTHERBOARD BOARD_TEENSY41 MIXING_STEPPERS 2 opt_enable MIXING_EXTRUDER DIRECT_MIXING_IN_G1 GRADIENT_MIX GRADIENT_VTOOL -opt_disable DISABLE_INACTIVE_EXTRUDER +opt_disable DISABLE_OTHER_EXTRUDERS exec_test $1 $2 "Mixing Extruder" "$3" # diff --git a/buildroot/web-ui/data/www/index.html b/buildroot/web-ui/data/www/index.html index 1a8db1cafb04..1628840634f3 100644 --- a/buildroot/web-ui/data/www/index.html +++ b/buildroot/web-ui/data/www/index.html @@ -384,7 +384,7 @@
-
GCode Lines
+
G-Code Lines
-
@@ -466,11 +466,11 @@
- GCode checksum value: + G-Code checksum value:  
- +
diff --git a/config/README.md b/config/README.md index d73a9c60b6de..c9c8408f4b76 100644 --- a/config/README.md +++ b/config/README.md @@ -1,3 +1,3 @@ # Where have all the configurations gone? -## https://github.com/MarlinFirmware/Configurations/archive/release-2.1.2.1.zip +## https://github.com/MarlinFirmware/Configurations/archive/release-2.1.2.2.zip diff --git a/docs/BinaryFileTransferProtocol.md b/docs/BinaryFileTransferProtocol.md new file mode 100644 index 000000000000..6d52671789f7 --- /dev/null +++ b/docs/BinaryFileTransferProtocol.md @@ -0,0 +1,234 @@ +# Marlin Binary File Transfer (BFT) +Marlin is capable of transferring binary data to the internal storage (SD card) via serial when built with `BINARY_FILE_TRANSFER` enabled. The following is a description of the binary protocol that must be used to conduct transfers once the printer is in binary mode after running `M28 B1`. + +## Data Endianness +All data structures are **little-endian**! This means that when constructing the packets with multi-byte values, the lower bits are packed first. For example, each packet should start with a 16-bit start token with the value of `0xB5AD`. The data itself should start with a value of `0xAD` followed by `0xB5` etc. + +An example Connection SYNC packet, which is only a header and has no payload: +``` + S S P P P H + t y r a a e + a n o c y a + r c t k l d + t o e o e + c t a r + o d + l t C + y l S + p e + e n +---- -- - - ---- ---- +ADB5 00 0 1 0000 0103 +``` + +## Packet Header + +``` + 0 1 2 3 + 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 ++-------------------------------+---------------+-------+-------+ +| Start Token (0xB5AD) | Sync Number | Prot- | Pack- | +| | | ocol | et | +| | | ID | Type | ++-------------------------------+---------------+-------+-------+ +| Payload Length | Header Checksum | ++-------------------------------+-------------------------------+ +``` + +| Field | Width | Description | +|-----------------|---------|---| +| Start Token | 16 bits | Each packet must start with the 16-bit value `0xB5AD`. | +| Sync Number | 8 bits | Synchronization value, each packet after sync should increment this value by 1. | +| Protocol ID | 4 bits | Protocol ID. `0` for Connection Control, `1` for Transfer. See Below. | +| Packet Type | 4 bits | Packet Type ID. Depends on the Protocol ID, see below. | +| Payload Length | 16 bits | Length of payload data. If this value is greater than 0, a packet payload will follow the header. | +| Header Checksum | 16 bits | 16-bit Fletchers checksum of the header data excluding the Start Token | + +## Packet Payload +If the Payload Length field of the header is non-zero, payload data is expected to follow. + +``` + 0 1 2 3 + 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 ++-------------------------------+-------------------------------+ +| Payload Data ... | ++-------------------------------+-------------------------------+ +| ... | Packet Checksum | ++-------------------------------+-------------------------------+ +``` + +| Field | Width | Description | +|-----------------|------------------------|---| +| Payload Data | Payload Length bytes | Payload data. This should be no longer than the buffer length reported by the Connection SYNC operation. | +| Packet Checksum | 16 bits | 16-bit Fletchers checksum of the header and payload, including the Header Checksum, but excluding the Start Token. | + +## Fletchers Checksum +Data packets require a checksum for the header and a checksum for the entire packet if the packet has a payload. In both cases the checksum does not include the first two bytes of the packet, the Start Token. + +A simple example implementation: +```c++ +uint16_t cs = 0; +for (size_t i = 2; i> 8) + cslow) % 255) << 8) | cslow; +} +``` + +## General Responses + +### ok +All packets **except** the SYNC Packet (see below) are acknowledged by an `ok` message. This acknowledgement only signifies the client has received the packet and that the header was well formed. An `ok` acknowledgement does not signify successful operation in cases where the client also sends detailed response messages (see details on packet types below). Most notably, with the current implementation the client will still respond `ok` when a client sends multiple packets with the same Sync Number, but will not send the proper response or any errors. + +**NOTE**: The `ok` acknowledgement is sent before any packet type specific output. The `SYNC` value should match the Sync Number of the last packet sent, and the next packet sent should use a Sync Number of this value + 1. + +Example: +``` +ok1 +``` + +### rs +In the case of a packet being sent out of order, where the Sync Number is not the previous Sync Number + 1, an `rs` message will be sent with the last Sync Number received. + +Example: +``` +rs1 +``` + +## Connection Control (`Protocol ID` 0) +`Protocol ID` 0 packets control the binary connection itself. There are only 2 types: + +| Packet Type | Name | Description | +|---|---|---| +| 1 | SYNC | Synchronize host and client and get connection info. | +| 2 | CLOSE | Close the binary connection and switch back to ASCII. | + +### SYNC Packet +A SYNC packet should be the first packet sent by a host after enabling binary mode. On success, a sync response will be sent. + +**Note**: This is the only packet that is not acknowledged with an `ok` response. + +Returns a sync response: +``` +ss,,.. +``` + +| Value | Description | +|---|---| +| SYNC | The current Sync Number, this should be used in the next packet sent and incremented by 1 for each packet sent after. | +| BUFFER_SIZE | The client buffer size. Packet Payload Length must not exceed this value. | +| VERSION_MAJOR | The major version number of the client Marlin BFT protocol, e.g., `0`. | +| VERSION_MINOR | The minor version number of the client Marlin BFT protocol, e.g., `1`. | +| VERSION_PATCH | The patch version number of the client Marlin BFT protocol, e.g., `0`. | + +Example response: +``` +ss0,96,0.1.0 +``` + +### CLOSE Packet +A CLOSE packet should be the last packet sent by a host. On success, the client will switch back to ASCII mode. + +## Transfer Control (`Protocol ID` 1) +`Protocol ID` 1 packets control the file transfers performed over the connection: + +| Packet Type | Name | Description | +|---|---|---| +| 0 | QUERY | Query the client protocol details and compression parameters. | +| 1 | OPEN | Open a file for writing and begin accepting data to transfer. | +| 2 | CLOSE | Finish writing and close the current file. | +| 3 | WRITE | Write data to an open file. | +| 4 | ABORT | Abort file transfer. | + +### QUERY Packet +A QUERY packet should be the second packet sent by a host, after a SYNC packet. On success a query response will be sent in addition to an `ok` acknowledgement. + +Returns a query response: +``` +PFT:version:..:compression:(,) +``` + +| Value | Description | +|---|---| +| VERSION_MAJOR | The major version number of the client Marlin BFT protocol, e.g., `0`. | +| VERSION_MINOR | The minor version number of the client Marlin BFT protocol, e.g., `1`. | +| VERSION_PATCH | The patch version number of the client Marlin BFT protocol, e.g., `0`. | +| COMPRESSION_ALGO | Compression algorithm. Currently either `heatshrink` or `none` | +| COMPRESSION_PARAMS | Compression parameters, separated by commas. Currently, if `COMPRESSION_AGLO` is heatshrink, this will be the window size and lookahead size. | + +Example response: +``` +PFT:version:0.1.0:compression:heatshrink,8,4 +``` + +### OPEN Packet +Opens a file for writing. The filename and other options are specified in the Packet Payload. The filename can be a long filename if the firmware is compiled with support, however the entire Packet Payload must not be longer than the buffer length returned by the SYNC Packet. The filename value must include a null terminator. + +Payload: +``` + 0 1 2 3 + 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 2 3 4 5 6 7 8 9 0 1 ++---------------+---------------+-------------------------------+ +| Dummy | Compression | Filename | ++---------------------------------------------------------------| +| ... | ++-------------------------------+-------------------------------+ +| ... | NULL (0x0) | Packet Checksum | ++-------------------------------+-------------------------------+ +``` + +| Field | Width | Description | +|-----------------|------------------------|---| +| Dummy | 8 bits | A boolean value indicating if this file transfer should be actually carried out or not. If `1`, the client will respond as if the file is opened and accept data transfer, but no data will be written. | +| Compression | 8 bits | A boolean value indicating if the data to be transferred will be compressed using the algorithm and parameters returned in the QUERY Packet. | +| Filename | ... | A filename including a null terminator byte. | +| Packet Checksum | 16 bits | 16-bit Fletchers checksum of the header and payload, including the Header Checksum, but excluding the Start Token. | + +Responses: + +| Response | Description | +|---|---| +| `PFT:success` | File opened and ready for write. | +| `PFT:fail` | The client couldn't open the file. | +| `PFT:busy` | The file is already open. | + +### CLOSE Packet +Closes the currently open file. + +Responses: + +| Response | Description | +|---|---| +| `PFT:success` | Buffer flushed and file closed. | +| `PFT:ioerror` | Client storage device failure. | +| `PFT:invalid` | No file open. | + +### WRITE Packet +Writes payload data to the currently open file. If the file was opened with Compression set to 1, the data will be decompressed first. Payload Length must not exceed the buffer size returned by the SYNC Packet. + +Responses: +On success, an `ok` response will be sent. On error, an `ok` response will be followed by an error response: + +| Response | Description | +|---|---| +| `PFT:ioerror` | Client storage device failure. | +| `PFT:invalid` | No file open. | + +### ABORT Packet +Closes the currently open file and remove it. + +Responses: + +| Response | Description | +|---|---| +| `PFT:success` | Transfer aborted, file removed. | + +## Typical Usage + +1. Send ASCII command `M28 B1` to initiate Binary Transfer mode. +2. Send Connection SYNC Packet, record Sync Number and Buffer Size. +3. Send Transfer QUERY Packet, using Sync Number from above. Record compression algorithm and parameters. +4. Send Transfer OPEN Packet, using last Sync Number + 1, filename and compression options. If error, send Connection CLOSE Packet and abort. +5. Send Transfer Write Packets, using last Sync Number + 1 with the file data. The Payload Length must not exceed the Buffer Size reported in step 2. On error, send a Transfer ABORT Packet, followed by a Connection CLOSE Packet and then abort transfer. +6. Send Transfer CLOSE Packet, using last Sync Number + 1. +7. Send Connection CLOSE Packet, using last Sync Number + 1. +8. Client is now in ASCII mode, transfer complete diff --git a/docs/Cutter.md b/docs/Cutter.md index c78b0551a0ac..623beb21f4d3 100644 --- a/docs/Cutter.md +++ b/docs/Cutter.md @@ -4,7 +4,7 @@ With Marlin version 2.0.9.x or higher, Laser improvements were introduced that e ### Architecture -Laser selectable feature capability is defined through 4 global mode flags within gcode ,laser/spindle, planner and stepper routines. The default mode maintains the standard laser function. G-Codes are received, processed and parsed to determine what mode to set through M3, M4 and M5 commands. When the inline mode parameter set is detected, laser power processing will be driven through the planner and stepper routines. Handling of the initial power values and settings are performed by G-Code parsing and the laser/spindle routines. +Laser selectable feature capability is defined through 4 global mode flags within G-code ,laser/spindle, planner and stepper routines. The default mode maintains the standard laser function. G-Codes are received, processed and parsed to determine what mode to set through M3, M4 and M5 commands. When the inline mode parameter set is detected, laser power processing will be driven through the planner and stepper routines. Handling of the initial power values and settings are performed by G-Code parsing and the laser/spindle routines. Inline power feeds from the block->inline_power variable into the planner's laser.power when in continuous power mode. Further power adjustment will be applied if the laser power trap feature is active otherwise laser.power is used as set in the stepper for the entire block. When laser power trap is active the power levels are step incremented during acceleration and step decremented during deceleration. @@ -20,52 +20,52 @@ The following flow charts depict the flow control logic for spindle and laser op #### Spindle Mode Logic: - ┌──────────┐ ┌───────────┐ ┌───────────┐ - │M3 S-Value│ │Dir !same ?│ │Stepper │ - │Spindle │ │stop & wait│ │processes │ - ┌──┤Clockwise ├──┤ & start ├──┤moves │ - ┌─────┐ │ │ │ │spindle │ │ │ - │GCode│ │ └──────────┘ └───────────┘ └───────────┘ - │Send ├──┤ ┌──────────┐ ┌───────────┐ ┌───────────┐ - └─────┘ │ │M4 S-Value│ │Dir !same ?│ │Stepper │ - ├──┤Spindle ├──┤stop & wait├──┤processes │ - │ │Counter │ │& start │ │moves │ - │ │Clockwise │ │spindle │ │ │ - │ └──────────┘ └───────────┘ └───────────┘ - │ ┌──────────┐ ┌────────┐ - │ │M5 │ │Wait for│ - │ │Spindle ├──┤move & │ - └──┤Stop │ │disable │ - └──────────┘ └────────┘ - ┌──────────┐ ┌──────────┐ - Sensors─────┤Fault ├──┤Disable │ - └──────────┘ │power │ - └──────────┘ + ┌──────────┐ ┌───────────┐ ┌───────────┐ + │M3 S-Value│ │Dir !same ?│ │Stepper │ + │Spindle │ │stop & wait│ │processes │ + ┌──┤Clockwise ├──┤ & start ├──┤moves │ + ┌──────┐ │ │ │ │spindle │ │ │ + │G-Code│ │ └──────────┘ └───────────┘ └───────────┘ + │Send ├──┤ ┌──────────┐ ┌───────────┐ ┌───────────┐ + └──────┘ │ │M4 S-Value│ │Dir !same ?│ │Stepper │ + ├──┤Spindle ├──┤stop & wait├──┤processes │ + │ │Counter │ │& start │ │moves │ + │ │Clockwise │ │spindle │ │ │ + │ └──────────┘ └───────────┘ └───────────┘ + │ ┌──────────┐ ┌────────┐ + │ │M5 │ │Wait for│ + │ │Spindle ├──┤move & │ + └──┤Stop │ │disable │ + └──────────┘ └────────┘ + ┌──────────┐ ┌──────────┐ + Sensors─────┤Fault ├──┤Disable │ + └──────────┘ │power │ + └──────────┘ #### Laser Mode Logic: - ┌──────────┐ ┌─────────────┐ ┌───────────┐ - │M3,M4,M5 I│ │Set power │ │Stepper │ - ┌──┤Standard ├──┤Immediately &├──┤processes │ - │ │Default │ │wait for move│ │moves │ - │ │ │ │completion │ │ │ - │ └──────────┘ └─────────────┘ └───────────┘ - │ ┌──────────┐ ┌───────────┐ ┌───────────┐ ┌────────────┐ ┌────────────┐ ┌────────────┐ ┌───────────┐ - ┌─────┐ │ │M3 I │ │G0,G1,G2,G4│ │Planner │ │Planner │ │Planner fan │ │Planner │ │Stepper │ - │GCode│ │ │Continuous│ │M3 receive │ │sets block │ │sync power ?│ │sync power ?│ │trap power ?│ │uses block │ - │Send ├──┼──┤Inline ├──┤power from ├──┤power using├──┤process M3 ├──┤process fan ├──┤adjusts for ├──┤values to │ - └─────┘ │ │ │ │S-Value │ │Gx S-Value │ │power inline│ │power inline│ │accel/decel │ │apply power│ - │ └──────────┘ └───────────┘ └───────────┘ └────────────┘ └────────────┘ └────────────┘ └───────────┘ - │ ┌──────────┐ ┌───────────┐ ┌────────────────┐ ┌───────────┐ - │ │M4 I │ │Gx F-Value │ │Planner │ │Stepper │ - │ │Dynamic │ │set power │ │Calc & set block│ │uses block │ - └──┤Inline ├──┤or use ├──┤block power ├──┤values to │ - │ │ │default │ │using F-Value │ │apply power│ - └──────────┘ └───────────┘ └────────────────┘ └───────────┘ - ┌──────────┐ ┌──────────┐ - Sensors─────┤Fault ├──┤Disable │ - └──────────┘ │Power │ - └──────────┘ + ┌──────────┐ ┌─────────────┐ ┌───────────┐ + │M3,M4,M5 I│ │Set power │ │Stepper │ + ┌──┤Standard ├──┤Immediately &├──┤processes │ + │ │Default │ │wait for move│ │moves │ + │ │ │ │completion │ │ │ + │ └──────────┘ └─────────────┘ └───────────┘ + │ ┌──────────┐ ┌───────────┐ ┌───────────┐ ┌────────────┐ ┌────────────┐ ┌────────────┐ ┌───────────┐ + ┌──────┐ │ │M3 I │ │G0,G1,G2,G4│ │Planner │ │Planner │ │Planner fan │ │Planner │ │Stepper │ + │G-Code│ │ │Continuous│ │M3 receive │ │sets block │ │sync power ?│ │sync power ?│ │trap power ?│ │uses block │ + │Send ├──┼──┤Inline ├──┤power from ├──┤power using├──┤process M3 ├──┤process fan ├──┤adjusts for ├──┤values to │ + └──────┘ │ │ │ │S-Value │ │Gx S-Value │ │power inline│ │power inline│ │accel/decel │ │apply power│ + │ └──────────┘ └───────────┘ └───────────┘ └────────────┘ └────────────┘ └────────────┘ └───────────┘ + │ ┌──────────┐ ┌───────────┐ ┌────────────────┐ ┌───────────┐ + │ │M4 I │ │Gx F-Value │ │Planner │ │Stepper │ + │ │Dynamic │ │set power │ │Calc & set block│ │uses block │ + └──┤Inline ├──┤or use ├──┤block power ├──┤values to │ + │ │ │default │ │using F-Value │ │apply power│ + └──────────┘ └───────────┘ └────────────────┘ └───────────┘ + ┌──────────┐ ┌──────────┐ + Sensors─────┤Fault ├──┤Disable │ + └──────────┘ │Power │ + └──────────┘ diff --git a/docs/Queue.md b/docs/Queue.md index bce68b0551a7..6d4fb9d041db 100644 --- a/docs/Queue.md +++ b/docs/Queue.md @@ -19,7 +19,7 @@ Here's a basic flowchart of Marlin command processing: | Host | | SerialState RingBuffer | | | | | Marlin | NUM_SERIAL BUF_SIZE | | Marlin | +--+---+ R/TX_BUFFER_SIZE | +---+ +------------------+ | | | - | +------------+ | | | | | | | GCode | + | +------------+ | | | | | | | G-Code | | | | | | | | MAX_CMD_SIZE +-+-----> processor | | | Platform | | | | On EOL | +--------------+ | r_pos | | +-------------> serial's +-----------> +--------> | G-code | | | +-----------+ diff --git a/docs/Serial.md b/docs/Serial.md index 88846e1bb45a..de436ffdef8e 100644 --- a/docs/Serial.md +++ b/docs/Serial.md @@ -69,6 +69,5 @@ The following macros are defined (in `serial.h`) to output data to the serial po | `SERIAL_ERROR_MSG` | Same as `SERIAL_ECHOLNPGM` | Print a full error line | `SERIAL_ERROR_MSG("Not found");` | `Error:Not found` | | `SERIAL_ECHO_SP` | Number of spaces | Print one or more spaces | `SERIAL_ECHO_SP(3)` | ` ` | | `SERIAL_EOL` | None | Print an end of line | `SERIAL_EOL();` | `\n` | -| `SERIAL_OUT` | `SERIAL_OUT(myMethod)` | Call a custom serial method | `SERIAL_OUT(msgDone);` | ... | *This document was written by [X-Ryl669](https://blog.cyril.by) and is under [CC-SA license](https://creativecommons.org/licenses/by-sa)* diff --git a/ini/avr.ini b/ini/avr.ini index 7c5f369dc6d7..f2f0658d842f 100644 --- a/ini/avr.ini +++ b/ini/avr.ini @@ -14,8 +14,8 @@ # [common_avr8] platform = atmelavr@~4.0.1 -build_flags = ${common.build_flags} -Wl,--relax -build_src_flags = -std=gnu++1z +build_flags = ${common.build_flags} -std=gnu++1z -Wl,--relax +build_unflags = -std=gnu++11 board_build.f_cpu = 16000000L build_src_filter = ${common.default_src_filter} + diff --git a/ini/esp32.ini b/ini/esp32.ini index f12ef99759cd..6e184979a4b8 100644 --- a/ini/esp32.ini +++ b/ini/esp32.ini @@ -13,15 +13,17 @@ # Espressif ESP32 # [env:esp32] -platform = espressif32@2.1.0 -board = esp32dev -build_flags = ${common.build_flags} -DCORE_DEBUG_LEVEL=0 -build_src_filter = ${common.default_src_filter} + -lib_ignore = NativeEthernet -upload_speed = 500000 -monitor_speed = 250000 -monitor_filters = colorize, time, send_on_enter, log2file, esp32_exception_decoder -#upload_port = marlinesp.local +platform = espressif32@2.1.0 +platform_packages = espressif/toolchain-xtensa-esp32s3 +board = esp32dev +build_flags = ${common.build_flags} -DCORE_DEBUG_LEVEL=0 -std=gnu++17 +build_unflags = -std=gnu11 -std=gnu++11 +build_src_filter = ${common.default_src_filter} + +lib_ignore = NativeEthernet +upload_speed = 500000 +monitor_speed = 250000 +monitor_filters = colorize, time, send_on_enter, log2file, esp32_exception_decoder +#upload_port = marlinesp.local #board_build.flash_mode = qio [env:FYSETC_E4] diff --git a/ini/features.ini b/ini/features.ini index d613fc512480..d62b0a832c99 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -9,23 +9,26 @@ # # ################################# +# The order of the features matters for source-filter resolution inside of common-dependencies.py. + [features] YHCB2004 = red-scorp/LiquidCrystal_AIP31068@^1.0.4, red-scorp/SoftSPIB@^1.1.1 -HAS_TFT_LVGL_UI = lvgl=https://github.com/makerbase-mks/LVGL-6.1.1-MKS/archive/master.zip +HAS_TFT_LVGL_UI = lvgl=https://github.com/makerbase-mks/LVGL-6.1.1-MKS/archive/a3ebe98bc6.zip build_src_filter=+ extra_scripts=download_mks_assets.py MARLIN_TEST_BUILD = build_src_filter=+ POSTMORTEM_DEBUGGING = build_src_filter=+ + build_flags=-funwind-tables -MKS_WIFI_MODULE = QRCode=https://github.com/makerbase-mks/QRCode/archive/master.zip +MKS_WIFI_MODULE = QRCode=https://github.com/makerbase-mks/QRCode/archive/261c5a696a.zip HAS_TRINAMIC_CONFIG = TMCStepper@~0.7.3 build_src_filter=+ + + + + HAS_T(RINAMIC_CONFIG|MC_SPI) = build_src_filter=+ HAS_STEALTHCHOP = build_src_filter=+ -SR_LCD_3W_NL = SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip +SR_LCD_3W_NL = SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/6f53c19a8a.zip +HAS_MOTOR_CURRENT_(I2C|DAC|SPI|PWM) = build_src_filter=+ HAS_MOTOR_CURRENT_I2C = SlowSoftI2CMaster build_src_filter=+ -HAS_TMC26X = TMC26XStepper=https://github.com/MarlinFirmware/TMC26XStepper/archive/master.zip +HAS_TMC26X = TMC26XStepper=https://github.com/MarlinFirmware/TMC26XStepper/archive/0.1.2.zip build_src_filter=+ LIB_INTERNAL_MAX31865 = build_src_filter=+ NEOPIXEL_LED = adafruit/Adafruit NeoPixel@~1.8.0 @@ -37,13 +40,16 @@ USES_LIQUIDCRYSTAL_I2C = marcoschwartz/LiquidCrystal_I2C@1.1.4 USES_LIQUIDTWI2 = LiquidTWI2@1.2.7 HAS_LCDPRINT = build_src_filter=+ HAS_MARLINUI_HD44780 = build_src_filter=+ -HAS_MARLINUI_U8GLIB = marlinfirmware/U8glib-HAL@~0.5.2 +HAS_MARLINUI_U8GLIB = marlinfirmware/U8glib-HAL@0.5.4 build_src_filter=+ -HAS_(FSMC|SPI|LTDC)_TFT = build_src_filter=+ + + +HAS_(FSMC|SPI|LTDC)_TFT = build_src_filter=+ +HAS_LTDC_TFT = build_src_filter=+ HAS_FSMC_TFT = build_src_filter=+ + -HAS_SPI_TFT = build_src_filter=+ + +HAS_SPI_TFT = build_src_filter=+ + + +HAS_TFT_XPT2046 = build_src_filter=+ + + +TFT_TOUCH_DEVICE_GT911 = build_src_filter=+ I2C_EEPROM = build_src_filter=+ -SOFT_I2C_EEPROM = SlowSoftI2CMaster, SlowSoftWire=https://github.com/felias-fogg/SlowSoftWire/archive/master.zip +SOFT_I2C_EEPROM = SlowSoftI2CMaster, SlowSoftWire=https://github.com/felias-fogg/SlowSoftWire/archive/f34d777f39.zip SPI_EEPROM = build_src_filter=+ HAS_DWIN_E3V2|IS_DWIN_MARLINUI = build_src_filter=+ DWIN_CREALITY_LCD = build_src_filter=+ @@ -53,21 +59,21 @@ IS_DWIN_MARLINUI = build_src_filter=+ IS_TFTGLCD_PANEL = build_src_filter=+ HAS_TOUCH_BUTTONS = build_src_filter=+ -HAS_MARLINUI_MENU = build_src_filter=+ +HAS_MARLINUI_MENU = build_src_filter=+ - HAS_GAMES = build_src_filter=+ MARLIN_BRICKOUT = build_src_filter=+ MARLIN_INVADERS = build_src_filter=+ MARLIN_MAZE = build_src_filter=+ MARLIN_SNAKE = build_src_filter=+ HAS_MENU_BACKLASH = build_src_filter=+ -HAS_MENU_BED_CORNERS = build_src_filter=+ LCD_BED_LEVELING = build_src_filter=+ +HAS_MENU_BED_TRAMMING = build_src_filter=+ HAS_MENU_CANCELOBJECT = build_src_filter=+ HAS_MENU_DELTA_CALIBRATE = build_src_filter=+ HAS_MENU_FILAMENT = build_src_filter=+ LCD_INFO_MENU = build_src_filter=+ HAS_MENU_JOB_RECOVERY = build_src_filter=+ -HAS_MULTI_LANGUAGE = build_src_filter=+ + +HAS_MENU_MULTI_LANGUAGE = build_src_filter=+ HAS_MENU_LED = build_src_filter=+ HAS_MENU_MEDIA = build_src_filter=+ HAS_MENU_MIXER = build_src_filter=+ @@ -78,8 +84,9 @@ HAS_MENU_CUTTER = build_src_filter=+ HAS_MENU_TMC = build_src_filter=+ HAS_MENU_TOUCH_SCREEN = build_src_filter=+ -HAS_MENU_TRAMMING = build_src_filter=+ +HAS_MENU_TRAMMING_WIZARD = build_src_filter=+ HAS_MENU_UBL = build_src_filter=+ +EXTENSIBLE_UI = build_src_filter=+ ANYCUBIC_LCD_CHIRON = build_src_filter=+ ANYCUBIC_LCD_I3MEGA = build_src_filter=+ HAS_DGUS_LCD_CLASSIC = build_src_filter=+ @@ -168,7 +175,6 @@ HAS_EXTRA_ENDSTOPS = build_src_filter=+ DIRECT_PIN_CONTROL = build_src_filter=+ + PINS_DEBUGGING = build_src_filter=+ -NO_VOLUMETRICS = build_src_filter=- HAS_MULTI_EXTRUDER = build_src_filter=+ HAS_HOTEND_OFFSET = build_src_filter=+ EDITABLE_SERVO_ANGLES = build_src_filter=+ @@ -176,6 +182,7 @@ PIDTEMP = build_src_filter=+ PIDTEMPBED = build_src_filter=+ HAS_USER_THERMISTORS = build_src_filter=+ +PIDTEMPCHAMBER = build_src_filter=+ SD_ABORT_ON_ENDSTOP_HIT = build_src_filter=+ BAUD_RATE_GCODE = build_src_filter=+ HAS_SMART_EFF_MOD = build_src_filter=+ @@ -184,10 +191,12 @@ AIR_EVACUATION = build_src_filter=+ SERVO_DETACH_GCODE = build_src_filter=+ HAS_DUPLICATION_MODE = build_src_filter=+ +SPI_FLASH_BACKUP = build_src_filter=+ +PLATFORM_M997_SUPPORT = build_src_filter=+ LIN_ADVANCE = build_src_filter=+ PHOTO_GCODE = build_src_filter=+ CONTROLLER_FAN_EDITABLE = build_src_filter=+ -HAS_SHAPING = build_src_filter=+ +HAS_ZV_SHAPING = build_src_filter=+ GCODE_MACROS = build_src_filter=+ GRADIENT_MIX = build_src_filter=+ HAS_SAVED_POSITIONS = build_src_filter=+ + @@ -209,6 +218,7 @@ HAS_LCD_CONTRAST = build_src_filter=+ HAS_LCD_BRIGHTNESS = build_src_filter=+ HAS_SOUND = build_src_filter=+ +HAS_MULTI_LANGUAGE = build_src_filter=+ TOUCH_SCREEN_CALIBRATION = build_src_filter=+ ARC_SUPPORT = build_src_filter=+ GCODE_MOTION_MODES = build_src_filter=+ @@ -216,13 +226,18 @@ BABYSTEPPING = build_src_filter=+ G38_PROBE_TARGET = build_src_filter=+ MAGNETIC_PARKING_EXTRUDER = build_src_filter=+ -SDSUPPORT = build_src_filter=+ + + + + + + +HAS_MEDIA = build_src_filter=+ + + + + + + HAS_MEDIA_SUBCALLS = build_src_filter=+ GCODE_REPEAT_MARKERS = build_src_filter=+ + -HAS_EXTRUDERS = build_src_filter=+ + + -HAS_TEMP_PROBE = build_src_filter=+ +HAS_EXTRUDERS = build_src_filter=+ + +HAS_HOTEND = build_src_filter=+ +HAS_FAN = build_src_filter=+ +HAS_HEATED_BED = build_src_filter=+ +HAS_HEATED_CHAMBER = build_src_filter=+ HAS_COOLER = build_src_filter=+ AUTO_REPORT_TEMPERATURES = build_src_filter=+ +HAS_TEMP_PROBE = build_src_filter=+ +HAS_PID_HEATING = build_src_filter=+ MPCTEMP = build_src_filter=+ INCH_MODE_SUPPORT = build_src_filter=+ TEMPERATURE_UNITS_SUPPORT = build_src_filter=+ @@ -240,7 +255,7 @@ HAS_SERVOS = build_src_filter=+ HAS_MICROSTEPS = build_src_filter=+ (ESP3D_)?WIFISUPPORT = AsyncTCP, ESP Async WebServer - ESP3DLib=https://github.com/luc-github/ESP3DLib/archive/master.zip + ESP3DLib=https://github.com/luc-github/ESP3DLib/archive/dc0f3d96c6.zip arduinoWebSockets=links2004/WebSockets@2.3.4 luc-github/ESP32SSDP@1.1.1 lib_ignore=ESPAsyncTCP diff --git a/ini/lpc176x.ini b/ini/lpc176x.ini index 0cb26628fe49..8d5d2fd157f5 100644 --- a/ini/lpc176x.ini +++ b/ini/lpc176x.ini @@ -15,17 +15,19 @@ [common_LPC] platform = https://github.com/p3p/pio-nxplpc-arduino-lpc176x/archive/0.1.3.zip platform_packages = framework-arduino-lpc176x@^0.2.8 + toolchain-gccarmnoneeabi@1.100301.220327 board = nxp_lpc1768 lib_ldf_mode = off lib_compat_mode = strict extra_scripts = ${common.extra_scripts} Marlin/src/HAL/LPC1768/upload_extra_script.py -build_src_filter = ${common.default_src_filter} + + +build_src_filter = ${common.default_src_filter} + - + lib_deps = ${common.lib_deps} Servo -custom_marlin.USES_LIQUIDCRYSTAL = arduino-libraries/LiquidCrystal@~1.0.7 +custom_marlin.USES_LIQUIDCRYSTAL = arduino-libraries/LiquidCrystal@~1.0.7 custom_marlin.NEOPIXEL_LED = Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/1.5.0.zip -build_flags = ${common.build_flags} -DU8G_HAL_LINKS -IMarlin/src/HAL/LPC1768/include -IMarlin/src/HAL/LPC1768/u8g +build_flags = ${common.build_flags} -DU8G_HAL_LINKS -DPLATFORM_M997_SUPPORT + -IMarlin/src/HAL/LPC1768/include -IMarlin/src/HAL/LPC1768/u8g # debug options for backtrace #-funwind-tables #-mpoke-function-name diff --git a/ini/native.ini b/ini/native.ini index 481dac1777bd..8d5a63dea2fe 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -36,16 +36,17 @@ build_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/u8g build_src_flags = -Wall -Wno-expansion-to-defined -Wno-deprecated-declarations -Wcast-align release_flags = -g0 -O3 -flto debug_build_flags = -fstack-protector-strong -g -g3 -ggdb lib_compat_mode = off build_src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} - MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/refs/heads/bugfix-2.1.x.zip - Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip - LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip + MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/8791f3ff43.zip + Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/c6b319f447.zip + LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/322fb5fc23.zip extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/simulator.py @@ -71,8 +72,9 @@ build_flags = ${simulator_linux.build_flags} ${simulator_linux.release_flags} # sudo port install gcc12 glm libsdl2 libsdl2_net # # cd /opt/local/bin -# sudo rm -f gcc g++ cc +# sudo rm gcc g++ cc ld # sudo ln -s gcc-mp-12 gcc ; sudo ln -s g++-mp-12 g++ ; sudo ln -s g++ cc +# sudo ln -s ld-classic ld # cd - # rehash # @@ -134,5 +136,7 @@ custom_gcc = g++ [env:simulator_windows] extends = simulator_common build_src_flags = ${simulator_common.build_src_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 +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 build_type = debug diff --git a/ini/renamed.ini b/ini/renamed.ini index ae1b5742b5e0..84f6acd7fab9 100644 --- a/ini/renamed.ini +++ b/ini/renamed.ini @@ -21,6 +21,12 @@ board = genericSTM32F103RE # List of environment names that are no longer used # +[env:megaatmega1280] ;=> mega1280 +extends = renamed + +[env:megaatmega2560] ;=> mega2560 +extends = renamed + [env:STM32F103RET6_creality_maple] ;=> STM32F103RE_creality_maple extends = renamed @@ -57,17 +63,35 @@ extends = renamed [env:BIGTREE_OCTOPUS_V1] ;=> STM32F446ZE_btt extends = renamed -[env:BIGTREE_OCTOPUS_V1_USB] ;=> STM32F446ZE_btt_USB +[env:BIGTREE_OCTOPUS_V1_USB] ;=> STM32F446ZE_btt_usb_flash_drive extends = renamed [env:BIGTREE_OCTOPUS_PRO_V1_F429] ;=> STM32F429ZG_btt extends = renamed -[env:BIGTREE_OCTOPUS_PRO_V1_F429_USB] ;=> STM32F429ZG_btt_USB +[env:BIGTREE_OCTOPUS_PRO_V1_F429_USB] ;=> STM32F429ZG_btt_usb_flash_drive extends = renamed [env:BIGTREE_OCTOPUS_V1_F407] ;=> STM32F407ZE_btt extends = renamed -[env:BIGTREE_OCTOPUS_V1_F407_USB] ;=> STM32F407ZE_btt_USB +[env:BIGTREE_OCTOPUS_V1_F407_USB] ;=> STM32F407ZE_btt_usb_flash_drive +extends = renamed + +[env:STM32H723Vx_btt] ;=> STM32H723VG_btt +extends = renamed + +[env:STM32H723Zx_btt] ;=> STM32H723ZE_btt +extends = renamed + +[env:STM32H743Vx_btt] ;=> STM32H743VI_btt +extends = renamed + +[env:STM32F446ZE_btt_USB] ;=> STM32F446ZE_btt_usb_flash_drive +extends = renamed + +[env:STM32F429ZG_btt_USB] ;=> STM32F429ZG_btt_usb_flash_drive +extends = renamed + +[env:STM32F407ZE_btt_USB] ;=> STM32F407ZE_btt_usb_flash_drive extends = renamed diff --git a/ini/samd21.ini b/ini/samd21.ini index 969ce3b9571e..f2acf829ff83 100644 --- a/ini/samd21.ini +++ b/ini/samd21.ini @@ -16,7 +16,7 @@ platform = atmelsam board = minitronics20 build_flags = ${common.build_flags} -std=gnu++17 - -DUSBCON -DUSBD_USE_CDC -D__SAMD21__ -DARDUINO_SAMD_MINITRONICS20 -Wno-deprecated-declarations -DU8G_HAL_LINKS -DDEBUG + -DUSBCON -DUSBD_USE_CDC -D__SAMD21__ -DARDUINO_SAMD_MINITRONICS20 -Wno-deprecated-declarations -DDEBUG -IMarlin/src/HAL/SAMD21/u8g build_unflags = -std=gnu++11 build_src_filter = ${common.default_src_filter} + diff --git a/ini/samd51.ini b/ini/samd51.ini index d7d9b3a4211c..70bda9ca52d0 100644 --- a/ini/samd51.ini +++ b/ini/samd51.ini @@ -22,5 +22,5 @@ lib_deps = ${common.lib_deps} SoftwareSerialM extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py -custom_marlin.SDSUPPORT = SdFat - Adafruit Fork, Adafruit SPIFlash +custom_marlin.HAS_MEDIA = SdFat - Adafruit Fork, Adafruit SPIFlash debug_tool = jlink diff --git a/ini/stm32-common.ini b/ini/stm32-common.ini index c8f28cd0e314..e4afaf07022a 100644 --- a/ini/stm32-common.ini +++ b/ini/stm32-common.ini @@ -12,13 +12,11 @@ [common_stm32] platform = ststm32@~12.1 board_build.core = stm32 -build_flags = ${common.build_flags} - -std=gnu++14 -DHAL_STM32 - -DUSBCON -DUSBD_USE_CDC - -DTIM_IRQ_PRIO=13 - -DADC_RESOLUTION=12 +build_flags = ${common.build_flags} -std=gnu++14 + -DHAL_STM32 -DPLATFORM_M997_SUPPORT + -DUSBCON -DUSBD_USE_CDC -DTIM_IRQ_PRIO=13 -DADC_RESOLUTION=12 build_unflags = -std=gnu++11 -build_src_filter = ${common.default_src_filter} + + +build_src_filter = ${common.default_src_filter} + - + extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py @@ -35,7 +33,8 @@ extra_scripts = ${common_stm32.extra_scripts} # USB Flash Drive mix-ins for STM32 # [stm_flash_drive] -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip +# Arduino_Core_STM32 uses usb-host-msc-cdc-msc-3 branch +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/39f37d6d6a.zip build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED -DHAL_HCD_MODULE_ENABLED -DUSBHOST -DUSBH_IRQ_PRIO=3 -DUSBH_IRQ_SUBPRIO=4 diff --git a/ini/stm32f0.ini b/ini/stm32f0.ini index d62ac3acf54f..d23ee2a6038e 100644 --- a/ini/stm32f0.ini +++ b/ini/stm32f0.ini @@ -48,4 +48,4 @@ board = malyanm300_f070cb build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED -build_src_filter = ${common.default_src_filter} + +build_src_filter = ${common.default_src_filter} + - diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index d361a0d40a98..d023a57db13b 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -26,9 +26,9 @@ platform = ststm32@~12.1 board_build.core = maple build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} -DARDUINO_ARCH_STM32 -DMAPLE_STM32F1 + ${common.build_flags} -DARDUINO_ARCH_STM32 -DMAPLE_STM32F1 -DPLATFORM_M997_SUPPORT build_unflags = -std=gnu11 -std=gnu++11 -build_src_filter = ${common.default_src_filter} + +build_src_filter = ${common.default_src_filter} + - lib_ignore = SPI, FreeRTOS701, FreeRTOS821 lib_deps = ${common.lib_deps} SoftwareSerialM @@ -95,7 +95,7 @@ upload_protocol = serial # BigTreeTech SKR Mini V1.1 / SKR Mini E3 & MZ (STM32F103RCT6 ARM Cortex-M3) # # STM32F103RC_btt_maple ............. RCT6 with 256K -# STM32F103RC_btt_USB_maple ......... RCT6 with 256K (USB mass storage) +# STM32F103RC_btt_USB_maple ......... RCT6 with 256K with USB Media Share Support # [env:STM32F103RC_btt_maple] extends = env:STM32F103RC_maple @@ -111,28 +111,26 @@ lib_deps = ${env:STM32F103RC_btt_maple.lib_deps} USBComposite for STM32F1@0.91 # -# Creality (STM32F103RET6) +# Creality 512K (STM32F103RET6) # [env:STM32F103RE_creality_maple] extends = env:STM32F103RE_maple build_flags = ${env:STM32F103RE_maple.build_flags} -DTEMP_TIMER_CHAN=4 board_build.address = 0x08007000 board_build.ldscript = creality.ld -extra_scripts = ${env:STM32F103RE_maple.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/random-bin.py +board_build.rename = firmware-{date}-{time}.bin debug_tool = jlink upload_protocol = jlink # -# Creality (STM32F103RCT6) +# Creality 256K (STM32F103RCT6) # [env:STM32F103RC_creality_maple] extends = env:STM32F103RC_maple build_flags = ${env:STM32F103RC_maple.build_flags} -DTEMP_TIMER_CHAN=4 board_build.address = 0x08007000 -board_build.ldscript = creality.ld -extra_scripts = ${env:STM32F103RC_maple.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/random-bin.py +board_build.ldscript = creality256k.ld +board_build.rename = firmware-{date}-{time}.bin debug_tool = jlink upload_protocol = jlink @@ -148,7 +146,7 @@ board_build.ldscript = crealityPro.ld # BigTreeTech SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) # # STM32F103RE_btt_maple ............. RET6 -# STM32F103RE_btt_USB_maple ......... RET6 (USB mass storage) +# STM32F103RE_btt_USB_maple ......... RET6 with USB Media Share Support # [env:STM32F103RE_btt_maple] extends = env:STM32F103RE_maple @@ -305,7 +303,7 @@ extends = STM32F1_maple board = marlin_malyanM200 build_flags = ${STM32F1_maple.build_flags} -DMCU_STM32F103CB -D__STM32F1__=1 -std=c++1y -DSERIAL_USB -ffunction-sections -fdata-sections - -Wl,--gc-sections -DDEBUG_LEVEL=0 -D__MARLIN_FIRMWARE__ + -Wl,--gc-sections -DDEBUG_LEVEL=0 lib_ignore = ${STM32F1_maple.lib_ignore} SoftwareSerialM @@ -400,8 +398,6 @@ extends = env:STM32F103RE_maple build_flags = ${STM32F1_maple.build_flags} -DTEMP_TIMER_CHAN=4 board_build.address = 0x08007000 board_build.ldscript = sovol.ld -extra_scripts = ${STM32F1_maple.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/random-bin.py - buildroot/share/PlatformIO/scripts/custom_board.py +board_build.rename = firmware-{date}-{time}.bin debug_tool = jlink upload_protocol = jlink diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 230f1ae774cb..2eab5d6f46e2 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -54,7 +54,7 @@ monitor_speed = 115200 # BigTreeTech SKR Mini V1.1 / SKR Mini E3 & MZ (STM32F103RCT6 ARM Cortex-M3) # # STM32F103RC_btt ............. RCT6 with 256K -# STM32F103RC_btt_USB ......... RCT6 with 256K (USB mass storage) +# STM32F103RC_btt_USB ......... RCT6 with 256K with USB Media Share Support # [env:STM32F103RC_btt] extends = common_STM32F103RC_variant @@ -121,6 +121,7 @@ debug_tool = stlink extends = stm32_variant board_build.variant = MARLIN_F103Rx board_build.offset = 0x7000 +board_build.rename = firmware-{date}-{time}.bin board_upload.offset_address = 0x08007000 build_flags = ${stm32_variant.build_flags} -DMCU_STM32F103RE -DHAL_SD_MODULE_ENABLED @@ -128,8 +129,6 @@ build_flags = ${stm32_variant.build_flags} -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${stm32_variant.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/random-bin.py monitor_speed = 115200 debug_tool = jlink upload_protocol = jlink @@ -207,7 +206,7 @@ build_flags = ${stm32_variant.build_flags} # BigTreeTech SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) # # STM32F103RE_btt ............. RET6 -# STM32F103RE_btt_USB ......... RET6 (USB mass storage) +# STM32F103RE_btt_USB ......... RET6 with USB Media Share Support # [env:STM32F103RE_btt] extends = stm32_variant @@ -253,7 +252,7 @@ board = malyanm200_f103cb build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED -build_src_filter = ${common.default_src_filter} + +build_src_filter = ${common.default_src_filter} + - # # FLYmaker FLY Mini (STM32F103RCT6) @@ -303,7 +302,8 @@ build_unflags = ${mks_robin_nano_v1v2_common.build_unflags} -DUSBC [env:mks_robin_mini] extends = STM32F103VE_robin board_build.encrypt_mks = Robin_mini.bin -build_unflags = ${STM32F103VE_robin.build_unflags} -DSS_TIMER=4 +build_unflags = ${STM32F103VE_robin.build_unflags} -DSS_TIMER=4 -DTIMER_SERVO=TIM2 +build_flags = ${STM32F103VE_robin.build_flags} -DTIMER_SERVO=TIM1 # # MKS Robin E3p (STM32F103VET6) diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index e9d74a70a461..03c8cfe8a737 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -47,6 +47,7 @@ board = marlin_STM32F407ZGT6 board_build.variant = MARLIN_FLY_F407ZG board_build.offset = 0x8000 upload_protocol = dfu + # # FYSETC S6 (STM32F446RET6 ARM Cortex-M4) # @@ -282,7 +283,7 @@ 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:STM32F446ZE_btt_USB] +[env:STM32F446ZE_btt_usb_flash_drive] extends = env:STM32F446ZE_btt platform_packages = ${stm_flash_drive.platform_packages} build_unflags = -DUSBD_USE_CDC @@ -308,7 +309,7 @@ build_flags = ${stm32_variant.build_flags} # # BigTreeTech Octopus V1.1 / Octopus Pro V1.0 (STM32F429ZGT6 ARM Cortex-M4) with USB Flash Drive Support # -[env:STM32F429ZG_btt_USB] +[env:STM32F429ZG_btt_usb_flash_drive] extends = env:STM32F429ZG_btt platform_packages = ${stm_flash_drive.platform_packages} build_unflags = -DUSBD_USE_CDC @@ -330,7 +331,7 @@ build_flags = ${stm32_variant.build_flags} # # BigTreeTech Octopus / Octopus Pro (STM32F407ZET6 ARM Cortex-M4) with USB Flash Drive Support # -[env:STM32F407ZE_btt_USB] +[env:STM32F407ZE_btt_usb_flash_drive] extends = env:STM32F407ZE_btt platform_packages = ${stm_flash_drive.platform_packages} build_unflags = -DUSBD_USE_CDC @@ -468,7 +469,6 @@ upload_protocol = jlink # # MKS Robin Nano V3 with USB Flash Drive Support -# Currently, using a STM32duino fork, until USB Host get merged # [env:mks_robin_nano_v3_usb_flash_drive] extends = env:mks_robin_nano_v3 @@ -481,7 +481,6 @@ build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} # # MKS Robin Nano V3 with USB Flash Drive Support and Shared Media -# Currently, using a STM32duino fork, until USB Host and USB Device MSC get merged # [env:mks_robin_nano_v3_usb_flash_drive_msc] extends = env:mks_robin_nano_v3_usb_flash_drive @@ -498,7 +497,6 @@ board = marlin_STM32F407VET6_CCM # # MKS Robin Nano V3.1 with USB Flash Drive Support -# Currently, using a STM32duino fork, until USB Host get merged # [env:mks_robin_nano_v3_1_usb_flash_drive] extends = env:mks_robin_nano_v3_usb_flash_drive @@ -506,7 +504,6 @@ board = marlin_STM32F407VET6_CCM # # MKS Robin Nano V3.1 with USB Flash Drive Support and Shared Media -# Currently, using a STM32duino fork, until USB Host and USB Device MSC get merged # [env:mks_robin_nano_v3_1_usb_flash_drive_msc] extends = env:mks_robin_nano_v3_usb_flash_drive_msc @@ -531,7 +528,6 @@ upload_protocol = jlink # # MKS Eagle with USB Flash Drive Support -# Currently, using a STM32duino fork, until USB Host get merged # [env:mks_eagle_usb_flash_drive] extends = env:mks_eagle @@ -544,7 +540,6 @@ build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} # # MKS Eagle with USB Flash Drive Support and Shared Media -# Currently, using a STM32duino fork, until USB Host and USB Device MSC get merged # [env:mks_eagle_usb_flash_drive_msc] extends = env:mks_eagle_usb_flash_drive @@ -576,7 +571,6 @@ upload_protocol = jlink # # MKS Monster8 V1 / V2 (STM32F407VET6 ARM Cortex-M4) with USB Flash Drive Support -# Currently, using a STM32duino fork, until USB Host get merged # [env:mks_monster8_usb_flash_drive] extends = env:mks_monster8 @@ -589,7 +583,6 @@ build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1_CAN.build_flag # # MKS Monster8 V1 / V2 (STM32F407VET6 ARM Cortex-M4) with USB Flash Drive Support and Shared Media -# Currently, using a STM32duino fork, until USB Host and USB Device MSC get merged # [env:mks_monster8_usb_flash_drive_msc] extends = env:mks_monster8_usb_flash_drive @@ -677,37 +670,70 @@ extra_scripts = ${common_stm32.extra_scripts} # # Ender-3 S1 STM32F401RC_creality # -[env:STM32F401RC_creality] +[STM32F401RC_creality_base] extends = stm32_variant board = genericSTM32F401RC board_build.variant = MARLIN_CREALITY_STM32F401RC -board_build.offset = 0x10000 -board_upload.offset_address = 0x08010000 build_flags = ${stm32_variant.build_flags} -DMCU_STM32F401RC -DSTM32F4 -DSS_TIMER=4 -DTIMER_SERVO=TIM5 -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${stm32_variant.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/random-bin.py monitor_speed = 115200 -[env:STM32F401RC_creality_jlink] -extends = env:STM32F401RC_creality -debug_tool = jlink -upload_protocol = jlink +[env:STM32F401RC_creality] +extends = STM32F401RC_creality_base +board_build.offset = 0x10000 +board_upload.offset_address = 0x08010000 +board_build.rename = firmware-{date}-{time}.bin -[env:STM32F401RC_creality_stlink] -extends = env:STM32F401RC_creality +[env:STM32F401RC_creality_nobootloader] +extends = STM32F401RC_creality_base +board_build.offset = 0x0000 +board_upload.offset_address = 0x08000000 debug_tool = stlink upload_protocol = stlink +[env:STM32F401RC_creality_jlink] +extends = env:STM32F401RC_creality +debug_tool = jlink +upload_protocol = jlink + +[env:STM32F401RC_creality_stlink] +extends = env:STM32F401RC_creality +debug_tool = stlink +upload_protocol = stlink + +# +# Ender-5 S1 STM32F401RE_creality (CR4NS200141C13 with STM32F401RET6) +# +[env:STM32F401RE_creality] +extends = stm32_variant +board = marlin_CREALITY_STM32F401RE +board_build.offset = 0x10000 +board_upload.offset_address = 0x08010000 +board_build.rename = firmware-{date}-{time}.bin +build_flags = ${stm32_variant.build_flags} -DSTM32F401xE -DSTM32F4 -DSTM32F4_UPDATE_FOLDER +build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC +monitor_speed = 115200 + +[env:STM32F401RE_creality_jlink] +extends = env:STM32F401RE_creality +debug_tool = jlink +upload_protocol = jlink + +[env:STM32F401RE_creality_stlink] +extends = env:STM32F401RE_creality +debug_tool = stlink +upload_protocol = stlink + # # BigTree SKR mini E3 V3.0.1 (STM32F401RCT6 ARM Cortex-M4) # [env:STM32F401RC_btt] extends = stm32_variant platform = ststm32@~14.1.0 -platform_packages = framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32/archive/main.zip +platform_packages = framework-arduinoststm32@~4.20600.231001 + toolchain-gccarmnoneeabi@1.100301.220327 board = marlin_STM32F401RC board_build.offset = 0x4000 board_upload.offset_address = 0x08004000 @@ -719,6 +745,20 @@ build_flags = ${stm32_variant.build_flags} upload_protocol = stlink debug_tool = stlink +# +# BigTreeTech SKR Mini E3 V3.0.1 (STM32F401RCT6 ARM Cortex-M0+) +# Custom upload to SD via Marlin with Binary Protocol +# Requires Marlin with BINARY_FILE_TRANSFER already installed on the target board. +# If CUSTOM_FIRMWARE_UPLOAD is also installed, Marlin will reboot the board to install the firmware. +# Currently CUSTOM_FIRMWARE_UPLOAD must also be enabled to use 'xfer' build envs. +# +[env:STM32F401RC_btt_xfer] +extends = env:STM32F401RC_btt +build_flags = ${env:STM32F401RC_btt.build_flags} -DXFER_BUILD +extra_scripts = ${env:STM32F401RC_btt.extra_scripts} + pre:buildroot/share/scripts/upload.py +upload_protocol = custom + # # MKS SKIPR v1.0 all-in-one board (STM32F407VE) # diff --git a/ini/stm32g0.ini b/ini/stm32g0.ini index 2ffee0979051..8da5ab230fe1 100644 --- a/ini/stm32g0.ini +++ b/ini/stm32g0.ini @@ -31,35 +31,41 @@ build_flags = -DPIN_WIRE_SCL=PB3 -DPIN_WIRE_SDA=PB4 # [env:BTT_EBB42_V1_1_filament_extruder] extends = stm32_variant -platform = ststm32@~14.1.0 -platform_packages = framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32/archive/main.zip +platform = ststm32@17.1.0 +platform_packages = framework-arduinoststm32@~4.20600.231001 + toolchain-gccarmnoneeabi@1.120301.0 board = marlin_BTT_EBB42_V1_1 board_build.offset = 0x0000 board_upload.offset_address = 0x08000000 build_flags = ${stm32_variant.build_flags} ${stm32g0_I2C2.build_flags} -upload_protocol = stlink + -flto + -Wl,--no-warn-rwx-segment debug_tool = stlink +upload_protocol = dfu +upload_command = dfu-util -a 0 -s 0x08000000:leave -D "$SOURCE" # -# BigTreeTech SKR Mini E3 V3.0 (STM32G0B1RET6 ARM Cortex-M0+) +# BigTreeTech SKR Mini E3 V3.0 (STM32G0B0RET6 / STM32G0B1RET6 ARM Cortex-M0+) # [env:STM32G0B1RE_btt] extends = stm32_variant -platform = ststm32@~14.1.0 -platform_packages = framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32/archive/main.zip +platform = ststm32@17.1.0 +platform_packages = framework-arduinoststm32@~4.20600.231001 + toolchain-gccarmnoneeabi@1.120301.0 board = marlin_STM32G0B1RE board_build.offset = 0x2000 board_upload.offset_address = 0x08002000 build_flags = ${stm32_variant.build_flags} - -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 + -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 + -Wl,--no-warn-rwx-segment upload_protocol = stlink debug_tool = stlink # -# BigTreeTech SKR Mini E3 V3.0 (STM32G0B1RET6 ARM Cortex-M0+) +# BigTreeTech SKR Mini E3 V3.0 (STM32G0B0RET6 / STM32G0B1RET6 ARM Cortex-M0+) # Custom upload to SD via Marlin with Binary Protocol # Requires Marlin with BINARY_FILE_TRANSFER already installed on the target board. # If CUSTOM_FIRMWARE_UPLOAD is also installed, Marlin will reboot the board to install the firmware. @@ -73,7 +79,8 @@ extra_scripts = ${env:STM32G0B1RE_btt.extra_scripts} upload_protocol = custom # -# BigTreeTech Manta E3 EZ V1.0 / Manta M4P V1.0 / Manta M5P V1.0 (STM32G0B1RET6 ARM Cortex-M0+) +# BigTreeTech Manta M4P V2.1 (STM32G0B0RET6 ARM Cortex-M0+) +# BigTreeTech Manta E3 EZ V1.0 / Manta M5P V1.0 (STM32G0B1RET6 ARM Cortex-M0+) # [env:STM32G0B1RE_manta_btt] extends = env:STM32G0B1RE_btt @@ -81,7 +88,8 @@ build_flags = ${env:STM32G0B1RE_btt.build_flags} -DPIN_SERIAL3_RX=PD_9 -DPIN_SERIAL3_TX=PD_8 -DENABLE_HWSERIAL3 # -# BigTreeTech Manta E3 EZ V1.0 / Manta M4P V1.0 / Manta M5P V1.0 (STM32G0B1RET6 ARM Cortex-M0+) +# BigTreeTech Manta M4P V2.1 (STM32G0B0RET6 ARM Cortex-M0+) +# BigTreeTech Manta E3 EZ V1.0 / Manta M5P V1.0 (STM32G0B1RET6 ARM Cortex-M0+) # Custom upload to SD via Marlin with Binary Protocol # Requires Marlin with BINARY_FILE_TRANSFER already installed on the target board. # If CUSTOM_FIRMWARE_UPLOAD is also installed, Marlin will reboot the board to install the firmware. @@ -99,17 +107,19 @@ upload_protocol = custom # [env:STM32G0B1VE_btt] extends = stm32_variant -platform = ststm32@~14.1.0 -platform_packages = framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32/archive/main.zip +platform = ststm32@17.1.0 +platform_packages = framework-arduinoststm32@~4.20600.231001 + toolchain-gccarmnoneeabi@1.120301.0 board = marlin_STM32G0B1VE board_build.offset = 0x2000 board_upload.offset_address = 0x08002000 build_flags = ${stm32_variant.build_flags} - -DPIN_SERIAL4_RX=PE_9 -DPIN_SERIAL4_TX=PE_8 - -DPIN_SERIAL5_RX=PE_11 -DPIN_SERIAL5_TX=PE_10 - -DSERIAL_RX_BUFFER_SIZE=1024 -DSERIAL_TX_BUFFER_SIZE=1024 - -DTIMER_SERVO=TIM3 -DTIMER_TONE=TIM4 - -DSTEP_TIMER_IRQ_PRIO=0 + -DPIN_SERIAL4_RX=PE_9 -DPIN_SERIAL4_TX=PE_8 + -DPIN_SERIAL5_RX=PE_11 -DPIN_SERIAL5_TX=PE_10 + -DSERIAL_RX_BUFFER_SIZE=1024 -DSERIAL_TX_BUFFER_SIZE=1024 + -DTIMER_SERVO=TIM3 -DTIMER_TONE=TIM4 + -DSTEP_TIMER_IRQ_PRIO=0 + -Wl,--no-warn-rwx-segment upload_protocol = stlink debug_tool = stlink diff --git a/ini/stm32h7.ini b/ini/stm32h7.ini index 5733d35bf0fd..cdc2a29c8002 100644 --- a/ini/stm32h7.ini +++ b/ini/stm32h7.ini @@ -12,8 +12,8 @@ # H : High Performance # 7 : Cortex M7 core (0:M0, 1-2:M3, 3-4:M4, 7:M7) # 43 : Line/Features -# I : 176 pins -# I : 2048KB Flash-memory +# I : 176 pins (T:36, C:48 or 49, M:81, V:100, Z:144, I:176) +# I : 2048KB Flash-memory (C:256KB, D:384KB, E:512KB, G:1024KB, I:2048KB) # T : LQFP package # 6 : -40...85°C (7: ...105°C) # @@ -24,7 +24,8 @@ # [env:BTT_SKR_SE_BX] extends = stm32_variant -platform_packages = framework-arduinoststm32@https://github.com/thisiskeithb/Arduino_Core_STM32/archive/biqu-bx-workaround.zip +# framework-arduinoststm32 uses biqu-bx-workaround branch +platform_packages = framework-arduinoststm32@https://github.com/thisiskeithb/Arduino_Core_STM32/archive/8b3522051a.zip board = marlin_BTT_SKR_SE_BX board_build.offset = 0x20000 build_flags = ${stm32_variant.build_flags} ${stm_flash_drive.build_flags} @@ -40,19 +41,18 @@ upload_protocol = cmsis-dap debug_tool = cmsis-dap # -# BigTreeTech SKR V3.0 / V3.0 EZ (STM32H743VIT6 ARM Cortex-M7) +# BigTreeTech STM32H743Vx ARM Cortex-M7 Common # -[env:STM32H743Vx_btt] +[STM32H743Vx_btt] extends = stm32_variant platform = ststm32@15.4.1 platform_packages = framework-arduinoststm32@~4.20200.220530 -board = marlin_STM32H743Vx board_build.offset = 0x20000 board_upload.offset_address = 0x08020000 build_flags = ${stm32_variant.build_flags} - -DPIN_SERIAL1_RX=PA_10 -DPIN_SERIAL1_TX=PA_9 - -DPIN_SERIAL3_RX=PD_9 -DPIN_SERIAL3_TX=PD_8 - -DPIN_SERIAL4_RX=PA_1 -DPIN_SERIAL4_TX=PA_0 + -DPIN_SERIAL1_TX=PA_9 -DPIN_SERIAL1_RX=PA_10 + -DPIN_SERIAL3_TX=PD_8 -DPIN_SERIAL3_RX=PD_9 + -DPIN_SERIAL4_TX=PA_0 -DPIN_SERIAL4_RX=PA_1 -DSERIAL_RX_BUFFER_SIZE=1024 -DSERIAL_TX_BUFFER_SIZE=1024 -DTIMER_SERVO=TIM5 -DTIMER_TONE=TIM2 -DSTEP_TIMER_IRQ_PRIO=0 @@ -61,22 +61,27 @@ upload_protocol = cmsis-dap debug_tool = cmsis-dap # -# BigTreeTech SKR V3.0 / SKR V3.0 EZ (STM32H723VGT6 ARM Cortex-M7) -# BigTreeTech Octopus Max EZ V1.0 (STM32H723VET6 ARM Cortex-M7) +# BigTreeTech SKR V3.0 / V3.0 EZ (STM32H743VIT6 ARM Cortex-M7) # -[env:STM32H723Vx_btt] +[env:STM32H743VI_btt] +extends = STM32H743Vx_btt +board = marlin_STM32H743VI + +# +# BigTreeTech STM32H723Vx ARM Cortex-M7 Common +# +[STM32H723Vx_btt] extends = stm32_variant platform = ststm32@15.4.1 platform_packages = framework-arduinoststm32@~4.20200.220530 -board = marlin_STM32H723Vx board_build.offset = 0x20000 board_upload.offset_address = 0x08020000 build_flags = ${stm32_variant.build_flags} - -DPIN_SERIAL1_RX=PA_10 -DPIN_SERIAL1_TX=PA_9 - -DPIN_SERIAL2_RX=PD_6 -DPIN_SERIAL2_TX=PD_5 - -DPIN_SERIAL3_RX=PD_9 -DPIN_SERIAL3_TX=PD_8 - -DPIN_SERIAL4_RX=PA_1 -DPIN_SERIAL4_TX=PA_0 - -DPIN_SERIAL7_RX=PE_7 -DPIN_SERIAL7_TX=PE_8 + -DPIN_SERIAL1_TX=PA_9 -DPIN_SERIAL1_RX=PA_10 + -DPIN_SERIAL2_TX=PD_5 -DPIN_SERIAL2_RX=PD_6 + -DPIN_SERIAL3_TX=PD_8 -DPIN_SERIAL3_RX=PD_9 + -DPIN_SERIAL4_TX=PA_0 -DPIN_SERIAL4_RX=PA_1 + -DPIN_SERIAL7_TX=PE_8 -DPIN_SERIAL7_RX=PE_7 -DSERIAL_RX_BUFFER_SIZE=1024 -DSERIAL_TX_BUFFER_SIZE=1024 -DTIMER_SERVO=TIM5 -DTIMER_TONE=TIM2 -DSTEP_TIMER_IRQ_PRIO=0 @@ -88,21 +93,27 @@ upload_protocol = cmsis-dap debug_tool = cmsis-dap # -# BigTreeTech Octopus Pro V1.0 / Octopus Max EZ V1.0 (STM32H723ZET6 ARM Cortex-M7) +# BigTreeTech SKR V3.0 / SKR V3.0 EZ (STM32H723VGT6 ARM Cortex-M7) # -[env:STM32H723Zx_btt] +[env:STM32H723VG_btt] +extends = STM32H723Vx_btt +board = marlin_STM32H723VG + +# +# BigTreeTech STM32H723Zx ARM Cortex-M7 Common +# +[STM32H723Zx_btt] extends = stm32_variant platform = ststm32@15.4.1 platform_packages = framework-arduinoststm32@~4.20200.220530 -board = marlin_STM32H723Zx board_build.offset = 0x20000 board_upload.offset_address = 0x08020000 build_flags = ${stm32_variant.build_flags} - -DPIN_SERIAL1_RX=PA_10 -DPIN_SERIAL1_TX=PA_9 - -DPIN_SERIAL2_RX=PD_6 -DPIN_SERIAL2_TX=PD_5 - -DPIN_SERIAL3_RX=PD_9 -DPIN_SERIAL3_TX=PD_8 - -DPIN_SERIAL4_RX=PA_1 -DPIN_SERIAL4_TX=PA_0 - -DPIN_SERIAL7_RX=PE_7 -DPIN_SERIAL7_TX=PE_8 + -DPIN_SERIAL1_TX=PA_9 -DPIN_SERIAL1_RX=PA_10 + -DPIN_SERIAL2_TX=PD_5 -DPIN_SERIAL2_RX=PD_6 + -DPIN_SERIAL3_TX=PD_8 -DPIN_SERIAL3_RX=PD_9 + -DPIN_SERIAL4_TX=PA_0 -DPIN_SERIAL4_RX=PA_1 + -DPIN_SERIAL7_TX=PE_8 -DPIN_SERIAL7_RX=PE_7 -DSERIAL_RX_BUFFER_SIZE=1024 -DSERIAL_TX_BUFFER_SIZE=1024 -DTIMER_SERVO=TIM5 -DTIMER_TONE=TIM2 -DSTEP_TIMER_IRQ_PRIO=0 @@ -112,3 +123,10 @@ build_flags = ${stm32_variant.build_flags} -UI2C5_BASE upload_protocol = cmsis-dap debug_tool = cmsis-dap + +# +# BigTreeTech Octopus Pro V1.0.1/1.1 / Octopus Max EZ V1.0 (STM32H723ZET6 ARM Cortex-M7) +# +[env:STM32H723ZE_btt] +extends = STM32H723Zx_btt +board = marlin_STM32H723ZE diff --git a/platformio.ini b/platformio.ini index 8b79ea2537da..e3bdb6f58676 100644 --- a/platformio.ini +++ b/platformio.ini @@ -52,217 +52,79 @@ extra_scripts = pre:buildroot/share/PlatformIO/scripts/preflight-checks.py post:buildroot/share/PlatformIO/scripts/common-dependencies-post.py lib_deps = -default_src_filter = + - - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +default_src_filter = + - - + ; LCDs and Controllers + - - - - - + - - - - - - - - - - - - - - - - - - - + ; Marlin HAL + - + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + ; Features and G-Codes + - + - + - + - + - + - + - + - + - + - + - - - - - - - - - - - - - - - - - - - - - - - + - + - + ; Library Code + - - - - - - - - - - - - - - - - - - - - - - - - - - - - + - + ; Modules + - + - + ; Media Support + - + ; + ; Minimal Requirements + ; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + # # Default values apply to all 'env:' prefixed environments